ros2-communication
2025-09-20 22:21:44

接口

接口:通信时使用的数据载体(特定的格式),由接口文件定义

  1. msg文件:用于话题通信,
  2. srv文件:用于服务通信
  3. action文件:用于动作通信

参数通信不使用,操作参数对象

interface

话题通信:

基于发布订阅模式
除了一个节点发布,一个节点接受的形式外,ROS2话题通信其实还可以是1对n, n对1, n对n的,1对n


发布者:

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
#include <rclcpp/rclcpp.hpp>
#include "std_msgs/msg/string.hpp"

using namespace std::chrono_literals;//1s 代表一秒 std::chrono::seconds(1)

class Talker :public rclcpp::Node{
public:
//将节点命名为talker,初始化count
Talker() :Node("talker"),count(0)){
//打印日志,说明节点被创建
RCLCPP_INFO(this->get_logger(),"a talker created");
//创建一个发布者 话题为chat 队列长为10
publisher_ = this->create_publisher<std_msgs::msg::String>("chat",10);
//创建一个每隔1秒触发一次的定时器,并将定时器的回调函数设置为当前对象的on_timer成员函数
timer_ = this->create_wall_timer(1s,std::bind(&Talker::on_timer,this));
}

private:
//创建一个定时器的指针
rclcpp::TimerBase::SharedPtr timer_ ;

//创建一个发布string类型数据的成员指针
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;

//无符号长整型
size_t count;

void on_timer(){
//创建一个String类的实例
//局部变量!!!!每次创建一个新的,函数结束后销毁,不会资源浪费
//也可以在函数外部预定义
auto message = std_msgs::msg::String();
//to_string 转化成字符串
message.data = "hello world!" + std::to_string(count++);
//
RCLCPP_INFO(this->get_logger(),"发布者发布消息:%s",message.data.c_str());
//publish:这是rclcpp::Publisher类的一个成员函数,用于发布消息。
//这个函数接受一个消息对象作为参数,并将其发送到指定的主题上。
publisher_->publish(message);

}
};

int main(int argc, char ** argv)
{
//初始化rcl客户端
rclcpp::init(argc,argv);

//回旋,一直执行回调函数,直到节点被关闭
//std::make_shared<T>() 是一个模板函数,用于创建一个std::shared_ptr<T>对象。它不仅创建了一个共享指针,还同时创建了一个T类型的对象实例。
rclcpp::spin(std::make_shared<Talker>());

//释放资源
rclcpp::shutdown();
return 0;
}

订阅方

tpic-subscriber

回调函数传入参数类型不能是std_msgs::msg::String的引用
create_subscription方法传递的是消息的共享指针,而不是消息的引用。正确的参数类型应该是const std_msgs::msg::String::SharedPtr

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/string.hpp>

class Listener : public rclcpp::Node{
public:
Listener() : Node("listener_node_cpp"){
RCLCPP_INFO(this->get_logger(),"订阅者已创建");
//接收到信息就执行回调函数
//create_subscription函数的作用是创建一个订阅者(subscriber),该订阅者会监听指定主题(topic)上的消息。
//当有消息发布到该主题时,create_subscription会将接收到的消息传递给指定的回调函数(callback function)。
subscription_ = this->create_subscription<std_msgs::msg::String>("chat",10,std::bind(&Listener::do_cb,this,std::placeholders::_1));
}
private:
//注意传入消息类型
void do_cb(const std_msgs::msg::String::SharedPtr message){
RCLCPP_INFO(this->get_logger(),"订阅到的消息是:%s",message->data.c_str());
}

rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
};

int main(int argc, char** argv){
rclcpp::init(argc,argv);
rclcpp::spin(std::make_shared<Listener>());
rclcpp::shutdown();
return 0;
}

生成代码片段
左下角设置——代码片段——cpp


自定义接口文件——编译前保存!!!!

文件名首字母大写

xml文件配置

1
2
3
4
5
6
7
8
<!-- 编译依赖-->
<build_depend></build_depend>

<!--执行依赖 -->
<exec_depend></exec_depend>

<!--声明当前包所属功能包组 -->
<member_of_group></member_of_group>

ros2 pkg list | grep -i NAME 筛选出来,不用记


CMakeLists.txt

1
2
3
4
5
6
find_package(rosidl_default_generators REQUIRED)

