动作通信
机器人导航到某个目标点,此过程需要一个节点A发布目标信息,然后一个节点B接收到请求并控制移动,最终响应目标达成状态信息。
乍一看,这好像是服务通信实现,因为需求中要A发送目标,B执行并返回结果,这是一个典型的基于请求响应的应答模式,不过,如果只是使用基本的服务通信实现,存在一个问题:导航是一个过程,是耗时操作,如果使用服务通信,那么只有在导航结束时,才会产生响应结果,而在导航过程中,节点A是不会获取到任何反馈的,从而可能出现程序"假死"的现象,过程的不可控意味着不良的用户体验,以及逻辑处理的缺陷(比如:导航中止的需求无法实现)。更合理的方案应该是:导航过程中,可以连续反馈当前机器人状态信息,当导航终止时,再返回最终的执行结果。在ROS中,该实现策略称之为:action 通信。
概念
动作通信适用于长时间运行的任务。就结构而言动作通信由目标、反馈和结果三部分组成;就功能而言动作通信类似于服务通信,动作客户端可以发送请求到动作服务端,并接收动作服务端响应的最终结果,不过动作通信可以在请求响应过程中获取连续反馈,并且也可以向动作服务端发送任务取消请求;就底层实现而言动作通信是建立在话题通信和服务通信之上的,目标发送实现是对服务通信的封装,结果的获取也是对服务通信的封装,而连续反馈则是对话题通信的封装。
案例
终端下进入工作空间的src目录,调用如下两条命令分别创建C++功能包和Python功能包。
ros2 pkg create cpp03_action --build-type ament_cmake --dependencies rclcpp rclcpp_action base_interfaces_demo --node-name demo01_action_server
ros2 pkg create py03_action --build-type ament_python --dependencies rclpy base_interfaces_demo --node-name demo01_action_server_py
定义动作接口消息与话题:
创建.action文件
编辑配置文件
编译测试
创建action文件
功能包base_interfaces_demo下新建action文件夹,action文件夹下新建Progress.action文件(首字母大写),内容:
int64 num
---
int64 sum
---
float64 progress
编辑配置文件
1.package.xml
如果单独构建action功能包,需要在package.xml中需要添加一些依赖包,具体内容如下:
<buildtool_depend>rosidl_default_generators</buildtool_depend>
<depend>action_msgs</depend>
<member_of_group>rosidl_interface_packages</member_of_group>
当前使用的是 base_interfaces_demo 功能包,已经为 msg 、srv 文件添加过了一些依赖,所以 package.xml 中添加如下内容即可:
<buildtool_depend>rosidl_default_generators</buildtool_depend>
<depend>action_msgs</depend>
2.CMakeLists.txt
如果是新建的功能包,与之前定义msg、srv文件同理,为了将.action
文件转换成对应的C++和Python代码,还需要在CMakeLists.txt 中添加如下配置:
find_package(rosidl_default_generators REQUIRED)rosidl_generate_interfaces(${PROJECT_NAME}"action/Progress.action"
)
不过,我们当前使用的base_interfaces_demo包,那么只需要修改rosidl_generate_interfaces函数即可,修改后的内容如下:
rosidl_generate_interfaces(${PROJECT_NAME}"msg/Student.msg""srv/AddInts.srv""action/Progress.action"
)
查看是否构建完成
终端输入,查看是否为Progress.action的内容
colcon build --packages-select base_interfaces_demo
. install/setup.bash
ros2 interface show base_interfaces_demo/action/Progress
C++实现
服务端
/*需求:编写动作服务端,解析客户端提交的数据,遍历数据累加求和,结果返回客户端,请求响应过程中连续反馈步骤:1.包含头文件;2.初始化 ROS2 客户端;3.定义节点类;3-1.创建动作服务端;3-2.处理请求数据;3-3.处理取消任务请求;3-4.生成连续反馈与最终响应。4.调用spin函数,并传入节点对象指针;5.释放资源。
*/
#include <rclcpp/rclcpp.hpp>
#include "rclcpp_action/rclcpp_action.hpp"
#include "base_interfaces_demo/action/progress.hpp"using std::placeholders::_1;
using std::placeholders::_2;
using base_interfaces_demo::action::Progress;
using GoalHandleProgress = rclcpp_action::ServerGoalHandle<Progress>;// 自定义节点类
class ProgressActionServer : public rclcpp::Node
{
public:ProgressActionServer() : Node("progress_action_server_node_cpp"){RCLCPP_INFO(this->get_logger(), "action服务端创建");// 3-1.创建动作服务端;server_ = rclcpp_action::create_server<Progress>(this, "get_sum",std::bind(&ProgressActionServer::handle_goal, this,_1,_2),std::bind(&ProgressActionServer::handle_cancel, this,_1),std::bind(&ProgressActionServer::handle_accepted, this,_1));/*rclcpp_action::Server<ActionT>::SharedPtrcreate_server<ActionT, NodeT>(NodeT node,const std::string &name,rclcpp_action::Server<ActionT>::GoalCallback handle_goal,rclcpp_action::Server<ActionT>::CancelCallback handle_cancel,rclcpp_action::Server<ActionT>::AcceptedCallback handle_accepted,const rcl_action_server_options_t &options = rcl_action_server_get_default_options(),rclcpp::CallbackGroup::SharedPtr group = nullptr)*/}// 3-2.处理请求数据;// std::function<GoalResponse(const GoalUUID &, std::shared_ptr<const typename ActionT::Goal>)>rclcpp_action::GoalResponse handle_goal(const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const Progress::Goal> goal){(void)uuid;//业务逻辑:判断提交的数据是否大于1,是就接受否则拒绝if(goal->num<=1){RCLCPP_INFO(this->get_logger(),"提交的目标数需要大于1");return rclcpp_action::GoalResponse::REJECT;}RCLCPP_INFO(this->get_logger(),"提交的目标值合法");return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;}// 3-3.处理取消任务请求;// std::function<CancelResponse(std::shared_ptr<ServerGoalHandle<ActionT>>)>;rclcpp_action::CancelResponse handle_cancel(std::shared_ptr<rclcpp_action::ServerGoalHandle<Progress>> goal_handle){(void)goal_handle;// 取消请求不做任何业务逻辑处理// 业务逻辑:直接接受取消请求RCLCPP_INFO(this->get_logger(),"取消请求已收到");return rclcpp_action::CancelResponse::ACCEPT;}// 3-4.生成连续反馈。// std::function<void(std::shared_ptr<ServerGoalHandle<ActionT>>)>;void execute(std::shared_ptr<rclcpp_action::ServerGoalHandle<Progress>> goal_handle){//生成连续反馈返回给客户端// publish_feedback(std::shared_ptr<base_interfaces_demo::action::Progress_Feedback> feedback_msg)// goal_handle->publish_feedback();//先获取目标值,然后遍历累加,每循环一次计算进度并作为连续反馈发布int num=goal_handle->get_goal()->num;int sum=0;auto feedback=std::make_shared<Progress::Feedback>();//设置休眠rclcpp::Rate rate(1);for(int i=0;i<=num;i++){sum+=i;double progress=i/(double)num;//计算进度feedback->progress=progress;//发布goal_handle->publish_feedback(feedback);RCLCPP_INFO(this->get_logger(),"已反馈进度:%.2f",progress);//判断是否被取消if(goal_handle->is_canceling()){RCLCPP_INFO(this->get_logger(),"计算被取消");auto result=std::make_shared<Progress::Result>();result->sum=sum;goal_handle->canceled(result);RCLCPP_INFO(this->get_logger(),"已反馈结果:%d",result->sum);return;}//模拟计算延时rate.sleep();}//生成最终响应结果// succeed(std::shared_ptr<base_interfaces_demo::action::Progress_Result> result_msg)// goal_handle->succeed();if(rclcpp::ok()){auto result=std::make_shared<Progress::Result>();result->sum=sum;goal_handle->succeed(result);RCLCPP_INFO(this->get_logger(),"计算完成,结果:%d",result->sum);}}void handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<Progress>> goal_handle){// 由于执行execute函数可能会阻塞,所以开启子线程处理std::thread(std::bind(&ProgressActionServer::execute,this,goal_handle)).detach();}private: rclcpp_action::Server<Progress>::SharedPtr server_;
};int main(int argc, char const *argv[])
{// 初始化rclcpp::init(argc, argv);// 调用spin,挂起当前rclcpp::spin(std::make_shared<ProgressActionServer>());// 释放rclcpp::shutdown();
}
客户端
/* 需求:客户端,发送一个整型数据到服务端,并处理服务端的连续反馈和最终响应结果步骤:1.包含头文件;2.初始化 ROS2 客户端;3.定义节点类;3-1.创建动作客户端;3-2.发送请求;3-3.处理目标发送后的反馈;3-4.处理连续反馈;3-5.处理最终响应。4.调用spin函数,并传入节点对象指针;5.释放资源。
*/
#include <rclcpp/rclcpp.hpp>
#include "rclcpp_action/rclcpp_action.hpp"
#include "base_interfaces_demo/action/progress.hpp"using base_interfaces_demo::action::Progress;
using namespace std::chrono_literals;
using namespace std::placeholders;
using GoalHandleProgress = rclcpp_action::ClientGoalHandle<Progress>;//自定义节点类
class ProgressActionClient:public rclcpp::Node{
public:ProgressActionClient():Node("progress_action_client_node_cpp"){RCLCPP_INFO(this->get_logger(),"action 客户端创建");// 3-1.创建动作客户端;
/* create_client(NodeT node,const std::string & name,rclcpp::CallbackGroup::SharedPtr group = nullptr,const rcl_action_client_options_t & options = rcl_action_client_get_default_options()) */client_=rclcpp_action::create_client<Progress>(this,"get_sum");}// 3-2.发送请求;void send_goal(int num){//连接服务端if(!client_->wait_for_action_server(10s)){RCLCPP_ERROR(this->get_logger(),"服务端连接失败");rclcpp::shutdown();}RCLCPP_INFO(this->get_logger(),"服务端连接成功");//发送请求/* std::shared_future<rclcpp_action::ClientGoalHandle<base_interfaces_demo::action::Progress>::SharedPtr> async_send_goal(const base_interfaces_demo::action::Progress::Goal &goal, const rclcpp_action::Client<base_interfaces_demo::action::Progress>::SendGoalOptions &options)*/auto goal=Progress::Goal();goal.num=num;RCLCPP_INFO(this->get_logger(),"发送的目标值:%ld",goal.num);rclcpp_action::Client<Progress>::SendGoalOptions options;options.feedback_callback=std::bind(&ProgressActionClient::feedback_callback,this,_1,_2);options.goal_response_callback=std::bind(&ProgressActionClient::goal_response_callback,this,_1);options.result_callback=std::bind(&ProgressActionClient::result_callback,this,_1);auto future=client_->async_send_goal(goal,options);}// 3-3.处理目标发送后的反馈;void goal_response_callback(GoalHandleProgress::SharedPtr goal_handle){if(!goal_handle){//空指针RCLCPP_ERROR(this->get_logger(),"目标被拒绝");}else{RCLCPP_INFO(this->get_logger(),"目标被接受");}}// 3-4.处理连续反馈;/* std::function<void (typename ClientGoalHandle<ActionT>::SharedPtr,const std::shared_ptr<const Feedback>)>; */void feedback_callback(GoalHandleProgress::SharedPtr goal_handle,const std::shared_ptr<const Progress::Feedback> feedback){(void)goal_handle;//未使用double progress=feedback->progress;RCLCPP_INFO(this->get_logger(),"连续反馈:当前进度%.2f%%",progress*100);}// 3-5.处理最终响应。// ResultCallback = std::function<void (const WrappedResult & result)>void result_callback(const GoalHandleProgress::WrappedResult & result){// result.code状态码if (result.code == rclcpp_action::ResultCode::SUCCEEDED) {RCLCPP_INFO(this->get_logger(), "目标成功完成,结果:%ld", result.result->sum);}else if (result.code == rclcpp_action::ResultCode::ABORTED) {RCLCPP_ERROR(this->get_logger(), "目标执行失败");}else if (result.code == rclcpp_action::ResultCode::CANCELED) {RCLCPP_ERROR(this->get_logger(), "目标被取消");}else {RCLCPP_ERROR(this->get_logger(), "未知的结果");}}private:rclcpp_action::Client<Progress>::SharedPtr client_;
};int main(int argc,char const *argv[]){if(argc!=2){RCLCPP_ERROR(rclcpp::get_logger("rclcpp"),"请提交一个整型数据");return 1;}//初始化rclcpp::init(argc,argv);//调用spin,挂起当前auto node=std::make_shared<ProgressActionClient>();node->send_goal(atoi(argv[1]));rclcpp::spin(node);//释放rclcpp::shutdown();
}
编译实现
colcon build --packages-select cpp03_action
. install/setup.bash
ro2 run cpp03_action demo01_action_server. install/setup.bash
ro2 run cpp03_action demo02_action_client
实现流程
客户端 (Client) 服务端 (Server)| ||-------- 1. 启动节点 ------------------------>|| ProgressActionClient | ProgressActionServer| ||<------- 2. 发送请求,等待服务端 ------------|| send_goal| client_->wait_for_action_server() || ||-------- 3. 发送目标 (num=10) -------------->|| async_send_goal(...) || ||<------- 4. handle_goal() -------------------|| | 检查 num > 1?| | 是 → ACCEPT_AND_EXECUTE| ||-------- 5. goal_response_callback() -------|| 目标被接受 || ||<------- 6. handle_accepted() ---------------|| | 启动新线程执行 execute()| ||<------- 7. execute() 开始循环 --------------|| | i=0, sum=0| | progress = 0.0|-------- 8. feedback_callback() <-----------|| 连续反馈: 0.0% || | sleep(1s)| | i=1, sum=1| | progress = 0.1|-------- 9. feedback_callback() <-----------|| 连续反馈: 10.0% || | ...继续...| | i=10, sum=55|--------10. result_callback() <-------------|| 最终结果: 55 || ||-------- 可选:发送取消请求 ----------------->|| async_cancel_goal(...) ||<------- handle_cancel() ---------------------|| | 接受取消|-------- result_callback(code=CANCELED) <----|| 目标被取消 |
通义千问过程讲解:通义 - 你的实用AI助y
python实现
服务端
"""需求:编写动作服务端,解析客户端提交的数据,遍历数据累加求和,结果返回客户端,请求响应过程中连续反馈步骤:1.包含头文件;2.初始化 ROS2 客户端;3.定义节点类;3-1.创建动作服务端对象;3-2.处理提交的目标值(回调函数) 默认实现;3-3.处理取消任务请求(回调函数) 默认实现;3-4.生成连续反馈与最终响应(回调函数)。4.调用spin函数,并传入节点对象指针;5.释放资源。
"""import rclpy
from rclpy.node import Node
from rclpy.action import ActionServer # 可根据需要替换为其他消息类型
from base_interfaces_demo.action import Progress
import time
from rclpy.action import GoalResponse, CancelResponseclass ProgressActionServer(Node):def __init__(self):super().__init__('progress_action_server_node_py')self.get_logger().info('服务端启动:progress_action_server_node_py')# 3-1.创建动作服务端对象;# node: Any,action_type: Any,action_name: Any,execute_callback: Any,self.server = ActionServer(self,Progress,'get_sum',self.execute_callback,goal_callback=self.goal_callback,cancel_callback=self.cancel_callback)# 3-2.处理提交的目标值(回调函数)def goal_callback(self,goal_request):self.get_logger().info("收到的目标值:%d"%goal_request.num)if goal_request.num<=1:self.get_logger().info('拒绝目标值')return GoalResponse.REJECTself.get_logger().info('接受目标值')return GoalResponse.ACCEPT# 3-3.处理取消任务请求(回调函数)def cancel_callback(self,goal_handle):self.get_logger().info('取消请求')return CancelResponse.ACCEPT# 3-4.生成连续反馈与最终响应(回调函数)。def execute_callback(self,goal_handle):# 生成连续反馈# 首先获取目标值,然后遍历累加求和,每累加一次就反馈一次num=goal_handle.request.numsum=0for i in range(1,num+1):if goal_handle.is_cancel_requested:goal_handle.canceled()self.get_logger().info('任务取消,最终结果:%d'%sum)return Progress.Result()sum+=ifeedback=Progress.Feedback()feedback.progress=i/numgoal_handle.publish_feedback(feedback)self.get_logger().info('连续反馈:%.2f'%feedback.progress)time.sleep(1)# 响应最终结果goal_handle.succeed()result=Progress.Result()result.sum=sumself.get_logger().info('最终结果:%d'%result.sum)return resultdef main(args=None):# 2. 初始化ROS2客户端rclpy.init(args=args)# 3. 创建节点对象node = ProgressActionServer()# 4. 调用 spin,传入节点对象rclpy.spin(node)# 5. 释放资源rclpy.shutdown()if __name__ == '__main__':main()
客户端
"""需求:客户端,发送一个整型数据到服务端,并处理服务端的连续反馈和最终响应结果步骤:前提:动态解析传入参数1.包含头文件;2.初始化 ROS2 客户端;3.定义节点类;3-1.创建动作客户端;3-2.发送请求;3-3.处理目标发送后的反馈(回调函数);3-4.处理连续反馈(回调函数);3-5.处理最终响应(回调函数)。4.调用spin函数,并传入节点对象指针;5.释放资源。
"""import rclpy
from rclpy.node import Node
import sys
from rclpy.logging import get_logger
from rclpy.action import ActionClient # 可根据需要替换为其他消息类型
from base_interfaces_demo.action import Progressclass ProgressActionClient(Node):def __init__(self):super().__init__('progress_action_client_node_py')self.get_logger().info('客户端启动:progress_action_client_node_py')# 3-1.创建动作客户端;# node: Any,action_type: Any,action_name: Any,self.client=ActionClient(self,Progress,'get_sum')# 3-2.发送请求;def send_goal(self,num):# 客户端连接服务端self.client.wait_for_server()# 发送请求goal=Progress.Goal()goal.num=numself.future=self.client.send_goal_async(goal,self.feedback_callback)self.future.add_done_callback(self.goal_response_callback)# 3-3.处理目标发送后的反馈(回调函数);def goal_response_callback(self,future):# 获取目标句柄goal_handle=future.result()# 判断目标是否正常接受if not goal_handle.accepted:self.get_logger().info('目标被拒绝')returnself.get_logger().info('目标被接受')# 3-5.处理最终响应(回调函数)self.result_future=goal_handle.get_result_async().add_done_callback(self.get_result_callback)# 3-4.处理连续反馈(回调函数);def feedback_callback(self,feedback_msg):feedback=feedback_msg.feedback.progressself.get_logger().info('收到反馈:%.2f'%feedback)# 3-5.处理最终响应(回调函数)def get_result_callback(self,future):result=future.result().resultself.get_logger().info('最终结果:%d'%result.sum)returndef main(args=None):# 动态解析传入参数if(len(sys.argv)!=2):get_logger('rclpy').info('请传入一个整数参数')return# 2. 初始化ROS2客户端rclpy.init(args=args)# 3. 创建节点对象# node = ProgressActionClient()# 4. 调用 spin,传入节点对象action_client=ProgressActionClient()action_client.send_goal(int(sys.argv[1]))rclpy.spin(action_client)# 5. 释放资源rclpy.shutdown()if __name__ == '__main__':main()
参数服务
导航实现时,会进行路径规划,路径规划主要包含, 全局路径规划和本地路径规划,所谓全局路径规划就是设计一个从出发点到目标点的大致路径,而本地路径规划,则是根据车辆当前路况生成实时的行进路径。两种路径规划实现,都会使用到车辆的尺寸数据——长度、宽度、高度等。那么这些通用数据在程序中应该如何存储、调用呢?
在一个节点下保存车辆尺寸数据,其他节点可以访问该节点并操作这些数据。
概念
参数服务是以共享的方式实现不同节点之间数据交互的一种通信模式。保存参数的节点称之为参数服务端,调用参数的节点称之为参数客户端。参数客户端与参数服务端的交互是基于请求响应的,且参数通信的实现本质上对服务通信的进一步封装。
C++客户端对应的类是rclcpp::Parameter
,Python客户端对应的类是rclpy.Parameter
。
参数API调用
cd到src目录下,新建两个包
ros2 pkg create cpp04_param --build-type ament_cmake --dependencies rclcpp --node-name demo00_param
ros2 pkg create py04_param --build-type ament_python --dependencies rclpy --node-name demo00_param_py
C++
/* 需求:参数API使用步骤:1.包含头文件;2.初始化 ROS2 客户端;3.定义节点类;3-1参数对象创建3-2参数对象解析(获取键、值、值转换字符串)4.调用spin函数,并传入节点对象指针;5.释放资源。
*/
#include <rclcpp/rclcpp.hpp>//自定义节点类
class MyParam:public rclcpp::Node{
public:MyParam():Node("my_param_node_cpp"){RCLCPP_INFO(this->get_logger(),"参数API使用");// 3-1参数对象创建rclcpp::Parameter p1("car_name","tiger");rclcpp::Parameter p2("max_speed",200.05);rclcpp::Parameter p3("wheels",4);// 3-2参数对象解析(获取键、值、值转换字符串)//解析值RCLCPP_INFO(this->get_logger(),"car_name=%s",p1.as_string().c_str());RCLCPP_INFO(this->get_logger(),"max_speed=%.2f",p2.as_double());RCLCPP_INFO(this->get_logger(),"wheels=%ld",p3.as_int());//解析键RCLCPP_INFO(this->get_logger(),"name=%s",p1.get_name().c_str());RCLCPP_INFO(this->get_logger(),"car_name=%s",p1.get_type_name().c_str());RCLCPP_INFO(this->get_logger(),"value2string=%s",p2.value_to_string().c_str());}
};int main(int argc,char const *argv[]){//初始化rclcpp::init(argc,argv);//调用spin,挂起当前rclcpp::spin(std::make_shared<MyParam>());//释放rclcpp::shutdown();
}
python
"""
流程:参数API使用1. 导包2. 初始化ROS2客户端3. 自定义节点类3-1参数对象创建3-2参数对象解析(获取键、值、值转换字符串)4. 调用 spin 函数,传入节点对象5. 资源释放
"""import rclpy
from rclpy.node import Node
from std_msgs.msg import String # 可根据需要替换为其他消息类型class MyParam(Node):def __init__(self):super().__init__('my_prama_node_py')self.get_logger().info('参数API使用_py')# 3-1参数对象创建p1=rclpy.Parameter("car_name",value="奔驰")p2=rclpy.Parameter("car_price",value=100.5)p3=rclpy.Parameter("wheel",value=4)# 3-2参数对象解析(获取键、值、值转换字符串)self.get_logger().info("car_name的值:%s" % p1.value)self.get_logger().info("car_price的值:%s" % p2.value)self.get_logger().info("wheel的值:%s" % p3.value)self.get_logger().info("key=%s"%p1.name)def main(args=None):# 2. 初始化ROS2客户端rclpy.init(args=args)# 3. 创建节点对象node = MyParam()# 4. 调用 spin,传入节点对象rclpy.spin(node)# 5. 释放资源rclpy.shutdown()if __name__ == '__main__':main()
增删改查:
C++
删除参数只能删除set_parameter的参数,declare的参数无法删除
服务端
/* 需求:编写参数服务端,设置并操作参数步骤:1.包含头文件;2.初始化 ROS2 客户端;3.定义节点类;3-1.声明参数;3-2.查询参数;3-3.修改参数;3-4.删除参数。4.调用spin函数,并传入节点对象指针;5.释放资源。
*/
#include <rclcpp/rclcpp.hpp>//自定义节点类
class ParamServer:public rclcpp::Node{
public:// 如果允许删除参数,需要在NodeOptions中设置allow_undeclared_parameters为trueParamServer():Node("param_server_node_cpp",rclcpp::NodeOptions().allow_undeclared_parameters(true)){RCLCPP_INFO(this->get_logger(),"参数服务端节点创建!");}// 3-1.声明参数;void declare_param(){RCLCPP_INFO(this->get_logger(),"声明参数!");this->declare_parameter("car_name","奔驰GLK");this->declare_parameter("car_price",30.5);this->declare_parameter("wheels",5);this->set_parameter(rclcpp::Parameter("height",1.8));}// 3-2.查询参数;void get_param(){RCLCPP_INFO(this->get_logger(),"查询参数!");//获取指定参数auto car=this->get_parameter("car_name");RCLCPP_INFO(this->get_logger(),"key=%s,val=%s",car.get_name().c_str(),car.as_string().c_str());//获取一些参数auto params=this->get_parameters({"car_name","wheels"});for (auto &¶m:params){RCLCPP_INFO(this->get_logger(),"key=%s,val=%s",param.get_name().c_str(),param.value_to_string().c_str());}//判断是否包含参数auto flag=this->has_parameter("car_price");auto flag2=this->has_parameter("car_type");RCLCPP_INFO(this->get_logger(),"是否包含car_price参数?%d",flag);RCLCPP_INFO(this->get_logger(),"是否包含car_type参数?%d",flag2);}// 3-3.修改参数;void update_param(){RCLCPP_INFO(this->get_logger(),"修改参数!");this->set_parameter(rclcpp::Parameter("car_name","宝马X6"));RCLCPP_INFO(this->get_logger(),"修改后car_name=%s",this->get_parameter("car_name").as_string().c_str()); }// 3-4.删除参数。//declare的参数无法删除,只能删除set_parameter的参数void delete_param(){RCLCPP_INFO(this->get_logger(),"删除参数!");//declare的参数无法删除// this->undeclare_parameter("wheels");// RCLCPP_INFO(this->get_logger(),"删除后是否包含wheels参数?%d",this->has_parameter("wheels"));this->undeclare_parameter("height");RCLCPP_INFO(this->get_logger(),"删除后是否包含height参数?%d",this->has_parameter("height"));}
};int main(int argc,char const *argv[]){//初始化rclcpp::init(argc,argv);//调用spin,挂起当前auto node=std::make_shared<ParamServer>();node->declare_param();node->get_param();node->update_param();node->delete_param();rclcpp::spin(node);//释放rclcpp::shutdown();
}
客户端
当添加服务端不存在的参数时需要rclcpp::NodeOptions().allow_undeclared_parameters(true)
/*需求:编写参数客户端,获取或修改服务端参数。步骤:1.包含头文件;2.初始化 ROS2 客户端;3.定义节点类;3-1.创建参数服务端对象3-2.连接服务端3-3.查询参数;3-4.修改参数;4.调用spin函数,并传入节点对象指针;5.释放资源。
*/
#include <rclcpp/rclcpp.hpp>using namespace std::chrono_literals;
// 自定义节点类
class ParamClient : public rclcpp::Node
{
public:ParamClient() : Node("param_client_node_cpp",rclcpp::NodeOptions().allow_undeclared_parameters(true)){RCLCPP_INFO(this->get_logger(), "参数客户端节点创建!");// 3-1.创建参数服务端对象//参数一:当前对象依赖节点指针//参数二:服务端节点名称,// 问:没有话题,通过节点名称找到服务端:// 答:1.参数服务端启动后底层封装了多个服务通信的服务端// 2.每个服务器话题都是采用 /服务端节点名称/服务名// 3.参数客户端创建后也会封装多个服务通信的客户端// 4.这些客户端和服务端相呼应,也要使用相同的话题名称,因此客户端创建时要使用服务端节点名称param_client_=std::make_shared<rclcpp::SyncParametersClient>(this,"param_server_node_cpp");}// 3-2.连接服务端bool connect_server(){while(!param_client_->wait_for_service(1s)){if(!rclcpp::ok()){//如果程序被终止RCLCPP_ERROR(this->get_logger(),"程序被终止!");return false;}RCLCPP_INFO(this->get_logger(),"等待服务端连接!");}return true;}// 3-3.查询参数;void get_param(){RCLCPP_INFO(this->get_logger(),"-----------查询参数-----------");//获取某个参数std::string car_name=param_client_->get_parameter<std::string>("car_name");double car_price=param_client_->get_parameter<double>("car_price");RCLCPP_INFO(this->get_logger(),"car_name=%s",car_name.c_str());RCLCPP_INFO(this->get_logger(),"car_price=%.2f",car_price);//获取多个参数auto params=param_client_->get_parameters({"car_name","car_price","wheels"});for (auto &¶m:params){RCLCPP_INFO(this->get_logger(),"key=%s,val=%s",param.get_name().c_str(),param.value_to_string().c_str());}//是否包含某个参数auto flag=param_client_->has_parameter("car_type");RCLCPP_INFO(this->get_logger(),"是否包含car_type参数?%d",flag);}// 3-4.修改参数;void update_param(){RCLCPP_INFO(this->get_logger(),"-----------修改参数-----------");//修改某个参数param_client_->set_parameters({rclcpp::Parameter("car_name","奥迪Q5")});RCLCPP_INFO(this->get_logger(),"修改后car_name=%s",param_client_->get_parameter<std::string>("car_name").c_str());//修改多个参数param_client_->set_parameters({rclcpp::Parameter("car_name","东风"),rclcpp::Parameter("car_price",45.5),rclcpp::Parameter("height",1.7)});auto params=param_client_->get_parameters({"car_name","car_price","height"});for (auto &¶m:params){RCLCPP_INFO(this->get_logger(),"key=%s,val=%s",param.get_name().c_str(),param.value_to_string().c_str());}}private:rclcpp::SyncParametersClient::SharedPtr param_client_;
};int main(int argc, char const *argv[])
{// 初始化rclcpp::init(argc, argv);auto client = std::make_shared<ParamClient>();bool flag=client->connect_server();if(!flag){RCLCPP_ERROR(client->get_logger(),"连接服务端失败!");return -1;}client->get_param();client->update_param();// 调用spin,挂起当前// rclcpp::spin(client);// 释放rclcpp::shutdown();
}
python
如果要允许删除参数,需要将 allow_undeclared_parameters设置为True
"""
编写参数服务端,设置并操作参数
流程:1. 导包2. 初始化ROS2客户端3. 自定义节点类3-1.声明参数;3-2.查询参数;3-3.修改参数;3-4.删除参数。4. 调用 spin 函数,传入节点对象5. 资源释放
"""import rclpy
from rclpy.node import Nodeclass ParamServer(Node):def __init__(self):# 如果要允许删除参数,需要将 allow_undeclared_parameters # 和 automatically_declare_parameters_from_overrides 都设置为 Truesuper().__init__('param_server_node_py',allow_undeclared_parameters=True, automatically_declare_parameters_from_overrides=True)self.get_logger().info('服务端启动param_server_node_py')# 3-1.声明参数;def declare_param(self):self.get_logger().info("声明参数")self.declare_parameter("car_name","BYD")self.declare_parameter("max_speed",200)self.declare_parameter("car_price",19.8)self.set_parameters([rclpy.Parameter("haha",value="xixi")])# 3-2.查询参数;def get_param(self):self.get_logger().info("查询参数")car_name=self.get_parameter("car_name")self.get_logger().info("car_name=%s"%car_name.value)params=self.get_parameters(["max_speed","car_price"])for param in params:self.get_logger().info("max_speed=%s,car_price=%s"%(param.name,param.value))car_type=self.has_parameter("car_type")self.get_logger().info("car_type=%s"%car_type)# 3-3.修改参数;def update_param(self):self.get_logger().info("修改参数")self.set_parameters([rclpy.Parameter('car_name',value="BYD秦")])car_name=self.get_parameter("car_name")self.get_logger().info("%s=%s"%(car_name.name,car_name.value))# 3-4.删除参数。def delete_param(self):self.get_logger().info("删除参数")self.undeclare_parameter("car_name")self.get_logger().info("删除car_name %s"%self.has_parameter("car_name"))def main(args=None):# 2. 初始化ROS2客户端rclpy.init(args=args)# 3. 创建节点对象node = ParamServer()node.declare_param()node.get_param()node.update_param()node.delete_param()# 4. 调用 spin,传入节点对象rclpy.spin(node)# 5. 释放资源rclpy.shutdown()if __name__ == '__main__':main()
ROS2的Python客户端暂时没有提供参数客户端专用的API,但是参数服务的底层是基于服务通信的,所以可以通过服务通信操作参数服务端的参数。