From a22bf595cb13a1a1ed984bb5df9e6d9d48ecbd4b Mon Sep 17 00:00:00 2001 From: Vladimir Ermakov Date: Sat, 9 Sep 2023 11:06:03 +0000 Subject: [PATCH] Imported upstream version '1.17.0' of 'upstream' --- libmavconn/CHANGELOG.rst | 7 +++ libmavconn/CMakeLists.txt | 1 + libmavconn/package.xml | 2 +- mavros/CHANGELOG.rst | 17 ++++++ mavros/CMakeLists.txt | 1 + mavros/include/mavros/mavlink_diag.h | 2 +- mavros/package.xml | 2 +- mavros/src/lib/enum_to_string.cpp | 60 +++++++++++++------- mavros/src/lib/mavlink_diag.cpp | 2 +- mavros/src/plugins/global_position.cpp | 4 +- mavros_extras/CHANGELOG.rst | 8 +++ mavros_extras/CMakeLists.txt | 1 + mavros_extras/package.xml | 2 +- mavros_extras/src/plugins/landing_target.cpp | 8 +-- mavros_extras/src/plugins/mount_control.cpp | 4 +- mavros_extras/src/plugins/wheel_odometry.cpp | 2 +- mavros_msgs/CHANGELOG.rst | 5 ++ mavros_msgs/msg/CommandCode.msg | 31 ++++++---- mavros_msgs/package.xml | 2 +- mavros_msgs/srv/SetMavFrame.srv | 24 ++++---- test_mavros/CHANGELOG.rst | 7 +++ test_mavros/CMakeLists.txt | 1 + test_mavros/package.xml | 2 +- 23 files changed, 137 insertions(+), 58 deletions(-) diff --git a/libmavconn/CHANGELOG.rst b/libmavconn/CHANGELOG.rst index 36a87fccc..a0b47ccd8 100644 --- a/libmavconn/CHANGELOG.rst +++ b/libmavconn/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package libmavconn ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.17.0 (2023-09-09) +------------------- +* Merge pull request `#1865 `_ from scoutdi/warnings + Fix / suppress some build warnings +* Suppress warnings from included headers +* Contributors: Morten Fyhn Amundsen, Vladimir Ermakov + 1.16.0 (2023-05-05) ------------------- diff --git a/libmavconn/CMakeLists.txt b/libmavconn/CMakeLists.txt index 1bcd328bc..91dc1daf7 100644 --- a/libmavconn/CMakeLists.txt +++ b/libmavconn/CMakeLists.txt @@ -35,6 +35,7 @@ catkin_package( include_directories( include + SYSTEM ${CMAKE_CURRENT_BINARY_DIR}/catkin_generated/include ${Boost_INCLUDE_DIRS} ${mavlink_INCLUDE_DIRS} diff --git a/libmavconn/package.xml b/libmavconn/package.xml index fdc15cdf1..5be2fcb0a 100644 --- a/libmavconn/package.xml +++ b/libmavconn/package.xml @@ -1,7 +1,7 @@ libmavconn - 1.16.0 + 1.17.0 MAVLink communication library. This library provide unified connection handling classes diff --git a/mavros/CHANGELOG.rst b/mavros/CHANGELOG.rst index d13629af6..96a0265e5 100644 --- a/mavros/CHANGELOG.rst +++ b/mavros/CHANGELOG.rst @@ -2,6 +2,23 @@ Changelog for package mavros ^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.17.0 (2023-09-09) +------------------- +* cog: regenerate all +* Bugfix/update map origin with home position (`#1892 `_) + * Update map origin with home position + * Uncrustify + * Revert "Uncrustify" + This reverts commit f1387c79c7670cc241986586436e3da43842e877. + * Change to relative topic + --------- + Co-authored-by: Natalia Molina +* Merge pull request `#1865 `_ from scoutdi/warnings + Fix / suppress some build warnings +* mavros: Remove extra ';' +* Suppress warnings from included headers +* Contributors: Morten Fyhn Amundsen, Vladimir Ermakov, natmol + 1.16.0 (2023-05-05) ------------------- * Merge pull request `#1829 `_ from snwu1996/latched_gp_origin_pub diff --git a/mavros/CMakeLists.txt b/mavros/CMakeLists.txt index 994003d68..020d07bb9 100644 --- a/mavros/CMakeLists.txt +++ b/mavros/CMakeLists.txt @@ -87,6 +87,7 @@ catkin_package( include_directories( include + SYSTEM ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS} ${mavlink_INCLUDE_DIRS} diff --git a/mavros/include/mavros/mavlink_diag.h b/mavros/include/mavros/mavlink_diag.h index b2dff3930..43f9e1cc3 100644 --- a/mavros/include/mavros/mavlink_diag.h +++ b/mavros/include/mavros/mavlink_diag.h @@ -40,5 +40,5 @@ class MavlinkDiag : public diagnostic_updater::DiagnosticTask unsigned int last_drop_count; std::atomic is_connected; }; -}; // namespace mavros +} // namespace mavros diff --git a/mavros/package.xml b/mavros/package.xml index 18b7991b6..1f2df7e93 100644 --- a/mavros/package.xml +++ b/mavros/package.xml @@ -1,7 +1,7 @@ mavros - 1.16.0 + 1.17.0 MAVROS -- MAVLink extendable communication node for ROS with proxy for Ground Control Station. diff --git a/mavros/src/lib/enum_to_string.cpp b/mavros/src/lib/enum_to_string.cpp index c3d8b1ff1..c361352d3 100644 --- a/mavros/src/lib/enum_to_string.cpp +++ b/mavros/src/lib/enum_to_string.cpp @@ -105,7 +105,7 @@ using mavlink::common::LANDING_TARGET_TYPE; // to_string_outl(ename) // ]]] //! MAV_AUTOPILOT values -static const std::array mav_autopilot_strings{{ +static const std::array mav_autopilot_strings{{ /* 0 */ "Generic autopilot", // Generic autopilot, full support for everything /* 1 */ "Reserved for future use", // Reserved for future use. /* 2 */ "SLUGS autopilot", // SLUGS autopilot, http://slugsuav.soe.ucsc.edu @@ -126,6 +126,7 @@ static const std::array mav_autopilot_strings{{ /* 17 */ "ASLUAV autopilot", // ASLUAV autopilot -- http://www.asl.ethz.ch /* 18 */ "SmartAP Autopilot", // SmartAP Autopilot - http://sky-drones.com /* 19 */ "AirRails", // AirRails - http://uaventure.com +/* 20 */ "Fusion Reflex", // Fusion Reflex - https://fusion.engineering }}; std::string to_string(MAV_AUTOPILOT e) @@ -136,7 +137,7 @@ std::string to_string(MAV_AUTOPILOT e) return mav_autopilot_strings[idx]; } -// [[[end]]] (checksum: c1feb82117da0447594aacbe5c52f97b) +// [[[end]]] (checksum: 036beb51a16d3fa9cbb47ab59c767238) // [[[cog: // ename = 'MAV_TYPE' @@ -153,7 +154,7 @@ std::string to_string(MAV_AUTOPILOT e) // to_string_outl(ename) // ]]] //! MAV_TYPE values -static const std::array mav_type_strings{{ +static const std::array mav_type_strings{{ /* 0 */ "Generic micro air vehicle", // Generic micro air vehicle /* 1 */ "Fixed wing aircraft", // Fixed wing aircraft. /* 2 */ "Quadrotor", // Quadrotor @@ -190,6 +191,13 @@ static const std::array mav_type_strings{{ /* 33 */ "Servo", // Servo /* 34 */ "Open Drone ID. See https:", // Open Drone ID. See https://mavlink.io/en/services/opendroneid.html. /* 35 */ "Decarotor", // Decarotor +/* 36 */ "Battery", // Battery +/* 37 */ "Parachute", // Parachute +/* 38 */ "Log", // Log +/* 39 */ "OSD", // OSD +/* 40 */ "IMU", // IMU +/* 41 */ "GPS", // GPS +/* 42 */ "Winch", // Winch }}; std::string to_string(MAV_TYPE e) @@ -200,14 +208,14 @@ std::string to_string(MAV_TYPE e) return mav_type_strings[idx]; } -// [[[end]]] (checksum: f44b083f4b6be34f26d75692072f09bf) +// [[[end]]] (checksum: 18825caa6c70eb36e076c1bfffa9150c) // [[[cog: // ename = 'MAV_TYPE' // enum_name_is_value_outl(ename, funcname='to_name', suffix='_names') // ]]] //! MAV_TYPE values -static const std::array mav_type_names{{ +static const std::array mav_type_names{{ /* 0 */ "GENERIC", // Generic micro air vehicle /* 1 */ "FIXED_WING", // Fixed wing aircraft. /* 2 */ "QUADROTOR", // Quadrotor @@ -244,6 +252,13 @@ static const std::array mav_type_names{{ /* 33 */ "SERVO", // Servo /* 34 */ "ODID", // Open Drone ID. See https://mavlink.io/en/services/opendroneid.html. /* 35 */ "DECAROTOR", // Decarotor +/* 36 */ "BATTERY", // Battery +/* 37 */ "PARACHUTE", // Parachute +/* 38 */ "LOG", // Log +/* 39 */ "OSD", // OSD +/* 40 */ "IMU", // IMU +/* 41 */ "GPS", // GPS +/* 42 */ "WINCH", // Winch }}; std::string to_name(MAV_TYPE e) @@ -254,7 +269,7 @@ std::string to_name(MAV_TYPE e) return mav_type_names[idx]; } -// [[[end]]] (checksum: 3775b5a8763b4e66287a471af939ef6c) +// [[[end]]] (checksum: 02033dc5baa70557f1072dde8c403251) // [[[cog: // ename = 'MAV_STATE' @@ -499,18 +514,18 @@ std::string to_string(MAV_MISSION_RESULT e) //! MAV_FRAME values static const std::array mav_frame_strings{{ /* 0 */ "GLOBAL", // Global (WGS84) coordinate frame + MSL altitude. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL). -/* 1 */ "LOCAL_NED", // Local coordinate frame, Z-down (x: North, y: East, z: Down). +/* 1 */ "LOCAL_NED", // NED local tangent frame (x: North, y: East, z: Down) with origin fixed relative to earth. /* 2 */ "MISSION", // NOT a coordinate frame, indicates a mission command. /* 3 */ "GLOBAL_RELATIVE_ALT", // Global (WGS84) coordinate frame + altitude relative to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. -/* 4 */ "LOCAL_ENU", // Local coordinate frame, Z-up (x: East, y: North, z: Up). -/* 5 */ "GLOBAL_INT", // Global (WGS84) coordinate frame (scaled) + MSL altitude. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL). -/* 6 */ "GLOBAL_RELATIVE_ALT_INT", // Global (WGS84) coordinate frame (scaled) + altitude relative to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location. -/* 7 */ "LOCAL_OFFSET_NED", // Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position. -/* 8 */ "BODY_NED", // Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right. -/* 9 */ "BODY_OFFSET_NED", // Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east. +/* 4 */ "LOCAL_ENU", // ENU local tangent frame (x: East, y: North, z: Up) with origin fixed relative to earth. +/* 5 */ "GLOBAL_INT", // Global (WGS84) coordinate frame (scaled) + MSL altitude. First value / x: latitude in degrees*1E7, second value / y: longitude in degrees*1E7, third value / z: positive altitude over mean sea level (MSL). +/* 6 */ "GLOBAL_RELATIVE_ALT_INT", // Global (WGS84) coordinate frame (scaled) + altitude relative to the home position. First value / x: latitude in degrees*1E7, second value / y: longitude in degrees*1E7, third value / z: positive altitude with 0 being at the altitude of the home location. +/* 7 */ "LOCAL_OFFSET_NED", // NED local tangent frame (x: North, y: East, z: Down) with origin that travels with the vehicle. +/* 8 */ "BODY_NED", // Same as MAV_FRAME_LOCAL_NED when used to represent position values. Same as MAV_FRAME_BODY_FRD when used with velocity/accelaration values. +/* 9 */ "BODY_OFFSET_NED", // This is the same as MAV_FRAME_BODY_FRD. /* 10 */ "GLOBAL_TERRAIN_ALT", // Global (WGS84) coordinate frame with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model. -/* 11 */ "GLOBAL_TERRAIN_ALT_INT", // Global (WGS84) coordinate frame (scaled) with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model. -/* 12 */ "BODY_FRD", // Body fixed frame of reference, Z-down (x: Forward, y: Right, z: Down). +/* 11 */ "GLOBAL_TERRAIN_ALT_INT", // Global (WGS84) coordinate frame (scaled) with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees*1E7, second value / y: longitude in degrees*1E7, third value / z: positive altitude in meters with 0 being at ground level in terrain model. +/* 12 */ "BODY_FRD", // FRD local tangent frame (x: Forward, y: Right, z: Down) with origin that travels with vehicle. The forward axis is aligned to the front of the vehicle in the horizontal plane. /* 13 */ "RESERVED_13", // MAV_FRAME_BODY_FLU - Body fixed frame of reference, Z-up (x: Forward, y: Left, z: Up). /* 14 */ "RESERVED_14", // MAV_FRAME_MOCAP_NED - Odometry local coordinate frame of data given by a motion capture system, Z-down (x: North, y: East, z: Down). /* 15 */ "RESERVED_15", // MAV_FRAME_MOCAP_ENU - Odometry local coordinate frame of data given by a motion capture system, Z-up (x: East, y: North, z: Up). @@ -518,8 +533,8 @@ static const std::array mav_frame_strings{{ /* 17 */ "RESERVED_17", // MAV_FRAME_VISION_ENU - Odometry local coordinate frame of data given by a vision estimation system, Z-up (x: East, y: North, z: Up). /* 18 */ "RESERVED_18", // MAV_FRAME_ESTIM_NED - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: North, y: East, z: Down). /* 19 */ "RESERVED_19", // MAV_FRAME_ESTIM_ENU - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-up (x: East, y: North, z: Up). -/* 20 */ "LOCAL_FRD", // Forward, Right, Down coordinate frame. This is a local frame with Z-down and arbitrary F/R alignment (i.e. not aligned with NED/earth frame). -/* 21 */ "LOCAL_FLU", // Forward, Left, Up coordinate frame. This is a local frame with Z-up and arbitrary F/L alignment (i.e. not aligned with ENU/earth frame). +/* 20 */ "LOCAL_FRD", // FRD local tangent frame (x: Forward, y: Right, z: Down) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane. +/* 21 */ "LOCAL_FLU", // FLU local tangent frame (x: Forward, y: Left, z: Up) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane. }}; std::string to_string(MAV_FRAME e) @@ -530,7 +545,7 @@ std::string to_string(MAV_FRAME e) return mav_frame_strings[idx]; } -// [[[end]]] (checksum: f7783e4d7764c236021e92fc4a1c16a1) +// [[[end]]] (checksum: 25c2bfb3375047a329efe0dd98ac014a) // [[[cog: // ename = 'MAV_COMPONENT' @@ -653,13 +668,20 @@ static const std::unordered_map::ty { 158, "PERIPHERAL" }, // Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter microservice. { 159, "QX1_GIMBAL" }, // Gimbal ID for QX1. { 160, "FLARM" }, // FLARM collision alert component. +{ 161, "PARACHUTE" }, // Parachute component. { 171, "GIMBAL2" }, // Gimbal #2. { 172, "GIMBAL3" }, // Gimbal #3. { 173, "GIMBAL4" }, // Gimbal #4 { 174, "GIMBAL5" }, // Gimbal #5. { 175, "GIMBAL6" }, // Gimbal #6. +{ 180, "BATTERY" }, // Battery #1. +{ 181, "BATTERY2" }, // Battery #2. +{ 189, "MAVCAN" }, // CAN over MAVLink client. { 190, "MISSIONPLANNER" }, // Component that can generate/supply a mission flight plan (e.g. GCS or developer API). { 191, "ONBOARD_COMPUTER" }, // Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on. +{ 192, "ONBOARD_COMPUTER2" }, // Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on. +{ 193, "ONBOARD_COMPUTER3" }, // Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on. +{ 194, "ONBOARD_COMPUTER4" }, // Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on. { 195, "PATHPLANNER" }, // Component that finds an optimal path between points based on a certain constraint (e.g. minimum snap, shortest path, cost, etc.). { 196, "OBSTACLE_AVOIDANCE" }, // Component that plans a collision free path between two points. { 197, "VISUAL_INERTIAL_ODOMETRY" }, // Component that provides position estimates using VIO techniques. @@ -677,7 +699,7 @@ static const std::unordered_map::ty { 242, "TUNNEL_NODE" }, // Component handling TUNNEL messages (e.g. vendor specific GUI of a component). { 250, "SYSTEM_CONTROL" }, // Component for handling system messages (e.g. to ARM, takeoff, etc.). }}; -// [[[end]]] (checksum: 2dc119e3e20f7668a71e8649ba3f67b6) +// [[[end]]] (checksum: 0f3c4a601107653ab0bb3bb92c415b8e) std::string to_string(MAV_COMPONENT e) { diff --git a/mavros/src/lib/mavlink_diag.cpp b/mavros/src/lib/mavlink_diag.cpp index c5f9ee885..54545ae0f 100644 --- a/mavros/src/lib/mavlink_diag.cpp +++ b/mavros/src/lib/mavlink_diag.cpp @@ -19,7 +19,7 @@ MavlinkDiag::MavlinkDiag(std::string name) : diagnostic_updater::DiagnosticTask(name), last_drop_count(0), is_connected(false) -{ }; +{ } void MavlinkDiag::run(diagnostic_updater::DiagnosticStatusWrapper &stat) { diff --git a/mavros/src/plugins/global_position.cpp b/mavros/src/plugins/global_position.cpp index 57cce6298..c8e35f395 100644 --- a/mavros/src/plugins/global_position.cpp +++ b/mavros/src/plugins/global_position.cpp @@ -48,6 +48,7 @@ class GlobalPositionPlugin : public plugin::PluginBase { GlobalPositionPlugin() : PluginBase(), gp_nh("~global_position"), + hp_nh("~home_position"), tf_send(false), use_relative_alt(true), is_map_init(false), @@ -89,7 +90,7 @@ class GlobalPositionPlugin : public plugin::PluginBase { // home position subscriber to set "map" origin // TODO use UAS - hp_sub = gp_nh.subscribe("home", 10, &GlobalPositionPlugin::home_position_cb, this); + hp_sub = hp_nh.subscribe("home", 10, &GlobalPositionPlugin::home_position_cb, this); // offset from local position to the global origin ("earth") gp_global_offset_pub = gp_nh.advertise("gp_lp_offset", 10); @@ -108,6 +109,7 @@ class GlobalPositionPlugin : public plugin::PluginBase { private: ros::NodeHandle gp_nh; + ros::NodeHandle hp_nh; //node handler in home_position namespace ros::Publisher raw_fix_pub; ros::Publisher raw_vel_pub; diff --git a/mavros_extras/CHANGELOG.rst b/mavros_extras/CHANGELOG.rst index b66df9f25..7cdad2b4e 100644 --- a/mavros_extras/CHANGELOG.rst +++ b/mavros_extras/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package mavros_extras ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.17.0 (2023-09-09) +------------------- +* Merge pull request `#1865 `_ from scoutdi/warnings + Fix / suppress some build warnings +* mavros_extras: Fix some init order warnings +* Suppress warnings from included headers +* Contributors: Morten Fyhn Amundsen, Vladimir Ermakov + 1.16.0 (2023-05-05) ------------------- * Merge pull request `#1817 `_ from lucasw/pluginlib_hpp diff --git a/mavros_extras/CMakeLists.txt b/mavros_extras/CMakeLists.txt index 0b19ac443..26e3a71bd 100644 --- a/mavros_extras/CMakeLists.txt +++ b/mavros_extras/CMakeLists.txt @@ -60,6 +60,7 @@ catkin_package( ########### include_directories( + SYSTEM ${catkin_INCLUDE_DIRS} ${mavlink_INCLUDE_DIRS} ) diff --git a/mavros_extras/package.xml b/mavros_extras/package.xml index 81507c603..884617102 100644 --- a/mavros_extras/package.xml +++ b/mavros_extras/package.xml @@ -1,7 +1,7 @@ mavros_extras - 1.16.0 + 1.17.0 Extra nodes and plugins for MAVROS. diff --git a/mavros_extras/src/plugins/landing_target.cpp b/mavros_extras/src/plugins/landing_target.cpp index 58e58df07..74a2a2f7e 100644 --- a/mavros_extras/src/plugins/landing_target.cpp +++ b/mavros_extras/src/plugins/landing_target.cpp @@ -40,18 +40,18 @@ class LandingTargetPlugin : public plugin::PluginBase, public: LandingTargetPlugin() : nh("~landing_target"), - tf_rate(10.0), send_tf(true), listen_tf(false), + tf_rate(10.0), listen_lt(false), - mav_frame("LOCAL_NED"), target_size_x(1.0), target_size_y(1.0), - image_width(640), - image_height(480), fov_x(2.0071286398), fov_y(2.0071286398), focal_length(2.8), + image_width(640), + image_height(480), + mav_frame("LOCAL_NED"), land_target_type("VISION_FIDUCIAL") { } diff --git a/mavros_extras/src/plugins/mount_control.cpp b/mavros_extras/src/plugins/mount_control.cpp index 3c590adac..22f177399 100644 --- a/mavros_extras/src/plugins/mount_control.cpp +++ b/mavros_extras/src/plugins/mount_control.cpp @@ -166,8 +166,8 @@ class MountControlPlugin : public plugin::PluginBase { public: MountControlPlugin() : PluginBase(), nh("~"), - mount_diag("Mount"), - mount_nh("~mount_control") + mount_nh("~mount_control"), + mount_diag("Mount") { } void initialize(UAS &uas_) override diff --git a/mavros_extras/src/plugins/wheel_odometry.cpp b/mavros_extras/src/plugins/wheel_odometry.cpp index 3f84eb4b5..22e8e1232 100644 --- a/mavros_extras/src/plugins/wheel_odometry.cpp +++ b/mavros_extras/src/plugins/wheel_odometry.cpp @@ -38,8 +38,8 @@ class WheelOdometryPlugin : public plugin::PluginBase { WheelOdometryPlugin() : PluginBase(), wo_nh("~wheel_odometry"), - count(0), odom_mode(OM::NONE), + count(0), raw_send(false), twist_send(false), tf_send(false), diff --git a/mavros_msgs/CHANGELOG.rst b/mavros_msgs/CHANGELOG.rst index da128e071..133409ded 100644 --- a/mavros_msgs/CHANGELOG.rst +++ b/mavros_msgs/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package mavros_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.17.0 (2023-09-09) +------------------- +* cog: regenerate all +* Contributors: Vladimir Ermakov + 1.16.0 (2023-05-05) ------------------- diff --git a/mavros_msgs/msg/CommandCode.msg b/mavros_msgs/msg/CommandCode.msg index b1fe834d9..cde585937 100644 --- a/mavros_msgs/msg/CommandCode.msg +++ b/mavros_msgs/msg/CommandCode.msg @@ -7,6 +7,9 @@ # from collections import OrderedDict # import re # +# def clear_desc(s): +# return ' '.join(v.strip() for v in s.splitlines() if v.strip()) +# # def wr_enum(enum, ename, pfx='', bsz=16): # cog.outl("# " + ename + "_" + pfx) # for k, e in enum: @@ -15,7 +18,7 @@ # sn = e.name[len('MAV_CMD') + 1:] # l = "uint{bsz} {sn} = {k}".format(**locals()) # if e.description: -# l += ' ' * (50 - len(l)) + ' # ' + e.description +# l += ' ' * (50 - len(l)) + ' # ' + clear_desc(e.description) # cog.outl(l) # cog.out('\n') # @@ -42,7 +45,14 @@ uint16 AIRFRAME_CONFIGURATION = 2520 # MAV_CMD_ARM uint16 ARM_AUTHORIZATION_REQUEST = 3001 # Request authorization to arm the vehicle to a external entity, the arm authorizer is responsible to request all data that is needs from the vehicle before authorize or deny the request. If approved the progress of command_ack message should be set with period of time that this authorization is valid in seconds or in case it was denied it should be set with one of the reasons in ARM_AUTH_DENIED_REASON. - + +# MAV_CMD_CAMERA +uint16 CAMERA_TRACK_POINT = 2004 # If the camera supports point visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_POINT is set), this command allows to initiate the tracking. +uint16 CAMERA_TRACK_RECTANGLE = 2005 # If the camera supports rectangle visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE is set), this command allows to initiate the tracking. +uint16 CAMERA_STOP_TRACKING = 2010 # Stops ongoing tracking. + +# MAV_CMD_CAN +uint16 CAN_FORWARD = 32000 # Request forwarding of CAN packets from the given CAN bus to this interface. CAN Frames are sent using CAN_FRAME and CANFD_FRAME messages # MAV_CMD_COMPONENT uint16 COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component @@ -71,7 +81,7 @@ uint16 DO_SET_SERVO = 183 # Set a servo to a desired PW uint16 DO_REPEAT_SERVO = 184 # Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. uint16 DO_FLIGHTTERMINATION = 185 # Terminate flight immediately uint16 DO_CHANGE_ALTITUDE = 186 # Change altitude set point. -uint16 DO_LAND_START = 189 # Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0 if not needed. If specified then it will be used to help find the closest landing sequence. +uint16 DO_LAND_START = 189 # Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude/Altitude is optional, and may be set to 0 if not needed. If specified then it will be used to help find the closest landing sequence. uint16 DO_RALLY_LAND = 190 # Mission command to perform a landing from a rally point. uint16 DO_GO_AROUND = 191 # Mission command to safely abort an autonomous landing. uint16 DO_REPOSITION = 192 # Reposition the vehicle to a specific WGS84 global position. @@ -102,6 +112,8 @@ uint16 DO_ENGINE_CONTROL = 223 # Control vehicle engine. Thi uint16 DO_SET_MISSION_CURRENT = 224 # Set the mission item with sequence number seq as current item. This means that the MAV will continue to this mission item on the shortest path (not following the mission items in-between). uint16 DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO commands in the enumeration uint16 DO_JUMP_TAG = 601 # Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number. +uint16 DO_GIMBAL_MANAGER_PITCHYAW = 1000 # Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate. +uint16 DO_GIMBAL_MANAGER_CONFIGURE = 1001 # Gimbal configuration to set which sysid/compid is in primary and secondary control. uint16 DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system. uint16 DO_VTOL_TRANSITION = 3000 # Request VTOL transition uint16 DO_ADSB_OUT_IDENT = 10001 # Trigger the start of an ADSB-out IDENT. This should only be used when requested to do so by an Air Traffic Controller in controlled airspace. This starts the IDENT which is then typically held for 18 seconds by the hardware per the Mode A, C, and S transponder spec. @@ -144,7 +156,7 @@ uint16 NAV_LOITER_TO_ALT = 31 # Begin loiter at the specifi uint16 NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. uint16 NAV_PATHPLANNING = 81 # Control autonomous path planning on the MAV. uint16 NAV_SPLINE_WAYPOINT = 82 # Navigate to waypoint using a spline path. -uint16 NAV_VTOL_TAKEOFF = 84 # Takeoff from ground using VTOL mode, and transition to forward flight with specified heading. +uint16 NAV_VTOL_TAKEOFF = 84 # Takeoff from ground using VTOL mode, and transition to forward flight with specified heading. The command should be ignored by vehicles that dont support both VTOL and fixed-wing flight (multicopters, boats,etc.). uint16 NAV_VTOL_LAND = 85 # Land using VTOL mode uint16 NAV_GUIDED_ENABLE = 92 # hand control over to an external controller uint16 NAV_DELAY = 93 # Delay the next navigation command a number of seconds or until a specified time @@ -153,15 +165,10 @@ uint16 NAV_LAST = 95 # NOP - This command is only uint16 NAV_SET_YAW_SPEED = 213 # Sets a desired vehicle turn angle and speed change. uint16 NAV_FENCE_RETURN_POINT = 5000 # Fence return point (there can only be one such point in a geofence definition). If rally points are supported they should be used instead. uint16 NAV_FENCE_POLYGON_VERTEX_INCLUSION = 5001 # Fence vertex for an inclusion polygon (the polygon must not be self-intersecting). The vehicle must stay within this area. Minimum of 3 vertices required. - uint16 NAV_FENCE_POLYGON_VERTEX_EXCLUSION = 5002 # Fence vertex for an exclusion polygon (the polygon must not be self-intersecting). The vehicle must stay outside this area. Minimum of 3 vertices required. - uint16 NAV_FENCE_CIRCLE_INCLUSION = 5003 # Circular fence area. The vehicle must stay inside this area. - uint16 NAV_FENCE_CIRCLE_EXCLUSION = 5004 # Circular fence area. The vehicle must stay outside this area. - uint16 NAV_RALLY_POINT = 5100 # Rally point. You can have multiple rally points defined. - # MAV_CMD_OBLIQUE uint16 OBLIQUE_SURVEY = 260 # Mission command to set a Camera Auto Mount Pivoting Oblique Survey (Replaces CAM_TRIGG_DIST for this purpose). The camera is triggered each time this distance is exceeded, then the mount moves to the next position. Params 4~6 set-up the angle limits and number of positions for oblique survey, where mount-enabled vehicles automatically roll the camera between shots to emulate an oblique camera setup (providing an increased HFOV). This command can also be used to set the shutter integration time for the camera. @@ -204,10 +211,10 @@ uint16 RUN_PREARM_CHECKS = 401 # Instructs system to run pre # MAV_CMD_SET uint16 SET_MESSAGE_INTERVAL = 511 # Set the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM. uint16 SET_CAMERA_MODE = 530 # Set camera running mode. Use NaN for reserved values. GCS will send a MAV_CMD_REQUEST_VIDEO_STREAM_STATUS command after a mode change if the camera supports video streaming. +uint16 SET_CAMERA_ZOOM = 531 # Set camera zoom. Camera must respond with a CAMERA_SETTINGS message (on success). +uint16 SET_CAMERA_FOCUS = 532 # Set camera focus. Camera must respond with a CAMERA_SETTINGS message (on success). uint16 SET_GUIDED_SUBMODE_STANDARD = 4000 # This command sets the submode to standard guided when vehicle is in guided mode. The vehicle holds position and altitude and the user can input the desired velocities along all three axes. - uint16 SET_GUIDED_SUBMODE_CIRCLE = 4001 # This command sets submode circle when vehicle is in guided mode. Vehicle flies along a circle facing the center of the circle. The user can input the velocity along the circle and change the radius. If no input is given the vehicle will hold position. - # MAV_CMD_START uint16 START_RX_PAIR = 500 # Starts receiver pairing. @@ -224,4 +231,4 @@ uint16 VIDEO_STOP_CAPTURE = 2501 # Stop the current video capt uint16 VIDEO_START_STREAMING = 2502 # Start video streaming uint16 VIDEO_STOP_STREAMING = 2503 # Stop the given video stream -# [[[end]]] (checksum: 01fa1723eb3702c301c5562fdf293bbc) +# [[[end]]] (checksum: cb312f449893c76af4bf35424ccff882) diff --git a/mavros_msgs/package.xml b/mavros_msgs/package.xml index 59e6019bc..e8ce7bd1c 100644 --- a/mavros_msgs/package.xml +++ b/mavros_msgs/package.xml @@ -1,7 +1,7 @@ mavros_msgs - 1.16.0 + 1.17.0 mavros_msgs defines messages for MAVROS. diff --git a/mavros_msgs/srv/SetMavFrame.srv b/mavros_msgs/srv/SetMavFrame.srv index 97f3552b9..8672954d8 100644 --- a/mavros_msgs/srv/SetMavFrame.srv +++ b/mavros_msgs/srv/SetMavFrame.srv @@ -19,18 +19,18 @@ # ]]] # MAV_FRAME uint8 FRAME_GLOBAL = 0 # Global (WGS84) coordinate frame + MSL altitude. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL). -uint8 FRAME_LOCAL_NED = 1 # Local coordinate frame, Z-down (x: North, y: East, z: Down). +uint8 FRAME_LOCAL_NED = 1 # NED local tangent frame (x: North, y: East, z: Down) with origin fixed relative to earth. uint8 FRAME_MISSION = 2 # NOT a coordinate frame, indicates a mission command. uint8 FRAME_GLOBAL_RELATIVE_ALT = 3 # Global (WGS84) coordinate frame + altitude relative to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. -uint8 FRAME_LOCAL_ENU = 4 # Local coordinate frame, Z-up (x: East, y: North, z: Up). -uint8 FRAME_GLOBAL_INT = 5 # Global (WGS84) coordinate frame (scaled) + MSL altitude. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL). -uint8 FRAME_GLOBAL_RELATIVE_ALT_INT = 6 # Global (WGS84) coordinate frame (scaled) + altitude relative to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location. -uint8 FRAME_LOCAL_OFFSET_NED = 7 # Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position. -uint8 FRAME_BODY_NED = 8 # Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right. -uint8 FRAME_BODY_OFFSET_NED = 9 # Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east. +uint8 FRAME_LOCAL_ENU = 4 # ENU local tangent frame (x: East, y: North, z: Up) with origin fixed relative to earth. +uint8 FRAME_GLOBAL_INT = 5 # Global (WGS84) coordinate frame (scaled) + MSL altitude. First value / x: latitude in degrees*1E7, second value / y: longitude in degrees*1E7, third value / z: positive altitude over mean sea level (MSL). +uint8 FRAME_GLOBAL_RELATIVE_ALT_INT = 6 # Global (WGS84) coordinate frame (scaled) + altitude relative to the home position. First value / x: latitude in degrees*1E7, second value / y: longitude in degrees*1E7, third value / z: positive altitude with 0 being at the altitude of the home location. +uint8 FRAME_LOCAL_OFFSET_NED = 7 # NED local tangent frame (x: North, y: East, z: Down) with origin that travels with the vehicle. +uint8 FRAME_BODY_NED = 8 # Same as MAV_FRAME_LOCAL_NED when used to represent position values. Same as MAV_FRAME_BODY_FRD when used with velocity/accelaration values. +uint8 FRAME_BODY_OFFSET_NED = 9 # This is the same as MAV_FRAME_BODY_FRD. uint8 FRAME_GLOBAL_TERRAIN_ALT = 10 # Global (WGS84) coordinate frame with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model. -uint8 FRAME_GLOBAL_TERRAIN_ALT_INT = 11 # Global (WGS84) coordinate frame (scaled) with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model. -uint8 FRAME_BODY_FRD = 12 # Body fixed frame of reference, Z-down (x: Forward, y: Right, z: Down). +uint8 FRAME_GLOBAL_TERRAIN_ALT_INT = 11 # Global (WGS84) coordinate frame (scaled) with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees*1E7, second value / y: longitude in degrees*1E7, third value / z: positive altitude in meters with 0 being at ground level in terrain model. +uint8 FRAME_BODY_FRD = 12 # FRD local tangent frame (x: Forward, y: Right, z: Down) with origin that travels with vehicle. The forward axis is aligned to the front of the vehicle in the horizontal plane. uint8 FRAME_RESERVED_13 = 13 # MAV_FRAME_BODY_FLU - Body fixed frame of reference, Z-up (x: Forward, y: Left, z: Up). uint8 FRAME_RESERVED_14 = 14 # MAV_FRAME_MOCAP_NED - Odometry local coordinate frame of data given by a motion capture system, Z-down (x: North, y: East, z: Down). uint8 FRAME_RESERVED_15 = 15 # MAV_FRAME_MOCAP_ENU - Odometry local coordinate frame of data given by a motion capture system, Z-up (x: East, y: North, z: Up). @@ -38,9 +38,9 @@ uint8 FRAME_RESERVED_16 = 16 # MAV_FRAME_VISION_NED - Odometry local uint8 FRAME_RESERVED_17 = 17 # MAV_FRAME_VISION_ENU - Odometry local coordinate frame of data given by a vision estimation system, Z-up (x: East, y: North, z: Up). uint8 FRAME_RESERVED_18 = 18 # MAV_FRAME_ESTIM_NED - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: North, y: East, z: Down). uint8 FRAME_RESERVED_19 = 19 # MAV_FRAME_ESTIM_ENU - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-up (x: East, y: North, z: Up). -uint8 FRAME_LOCAL_FRD = 20 # Forward, Right, Down coordinate frame. This is a local frame with Z-down and arbitrary F/R alignment (i.e. not aligned with NED/earth frame). -uint8 FRAME_LOCAL_FLU = 21 # Forward, Left, Up coordinate frame. This is a local frame with Z-up and arbitrary F/L alignment (i.e. not aligned with ENU/earth frame). -# [[[end]]] (checksum: 013a057712ce80e0a4bffa7c5e2c05a9) +uint8 FRAME_LOCAL_FRD = 20 # FRD local tangent frame (x: Forward, y: Right, z: Down) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane. +uint8 FRAME_LOCAL_FLU = 21 # FLU local tangent frame (x: Forward, y: Left, z: Up) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane. +# [[[end]]] (checksum: c5ddb537c91e87c4efba8b24c9cde50e) uint8 mav_frame --- diff --git a/test_mavros/CHANGELOG.rst b/test_mavros/CHANGELOG.rst index ef383ebec..25b3b19cd 100644 --- a/test_mavros/CHANGELOG.rst +++ b/test_mavros/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package test_mavros ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.17.0 (2023-09-09) +------------------- +* Merge pull request `#1865 `_ from scoutdi/warnings + Fix / suppress some build warnings +* Suppress warnings from included headers +* Contributors: Morten Fyhn Amundsen, Vladimir Ermakov + 1.16.0 (2023-05-05) ------------------- diff --git a/test_mavros/CMakeLists.txt b/test_mavros/CMakeLists.txt index ec80ddab2..63cfe3a46 100644 --- a/test_mavros/CMakeLists.txt +++ b/test_mavros/CMakeLists.txt @@ -66,6 +66,7 @@ catkin_package( include_directories( include + SYSTEM ${Boost_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIRS} ${catkin_INCLUDE_DIRS} diff --git a/test_mavros/package.xml b/test_mavros/package.xml index 4bfcbbd23..dd813443f 100644 --- a/test_mavros/package.xml +++ b/test_mavros/package.xml @@ -1,7 +1,7 @@ test_mavros - 1.16.0 + 1.17.0 Tests for MAVROS package Vladimir Ermakov