rosidl_generate_interfaces(
${PROJECT_NAME}
"msg/Student.msg"
)

使用自定义接口文件要包含路径

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
#include <rclcpp/rclcpp.hpp>
#include <base_interfaces_demo/msg/student.hpp>

using namespace std::chrono_literals;//1s 代表一秒 std::chrono::seconds(1)
using base_interfaces_demo::msg::Student;


class TalkerStu :public rclcpp::Node{
public:
TalkerStu() :Node("talker_stu"){
publisher_ = this->create_publisher<Student>("Student",10);
timer_ = this->create_wall_timer(1s,std::bind(&TalkerStu::callback,this));
}
private:
rclcpp::Publisher<Student>::SharedPtr publisher_;
rclcpp::TimerBase::SharedPtr timer_;
Student stu;

void callback(){
stu.name = "lihua";
stu.age = 12;
stu.height = 180.0;

publisher_->publish(stu);
RCLCPP_INFO(this->get_logger(),"发布消息:%s,%d,%lf",stu.name.c_str(),stu.age,stu.height);
}
};

int main(int argc,char **argv){
rclcpp::init(argc,argv);
rclcpp::spin(std::make_shared<TalkerStu>());
rclcpp::shutdown();
return 0;
}
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
#include <rclcpp/rclcpp.hpp>
#include <base_interfaces_demo/msg/student.hpp>

using base_interfaces_demo::msg::Student;
using namespace std::chrono_literals;

class ListenerStu :public rclcpp::Node{
public:
ListenerStu() :Node("listener_stu"){
RCLCPP_INFO(this->get_logger(),"订阅者已创建");
subscription_ = this->create_subscription<Student>("Student",10,std::bind(&ListenerStu::callback,this,std::placeholders::_1));

}
private:
rclcpp::Subscription<Student>::SharedPtr subscription_;

void callback(const Student::SharedPtr message){
RCLCPP_INFO(this->get_logger(),"订阅者已接收:%s,%d,%lf",message->name.c_str(),message->age,message->height);
}

};

int main(int argc,char **argv){
rclcpp::init(argc,argv);


rclcpp::shutdown();
return 0;
}

服务通信

一对多,一个服务端,多个客户端

自定义接口文件

1
2
3
请求数据  
---
响应数据

在之前的基础上,修改CMakeLists.txt ——rosidl_generate_interfaces即可

服务端

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
#include <rclcpp/rclcpp.hpp>
#include <base_interfaces_demo/srv/addints.hpp>

using base_interfaces_demo::srv::Addints;
using std::placeholders::_1;
using std::placeholders::_2;

class AddIntServer :public rclcpp::Node{
public:
AddIntServer() :Node("add_int_server"){
RCLCPP_INFO(this->get_logger(),"服务端节点创建成功");
service_ = this->create_service<Addints>("add_ints",std::bind(&AddIntServer::sum,this,_1,_2));
}
private:
rclcpp::Service<Addints>::SharedPtr service_;
void sum(const Addints::Request::SharedPtr req,const Addints::Response::SharedPtr res){
res->sum = req->num1 + req->num2;
RCLCPP_INFO(this->get_logger(),"%d + %d = %d",req->num1,req->num2,res->sum);
}

};

int main(int argc,char **argv){
rclcpp::init(argc,argv);

rclcpp::spin(std::make_shared<AddIntServer>());
rclcpp::shutdown();
return 0;
}

测试:
ros2 service call /add_ints base_interfaces_demo/srv/Addints “{'num1':10,'num2':30}"

rclcpp::ok();
rclcpp::get_logger(); 不依赖于context


客户端

main函数中需要判断提交参数是否正确
自定义节点类中要包括 判断是否连接到服务端

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
#include <rclcpp/rclcpp.hpp>
#include <base_interfaces_demo/srv/addints.hpp>

using base_interfaces_demo::srv::Addints;
using namespace std::chrono_literals;

class AddIntClient :public rclcpp::Node {
public:
AddIntClient() :Node("add_int_client"){
RCLCPP_INFO(this->get_logger(),"客户端节点创建");
client_ = this->create_client<Addints>("add_ints");
}
//连接服务器
bool connect_server(){
//以1s为超时时间,连接不上,一直连接
while(!client_ -> wait_for_service(1s)){
//rclcpp::ok()函数来检查ROS 2节点是否仍在运行
//如果节点被请求停止(例如,通过按下Ctrl+C),rclcpp::ok()会返回false
if(!rclcpp::ok()){
RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"强制退出");
return false;
}
RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"服务器连接中");
}
return true;
}
//发送请求函数
//参数两个整形数据 返回服务器处理后的结果

