diff --git a/ros2/src/airsim_ros_pkgs/include/airsim_ros_wrapper.h b/ros2/src/airsim_ros_pkgs/include/airsim_ros_wrapper.h index a5126034b7..4092ac57f5 100755 --- a/ros2/src/airsim_ros_pkgs/include/airsim_ros_wrapper.h +++ b/ros2/src/airsim_ros_pkgs/include/airsim_ros_wrapper.h @@ -119,7 +119,7 @@ class AirsimROSWrapper CAR }; - AirsimROSWrapper(const std::shared_ptr nh, const std::shared_ptr nh_img, const std::shared_ptr nh_lidar, const std::string& host_ip); + AirsimROSWrapper(const std::shared_ptr nh, const std::shared_ptr nh_img, const std::shared_ptr nh_lidar, const std::string& host_ip, const std::shared_ptr callbackGroup); ~AirsimROSWrapper(){}; void initialize_airsim(); @@ -317,6 +317,7 @@ class AirsimROSWrapper std::shared_ptr nh_; std::shared_ptr nh_img_; std::shared_ptr nh_lidar_; + std::shared_ptr cb_; // todo not sure if async spinners shuold be inside this class, or should be instantiated in airsim_node.cpp, and cb queues should be public // todo for multiple drones with multiple sensors, this won't scale. make it a part of VehicleROS? diff --git a/ros2/src/airsim_ros_pkgs/src/airsim_node.cpp b/ros2/src/airsim_ros_pkgs/src/airsim_node.cpp index 1003f8556a..43d9975f98 100644 --- a/ros2/src/airsim_ros_pkgs/src/airsim_node.cpp +++ b/ros2/src/airsim_ros_pkgs/src/airsim_node.cpp @@ -11,25 +11,12 @@ int main(int argc, char** argv) std::shared_ptr nh_lidar = nh->create_sub_node("lidar"); std::string host_ip; nh->get_parameter("host_ip", host_ip); - AirsimROSWrapper airsim_ros_wrapper(nh, nh_img, nh_lidar, host_ip); + auto callbackGroup = nh->create_callback_group(rclcpp::CallbackGroupType::Reentrant); + AirsimROSWrapper airsim_ros_wrapper(nh, nh_img, nh_lidar, host_ip, callbackGroup); - if (airsim_ros_wrapper.is_used_img_timer_cb_queue_) { - rclcpp::executors::SingleThreadedExecutor executor; - executor.add_node(nh_img); - while (rclcpp::ok()) { - executor.spin(); - } - } - - if (airsim_ros_wrapper.is_used_lidar_timer_cb_queue_) { - rclcpp::executors::SingleThreadedExecutor executor; - executor.add_node(nh_lidar); - while (rclcpp::ok()) { - executor.spin(); - } - } - - rclcpp::spin(nh); + rclcpp::executors::MultiThreadedExecutor executor; + executor.add_node(nh); + executor.spin(); return 0; } \ No newline at end of file diff --git a/ros2/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp b/ros2/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp index ce3f3390df..18b6653362 100755 --- a/ros2/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp +++ b/ros2/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp @@ -24,7 +24,7 @@ const std::unordered_map AirsimROSWrapper::image_type_int_to_s { 7, "Infrared" } }; -AirsimROSWrapper::AirsimROSWrapper(const std::shared_ptr nh, const std::shared_ptr nh_img, const std::shared_ptr nh_lidar, const std::string& host_ip) +AirsimROSWrapper::AirsimROSWrapper(const std::shared_ptr nh, const std::shared_ptr nh_img, const std::shared_ptr nh_lidar, const std::string& host_ip, const std::shared_ptr callbackGroup) : is_used_lidar_timer_cb_queue_(false) , is_used_img_timer_cb_queue_(false) , airsim_settings_parser_(host_ip) @@ -35,6 +35,7 @@ AirsimROSWrapper::AirsimROSWrapper(const std::shared_ptr nh, const , nh_(nh) , nh_img_(nh_img) , nh_lidar_(nh_lidar) + , cb_(callbackGroup) , isENU_(false) , publish_clock_(false) { @@ -109,7 +110,7 @@ void AirsimROSWrapper::initialize_ros() nh_->declare_parameter("vehicle_name", rclcpp::ParameterValue("")); create_ros_pubs_from_settings_json(); - airsim_control_update_timer_ = nh_->create_wall_timer(std::chrono::duration(update_airsim_control_every_n_sec), std::bind(&AirsimROSWrapper::drone_state_timer_cb, this)); + airsim_control_update_timer_ = nh_->create_wall_timer(std::chrono::duration(update_airsim_control_every_n_sec), std::bind(&AirsimROSWrapper::drone_state_timer_cb, this), cb_); } void AirsimROSWrapper::create_ros_pubs_from_settings_json() @@ -310,7 +311,7 @@ void AirsimROSWrapper::create_ros_pubs_from_settings_json() double update_airsim_img_response_every_n_sec; nh_->get_parameter("update_airsim_img_response_every_n_sec", update_airsim_img_response_every_n_sec); - airsim_img_response_timer_ = nh_img_->create_wall_timer(std::chrono::duration(update_airsim_img_response_every_n_sec), std::bind(&AirsimROSWrapper::img_response_timer_cb, this)); + airsim_img_response_timer_ = nh_img_->create_wall_timer(std::chrono::duration(update_airsim_img_response_every_n_sec), std::bind(&AirsimROSWrapper::img_response_timer_cb, this), cb_); is_used_img_timer_cb_queue_ = true; } @@ -318,7 +319,7 @@ void AirsimROSWrapper::create_ros_pubs_from_settings_json() if (lidar_cnt > 0) { double update_lidar_every_n_sec; nh_->get_parameter("update_lidar_every_n_sec", update_lidar_every_n_sec); - airsim_lidar_update_timer_ = nh_lidar_->create_wall_timer(std::chrono::duration(update_lidar_every_n_sec), std::bind(&AirsimROSWrapper::lidar_timer_cb, this)); + airsim_lidar_update_timer_ = nh_lidar_->create_wall_timer(std::chrono::duration(update_lidar_every_n_sec), std::bind(&AirsimROSWrapper::lidar_timer_cb, this), cb_); is_used_lidar_timer_cb_queue_ = true; }