Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 1 addition & 2 deletions mavros/src/lib/mavros_router.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -469,8 +469,7 @@ std::pair<bool, std::string> ROSEndpoint::open()
}

try {
auto qos = QoS(
1000).best_effort().durability_volatile();
auto qos = rclcpp::SensorDataQoS();
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What for? It's queue size is 5, which may be small.

this->source =
nh->create_publisher<mavros_msgs::msg::Mavlink>(
utils::format(
Expand Down
3 changes: 1 addition & 2 deletions mavros/src/lib/mavros_uas.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<mavros_msgs::msg::Mavlink>(
Expand Down
2 changes: 1 addition & 1 deletion mavros/src/lib/uas_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ UASExecutor::UASExecutor(const rclcpp::ExecutorOptions & options)
size_t UASExecutor::select_number_of_threads()
{
// return std::max<size_t>(16, std::min<size_t>(std::thread::hardware_concurrency(), 4));
return std::clamp<size_t>(std::thread::hardware_concurrency(), 4, 16);
return std::clamp<size_t>(std::thread::hardware_concurrency(), 2, 8);
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'd like to introduce UAS_MAXPROC env var, but it must be >= 2.

}

void UASExecutor::set_ids(uint8_t sysid, uint8_t compid)
Expand Down
2 changes: 1 addition & 1 deletion mavros/src/mavros_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Have you tested it? Does it work if the router and uas in the different processes (i mean if that scenario continue to work)?


std::string fcu_url, gcs_url, uas_url;
std::string base_link_frame_id, odom_frame_id, map_frame_id;
Expand Down
Loading