本人使用版本为ROS2-dashing版本。
由于学习ROS2时十分匆忙,只把它当成一个通讯工具,所以看官方文档时并没有仔细思考,目的是能用就行,到具体报错时才不得不去看源代码找答案。即便写代码时知道Node,Executor如何定义,但对于这两个东西的内部实现并不了解。直到使用官方文档(service and client)的Client代码抄出了问题…
以下是我浅显的想法,如果有问题欢迎指正。
1.node的构成
rclcpp::Node的成员变量有一些interface,例如
- node_base:可以记录node的基本状态,例如:
- node的name;
- node的call_back_group
- node的associated_with_executor_,即是否与executor绑定,以此确定只跟一个executor有关系
- node_graph
- node_services
- node_topics:显而易见用来创建publisher,subscriber等
2.executor
- 用来在node 调用spin(内部循环)时,执行node内部的callback函数。
- 一个executor可以添加多个node,及为不同的node执行callback函数
- executor分singleThreadExecutor和multiThreadExecutor。即单线程执行和多线程执行。
- singleThreadExecutor添加多个node时,顺序执行call_back
- multiThreadExecutor添加多个node时,多线程执行call_back
- 一个node只能被一个executor添加,
- 在executor.add(node)函数中会检查
- node是否已经被其他executor添加(即查看node.node_base.associated_with_executor_是否为true)
- 或node是否已被此executor添加过
3.出错的程序
3.1 node_main.cpp,正常执行
rclcpp::init(argc, argv);
rclcpp::executors::SingleThreadedExecutor executor;
auto node = std::make_shared<robotis::localization::LocalizationNode>(rclcpp::NodeOptions());
executor.add_node(node);
std::atomic_bool & has_executor = node->get_node_base_interface()->get_associated_with_executor_atomic();
//此时会成功输出,因为上面的executor已成功添加node
if (has_executor.exchange(true)) {
printf("yes yes yes yes yes yes\n");
}
executor.spin();
rclcpp::shutdown();
return EXIT_SUCCESS;
3.2 照抄官方文档中client 的response报错
我的service定义
string data
---
Int32 num
接收到一个随便的std_msgs::msg::Int32数据后调用mySubCallback函数,在其中call service
void mySubCallback(const std_msgs::msg::Int32::SharedPtr msg){
printf("recieve a msg:%d\n",msg->data);
std::string data =std::to_string(pose_msg->data);
auto request = std::make_shared<my_msgs::srv::MyService::Request>();
request->data = data;
while (!my_client_->wait_for_service(std::chrono::seconds(1))) {
if (!rclcpp::ok()) {
RCLCPP_ERROR(nh_->get_logger(), "Interrupted while waiting for the service. Exiting.");
return;
}
RCLCPP_INFO(nh_->get_logger(), "service not available, waiting again...");
}
auto result = my_client_->async_send_request(request);
//以下报错
if (rclcpp::spin_until_future_complete(nh_, result) == rclcpp::executor::FutureReturnCode::SUCCESS){
int num= int(result.get()->num);
printf("result:num:%d\n",num);
}
else {
RCLCPP_ERROR(nh_->get_logger(), "Failed to call service");
}
}
执行到rclcpp::spin_until_future_complete(nh_, result)时会报错"Node has already been added to an executor"。原因是spin_until_future_complete函数内部会创建一个executor,添加nh_这个Node,但一个node不允许被多个executor添加,所以报了错。
由于这个Node已经在main函数中被添加,所以直接接收response即可
void mySubCallback(const std_msgs::msg::Int32::SharedPtr msg){
printf("recieve a msg:%d\n",msg->data);
std::string data =std::to_string(pose_msg->data);
auto request = std::make_shared<my_msgs::srv::MyService::Request>();
request->data = data;
while (!my_client_->wait_for_service(std::chrono::seconds(1))) {
if (!rclcpp::ok()) {
RCLCPP_ERROR(nh_->get_logger(), "Interrupted while waiting for the service. Exiting.");
return;
}
RCLCPP_INFO(nh_->get_logger(), "service not available, waiting again...");
}
//成功执行
using ServiceResponseFuture =
rclcpp::Client<my_msgs::srv::MyService>::SharedFuture;
auto response_received_callback = [this](ServiceResponseFuture future) {
RCLCPP_INFO(nh_->get_logger(), "Got result: [%d]", future.get()->num);
};
auto future_result = my_client_->async_send_request(request, response_received_callback);
}