rclcpp::Client<Addints>::SharedFuture send_request(int num1,int num2){
auto request = std::make_shared<Addints::Request>();
request->num1 = num1;
request->num2 = num2;
//rclcpp::Client<base_interfaces_demo::srv::Addints>::SharedFuture
//async_send_request(std::shared_ptr<base_interfaces_demo::srv::Addints_Request> request)

return client_->async_send_request(request);
}
private:
rclcpp::Client<Addints>::SharedPtr client_;
};

int main(int argc,char **argv){
if(argc != 3){
RCLCPP_ERROR(rclcpp::get_logger("rclcpp"),"请提交两个整型数据");
return 1;
}


rclcpp::init(argc,argv);

auto client = std::make_shared<AddIntClient>();

bool flag = client->connect_server();
//判断是否链接上服务器
if(!flag){
RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"服务器连接失败");
return 0;
}
//调用请求提交函数,接收并处理响应结果
auto future = client->send_request(atoi(argv[1]),atoi(argv[2]));

//处理响应
if(rclcpp::spin_until_future_complete(client,future) == rclcpp::FutureReturnCode::SUCCESS){
RCLCPP_INFO(client->get_logger(),"响应成功!sum = %d",future.get()->sum);


}else{
RCLCPP_INFO(client->get_logger(),"sd");
}

rclcpp::shutdown();
return 0;
}

动作通信

自定义接口文件

1
2
3
4
5
请求数据  
---
响应数据
---
反馈数据

xml:

1
2
3
<!-- action补充-->
<buildtool_depend>rosidl_default_generators</buildtool_depend>
<depend>action_msgs</depend>

CMakeLists.txt补充rosidl_generate_interfaces

服务端

ros2 action send_goal /get_sum base_interfaces_demo/action/Progress -f "{'num':10}"

rclcpp::Rate 的构造函数接受一个频率值(单位为 Hz),表示每秒执行的次数。例如:

1
rclcpp::Rate rate(1.0);  // 每秒执行 1 次,即每秒运行一次循环

rate.sleep() 方法来暂停代码的执行,直到下一次循环的时间点。如果当前循环提前完成,rate.sleep() 会阻塞当前线程,直到达到预期的频率。

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_action/rclcpp_action.hpp>
#include <base_interfaces_demo/action/progress.hpp>

using base_interfaces_demo::action::Progress;
using std::placeholders::_1;
using std::placeholders::_2;

class ActionService :public rclcpp::Node{
public:
ActionService() :Node("action_service"){
RCLCPP_INFO(this->get_logger(),"服务器已创建!");

//rclcpp_action::Server<ActionT>::SharedPtr
//create_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)
//All provided callback functions must be non-blocking.
server_ = rclcpp_action::create_server<Progress>(
this,
"get_sum",
std::bind(&ActionService::handle_goal,this,_1,_2),
std::bind(&ActionService::handle_cancel,this,_1),
std::bind(&ActionService::handle_accepted,this,_1)
);
}

private:
rclcpp_action::Server<Progress>::SharedPtr server_;
//处理提交的目标值,注意参数
rclcpp_action::GoalResponse handle_goal(const rclcpp_action::GoalUUID& uuid,std::shared_ptr<const Progress::Goal> goal){
//判断提交的数字是否大于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;
}

//处理取消请求
//客户端可发送取消请求
rclcpp_action::CancelResponse handle_cancel(std::shared_ptr<rclcpp_action::ServerGoalHandle<Progress>> goal_handle){
RCLCPP_INFO(this->get_logger(),"任务已取消");
return rclcpp_action::CancelResponse::ACCEPT;
}

//生成连续反馈和最终响应
void execute(std::shared_ptr<rclcpp_action::ServerGoalHandle<Progress>> goal_handle){
//生成连续反馈给客户端 goal_handle->publish_feedback()
//void publish_feedback(std::shared_ptr<base_interfaces_demo::action::Progress_Feedback> feedback_msg)
//首先获取目标值,遍历然后累加,每循环一次计算进度,作为连续反馈发布
int num = goal_handle->get_goal()->num;
int sum=0;
double progress;
auto feedback = std::make_shared<Progress::Feedback>();
auto result = std::make_shared<Progress::Result>();

//设置休眠,1s一次
rclcpp::Rate rate(1.0);
for(int i = 1;i<=num;i++){
sum+=i;
progress = i / (double)num;
feedback->progress = progress;
goal_handle->publish_feedback(feedback);
RCLCPP_INFO(this->get_logger(),"连续反馈中,进度:%.2f",progress);

//判断是否接收到了取消请求
//true——接收到取消请求
if(goal_handle->is_canceling()){

//canceled(std::shared_ptr<base_interfaces_demo::action::Progress_Result> result_msg)
//取消时发送最终结果
result->sum = sum;
goal_handle->canceled(result);
RCLCPP_INFO(this->get_logger(),"反馈取消,结果:%d",sum);

return ;
}
rate.sleep();
}

//生成最终响应结果 goal_handle->succeed()
//void succeed(std::shared_ptr<base_interfaces_demo::action::Progress_Result> result_msg)
if(rclcpp::ok()){
result->sum = sum;
goal_handle->succeed(result);
RCLCPP_INFO(this->get_logger(),"最终响应结果:%d",sum);
}
}
void handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<Progress>> goal_handle){
//新建子线程处理耗时的主逻辑实现
std::thread(std::bind(&ActionService::execute,this,goal_handle)).detach();
}
};

