From 2d8178d61b1b050bc188fccf83c1629aaec6a26f Mon Sep 17 00:00:00 2001 From: Vladimir Ermakov Date: Fri, 7 Jun 2024 11:31:12 +0200 Subject: [PATCH] regenerate all using cogall.sh --- mavros/src/plugins/sys_status.cpp | 10 ++++------ mavros_extras/CMakeLists.txt | 2 +- mavros_extras/mavros_plugins.xml | 5 +++-- mavros_extras/src/plugins/onboard_computer_status.cpp | 5 ++--- mavros_msgs/CMakeLists.txt | 10 +++++----- 5 files changed, 15 insertions(+), 17 deletions(-) diff --git a/mavros/src/plugins/sys_status.cpp b/mavros/src/plugins/sys_status.cpp index 75b7a8a4a..d7aa9066f 100644 --- a/mavros/src/plugins/sys_status.cpp +++ b/mavros/src/plugins/sys_status.cpp @@ -780,9 +780,8 @@ class SystemStatusPlugin : public plugin::Plugin case enum_value(MAV_SEVERITY::ALERT): case enum_value(MAV_SEVERITY::CRITICAL): case enum_value(MAV_SEVERITY::ERROR): - RCLCPP_ERROR_STREAM( - node->get_logger(), - "FCU: EVENT " << px4_id << " with args " << arg_str); + RCLCPP_ERROR_STREAM(node->get_logger(), + "FCU: EVENT " << px4_id << " with args " << arg_str); break; case enum_value(MAV_SEVERITY::WARNING): case enum_value(MAV_SEVERITY::NOTICE): @@ -792,9 +791,8 @@ class SystemStatusPlugin : public plugin::Plugin RCLCPP_INFO_STREAM(node->get_logger(), "FCU: EVENT " << px4_id << " with args " << arg_str); break; case enum_value(MAV_SEVERITY::DEBUG): - RCLCPP_DEBUG_STREAM( - node->get_logger(), - "FCU: EVENT " << px4_id << " with args " << arg_str); + RCLCPP_DEBUG_STREAM(node->get_logger(), + "FCU: EVENT " << px4_id << " with args " << arg_str); break; // [[[end]]] (checksum: 83f5eab6a8989f95de46d2a95387304c) default: diff --git a/mavros_extras/CMakeLists.txt b/mavros_extras/CMakeLists.txt index 770327fe0..7cb732513 100644 --- a/mavros_extras/CMakeLists.txt +++ b/mavros_extras/CMakeLists.txt @@ -124,7 +124,7 @@ add_library(mavros_extras_plugins SHARED src/plugins/vision_pose_estimate.cpp src/plugins/vision_speed_estimate.cpp src/plugins/wheel_odometry.cpp - # [[[end]]] (checksum: e9b770ce685f15417fe9a859f1157b88) + # [[[end]]] (checksum: 1f8cd51fa90b89b27ee35d276b5f8c83) ) ament_target_dependencies(mavros_extras_plugins angles diff --git a/mavros_extras/mavros_plugins.xml b/mavros_extras/mavros_plugins.xml index ecffe7356..8e2e2a502 100644 --- a/mavros_extras/mavros_plugins.xml +++ b/mavros_extras/mavros_plugins.xml @@ -74,7 +74,8 @@ without a flag set. @brief Gimbal Control Plugin @plugin gimbal_control -Adds support for Mavlink Gimbal Protocol v2. +Adds support for Mavlink Gimbal Protocol v2. +Also publishes gimbal pose to TF when parameter tf_send==true @brief GPS_INPUT GPS plugin. @@ -239,4 +240,4 @@ This plugin allows computing and publishing wheel odometry coming from FCU wheel Can use either wheel's RPM or WHEEL_DISTANCE messages (the latter gives better accuracy). - + diff --git a/mavros_extras/src/plugins/onboard_computer_status.cpp b/mavros_extras/src/plugins/onboard_computer_status.cpp index 4899fc3fa..2a0aa9e61 100644 --- a/mavros_extras/src/plugins/onboard_computer_status.cpp +++ b/mavros_extras/src/plugins/onboard_computer_status.cpp @@ -99,9 +99,8 @@ class OnboardComputerStatusPlugin : public plugin::Plugin std::copy(req->cpu_combined.cbegin(), req->cpu_combined.cend(), status.cpu_combined.begin()); std::copy(req->gpu_cores.cbegin(), req->gpu_cores.cend(), status.gpu_cores.begin()); std::copy(req->gpu_combined.cbegin(), req->gpu_combined.cend(), status.gpu_combined.begin()); - std::copy( - req->temperature_core.cbegin(), - req->temperature_core.cend(), status.temperature_core.begin()); + std::copy(req->temperature_core.cbegin(), req->temperature_core.cend(), + status.temperature_core.begin()); std::copy(req->fan_speed.cbegin(), req->fan_speed.cend(), status.fan_speed.begin()); std::copy(req->storage_type.cbegin(), req->storage_type.cend(), status.storage_type.begin()); std::copy(req->storage_usage.cbegin(), req->storage_usage.cend(), status.storage_usage.begin()); diff --git a/mavros_msgs/CMakeLists.txt b/mavros_msgs/CMakeLists.txt index 93ca8d88b..a3220b0e2 100644 --- a/mavros_msgs/CMakeLists.txt +++ b/mavros_msgs/CMakeLists.txt @@ -50,6 +50,9 @@ set(msg_files msg/EstimatorStatus.msg msg/ExtendedState.msg msg/FileEntry.msg + msg/GPSINPUT.msg + msg/GPSRAW.msg + msg/GPSRTK.msg msg/GimbalDeviceAttitudeStatus.msg msg/GimbalDeviceInformation.msg msg/GimbalDeviceSetAttitude.msg @@ -57,9 +60,6 @@ set(msg_files msg/GimbalManagerSetAttitude.msg msg/GimbalManagerSetPitchyaw.msg msg/GimbalManagerStatus.msg - msg/GPSINPUT.msg - msg/GPSRAW.msg - msg/GPSRTK.msg msg/GlobalPositionTarget.msg msg/HilActuatorControls.msg msg/HilControls.msg @@ -105,7 +105,7 @@ set(msg_files msg/WaypointList.msg msg/WaypointReached.msg msg/WheelOdomStamped.msg - # [[[end]]] (checksum: 8a6c06289f2a7d9149b7309c1fe63463) + # [[[end]]] (checksum: a8e24eb0a6da5cea6cc049fdc6b2612e) ) set(srv_files @@ -158,7 +158,7 @@ set(srv_files srv/WaypointPull.srv srv/WaypointPush.srv srv/WaypointSetCurrent.srv - # [[[end]]] (checksum: def9cd208ca118971750a304b784d92a) + # [[[end]]] (checksum: cd7701b28a3176d96ef65cb1f2157917) ) rosidl_generate_interfaces(${PROJECT_NAME}