diff --git a/mavros/src/lib/mavros_router.cpp b/mavros/src/lib/mavros_router.cpp index ebb34601b..b52d7eb76 100644 --- a/mavros/src/lib/mavros_router.cpp +++ b/mavros/src/lib/mavros_router.cpp @@ -469,8 +469,7 @@ std::pair ROSEndpoint::open() } try { - auto qos = QoS( - 1000).best_effort().durability_volatile(); + auto qos = rclcpp::SensorDataQoS(); this->source = nh->create_publisher( utils::format( diff --git a/mavros/src/lib/mavros_uas.cpp b/mavros/src/lib/mavros_uas.cpp index d3c1a591a..7be1248de 100644 --- a/mavros/src/lib/mavros_uas.cpp +++ b/mavros/src/lib/mavros_uas.cpp @@ -346,8 +346,7 @@ rcl_interfaces::msg::SetParametersResult UAS::on_set_parameters_cb( void UAS::connect_to_router() { - auto qos = rclcpp::QoS( - 1000).best_effort().durability_volatile(); + auto qos = rclcpp::SensorDataQoS(); this->sink = this->create_publisher( diff --git a/mavros/src/lib/uas_executor.cpp b/mavros/src/lib/uas_executor.cpp index 567b15a84..92e82a57c 100644 --- a/mavros/src/lib/uas_executor.cpp +++ b/mavros/src/lib/uas_executor.cpp @@ -29,7 +29,7 @@ UASExecutor::UASExecutor(const rclcpp::ExecutorOptions & options) size_t UASExecutor::select_number_of_threads() { // return std::max(16, std::min(std::thread::hardware_concurrency(), 4)); - return std::clamp(std::thread::hardware_concurrency(), 4, 16); + return std::clamp(std::thread::hardware_concurrency(), 2, 8); } void UASExecutor::set_ids(uint8_t sysid, uint8_t compid) diff --git a/mavros/src/mavros_node.cpp b/mavros/src/mavros_node.cpp index a39887e31..99d4c438d 100644 --- a/mavros/src/mavros_node.cpp +++ b/mavros/src/mavros_node.cpp @@ -29,7 +29,7 @@ int main(int argc, char * argv[]) rclcpp::executors::MultiThreadedExecutor exec(rclcpp::ExecutorOptions(), 2); rclcpp::NodeOptions options; - // options.use_intra_process_comms(true); + options.use_intra_process_comms(true); std::string fcu_url, gcs_url, uas_url; std::string base_link_frame_id, odom_frame_id, map_frame_id;