int main(int argc,char **argv){
rclcpp::init(argc,argv);
rclcpp::spin(std::make_shared<ActionService>());

rclcpp::shutdown();
return 0;
}

客户端

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
#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 std::placeholders::_1;
using std::placeholders::_2;

class ActionClient :public rclcpp::Node{
public:
ActionClient() :Node("action_client"){
RCLCPP_INFO(this->get_logger(),"Action 客户端已创建");
//rclcpp::CallbackGroup::SharedPtr group = nullptr)
client_ = rclcpp_action::create_client<Progress>(this,"get_sum");
}

void send(int num){
//1.连接到服务器
if(!client_->wait_for_action_server(10s)){
RCLCPP_ERROR(this->get_logger(),"服务器连接失败!");
return ;
}

//2.发送请求

auto goal = Progress::Goal();
auto options = rclcpp_action::Client<Progress>::SendGoalOptions();

goal.num = num;

options.feedback_callback = std::bind(&ActionClient::feedback_callback,this,_1,_2);
options.goal_response_callback = std::bind(&ActionClient::goal_response_callback,this,_1);
options.result_callback = std::bind(&ActionClient::result_callback,this,_1);

auto future = client_->async_send_goal(goal,options);

}

void feedback_callback(rclcpp_action::ClientGoalHandle<Progress>::SharedPtr goal_handle,const std::shared_ptr<const Progress::Feedback> feedback){
double progress = feedback->progress;
RCLCPP_INFO(this->get_logger(),"进度:%lf",progress);
}

//处理关于目标值的服务端响应
void goal_response_callback(std::shared_future<rclcpp_action::ClientGoalHandle<Progress>::SharedPtr> goal_handle){
//响应成功返回指针,注意!!!
if(!goal_handle.get()){
RCLCPP_INFO(this->get_logger(),"请求被拒绝");
}else{
RCLCPP_INFO(this->get_logger(),"请求成功");
}
}

void result_callback(const rclcpp_action::ClientGoalHandle<Progress>::WrappedResult &result){
//result.code 状态码判断最终结果状态 状态玛封装在rclcpp_action::ResultCode::
if(result.code == rclcpp_action::ResultCode::SUCCEEDED){
RCLCPP_INFO(this->get_logger(),"成功!,结果:%d",result.result->sum);
}else{
RCLCPP_ERROR(this->get_logger(),"失败!");
}
}

private:
rclcpp_action::Client<Progress>::SharedPtr client_;

};

int main(int argc,char **argv){
if(argc !=2 ){
RCLCPP_ERROR(rclcpp::get_logger("rclcpp"),"请提交一个整型数据!");
return 1;
}

rclcpp::init(argc,argv);
auto node = std::make_shared<ActionClient>();

node->send(atoi(argv[1]));

rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}

参数通信

parameter-type

param-example

ros2 param list
查询参数
ros2 param get my_server wheels
查询参数值

服务端

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
#include <rclcpp/rclcpp.hpp>

class MyServer :public rclcpp::Node{
public:
//如果允许删除参数,需要通过NodeOptions配置
MyServer() :Node("my_server",rclcpp::NodeOptions().allow_undeclared_parameters(true)){

RCLCPP_INFO(this->get_logger(),"参数服务器已建立");
}

void declare(){
RCLCPP_INFO(this->get_logger(),"------------增-----------");
this->declare_parameter("car_type","tiger");
this->declare_parameter("width",1.5);
this->declare_parameter("wheels",5);

//set也可以,但必须rclcpp::NodeOptions().allow_undeclared_parameters(true)
this->set_parameter(rclcpp::Parameter("height",1.8));
}

void get(){
RCLCPP_INFO(this->get_logger(),"------------查-----------");
//指定
auto car = this->get_parameter("car_type");
RCLCPP_INFO(this->get_logger(),"key = %s , value = %s",car.get_name().c_str(),car.as_string().c_str());
//一些
auto params = this->get_parameters({"car_type","width","wheels"});
for(rclcpp::Parameter n : params){
RCLCPP_INFO(this->get_logger(),"key = %s , value = %s",n.get_name().c_str(),n.value_to_string().c_str());

//判断是否含有
RCLCPP_INFO(this->get_logger(),"是否包含%s? %d",n.get_name().c_str(),this->has_parameter(n.get_name()));
}
}
void update(){
RCLCPP_INFO(this->get_logger(),"------------改-----------");

this->set_parameter(rclcpp::Parameter("width",1.4));
RCLCPP_INFO(this->get_logger(),"width = %lf",this->get_parameter("width").as_double());

}
void del(){
RCLCPP_INFO(this->get_logger(),"------------删-----------");
this->undeclare_parameter("car_type");

RCLCPP_INFO(this->get_logger(),"car_type还存在吗? %d",this->has_parameter("car_type"));
}
private:
};

int main(int argc,char **argv){
rclcpp::init(argc,argv);

auto node = std::make_shared<MyServer>();
node->declare();
node->get();
node->update();
node->del();

rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}

客户端

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
#include <rclcpp/rclcpp.hpp>
#include <vector>

using namespace std::chrono_literals;

class MyClient :public rclcpp::Node{
public:
MyClient() :Node("my_client"){
RCLCPP_INFO(this->get_logger(),"参数客户端已建立");
client_ = std::make_shared<rclcpp::SyncParametersClient>(this,"my_server");

}

bool connect_server(){

while(!client_->wait_for_service(1s)){

if(!rclcpp::ok()){
RCLCPP_INFO(this->get_logger(),"中断!");
return false;
}

RCLCPP_INFO(this->get_logger(),"连接中");
}

return true;
}

void get(){
RCLCPP_INFO(this->get_logger(),"获取");

//获取单个
std::string car_name =client_->get_parameter<std::string>("car_type");
double width = client_->get_parameter<double>("width");
RCLCPP_INFO(this->get_logger(),"car_name:%s",car_name.c_str());
RCLCPP_INFO(this->get_logger(),"width:%lf",width);


//获取多个
auto params = client_->get_parameters({"car_type","width"});
for(rclcpp::Parameter n : params){
RCLCPP_INFO(this->get_logger(),"key = %s , value = %s",n.get_name().c_str(),n.value_to_string().c_str());

}

//判断是否含有_IN
RCLCPP_INFO(this->get_logger(),"car_type? %d",client_->has_parameter("car_type"));
}
void update(){
RCLCPP_INFO(this->get_logger(),"修改");
client_->set_parameters({rclcpp::Parameter("car_type","pig"),
rclcpp::Parameter("length","5.0")});//不存在也可以,但要保证服务端那个参数

RCLCPP_INFO(this->get_logger(),"length? %d",client_->has_parameter("length"));
}
private:
rclcpp::SyncParametersClient::SharedPtr client_;

};

int main(int argc,char **argv){
rclcpp::init(argc,argv);
auto note = std::make_shared<MyClient>();

bool flag = note->connect_server();

if(!flag == true){
return 0;
}
note->get();
note->update();
note->get();
rclcpp::spin(note);
rclcpp::shutdown();
return 0;
}

出现乱码:C语言字符串输出不兼容