Skip to content

Commit

Permalink
Imported upstream version '1.17.0' of 'upstream'
Browse files Browse the repository at this point in the history
  • Loading branch information
vooon committed Sep 9, 2023
1 parent 5fd29da commit a22bf59
Show file tree
Hide file tree
Showing 23 changed files with 137 additions and 58 deletions.
7 changes: 7 additions & 0 deletions libmavconn/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,13 @@
Changelog for package libmavconn
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

1.17.0 (2023-09-09)
-------------------
* Merge pull request `#1865 <https://github.com/mavlink/mavros/issues/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)
-------------------

Expand Down
1 change: 1 addition & 0 deletions libmavconn/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@ catkin_package(

include_directories(
include
SYSTEM
${CMAKE_CURRENT_BINARY_DIR}/catkin_generated/include
${Boost_INCLUDE_DIRS}
${mavlink_INCLUDE_DIRS}
Expand Down
2 changes: 1 addition & 1 deletion libmavconn/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>libmavconn</name>
<version>1.16.0</version>
<version>1.17.0</version>
<description>
MAVLink communication library.
This library provide unified connection handling classes
Expand Down
17 changes: 17 additions & 0 deletions mavros/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -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 <https://github.com/mavlink/mavros/issues/1892>`_)
* Update map origin with home position
* Uncrustify
* Revert "Uncrustify"
This reverts commit f1387c79c7670cc241986586436e3da43842e877.
* Change to relative topic
---------
Co-authored-by: Natalia Molina <[email protected]>
* Merge pull request `#1865 <https://github.com/mavlink/mavros/issues/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 <https://github.com/mavlink/mavros/issues/1829>`_ from snwu1996/latched_gp_origin_pub
Expand Down
1 change: 1 addition & 0 deletions mavros/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -87,6 +87,7 @@ catkin_package(

include_directories(
include
SYSTEM
${catkin_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
${mavlink_INCLUDE_DIRS}
Expand Down
2 changes: 1 addition & 1 deletion mavros/include/mavros/mavlink_diag.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,5 +40,5 @@ class MavlinkDiag : public diagnostic_updater::DiagnosticTask
unsigned int last_drop_count;
std::atomic<bool> is_connected;
};
}; // namespace mavros
} // namespace mavros

2 changes: 1 addition & 1 deletion mavros/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>mavros</name>
<version>1.16.0</version>
<version>1.17.0</version>
<description>
MAVROS -- MAVLink extendable communication node for ROS
with proxy for Ground Control Station.
Expand Down
60 changes: 41 additions & 19 deletions mavros/src/lib/enum_to_string.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,7 @@ using mavlink::common::LANDING_TARGET_TYPE;
// to_string_outl(ename)
// ]]]
//! MAV_AUTOPILOT values
static const std::array<const std::string, 20> mav_autopilot_strings{{
static const std::array<const std::string, 21> 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
Expand All @@ -126,6 +126,7 @@ static const std::array<const std::string, 20> 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)
Expand All @@ -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'
Expand All @@ -153,7 +154,7 @@ std::string to_string(MAV_AUTOPILOT e)
// to_string_outl(ename)
// ]]]
//! MAV_TYPE values
static const std::array<const std::string, 36> mav_type_strings{{
static const std::array<const std::string, 43> mav_type_strings{{
/* 0 */ "Generic micro air vehicle", // Generic micro air vehicle
/* 1 */ "Fixed wing aircraft", // Fixed wing aircraft.
/* 2 */ "Quadrotor", // Quadrotor
Expand Down Expand Up @@ -190,6 +191,13 @@ static const std::array<const std::string, 36> 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)
Expand All @@ -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<const std::string, 36> mav_type_names{{
static const std::array<const std::string, 43> mav_type_names{{
/* 0 */ "GENERIC", // Generic micro air vehicle
/* 1 */ "FIXED_WING", // Fixed wing aircraft.
/* 2 */ "QUADROTOR", // Quadrotor
Expand Down Expand Up @@ -244,6 +252,13 @@ static const std::array<const std::string, 36> 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)
Expand All @@ -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'
Expand Down Expand Up @@ -499,27 +514,27 @@ std::string to_string(MAV_MISSION_RESULT e)
//! MAV_FRAME values
static const std::array<const std::string, 22> 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).
/* 16 */ "RESERVED_16", // MAV_FRAME_VISION_NED - Odometry local coordinate frame of data given by a vision estimation system, Z-down (x: North, y: East, z: Down).
/* 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)
Expand All @@ -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'
Expand Down Expand Up @@ -653,13 +668,20 @@ static const std::unordered_map<typename std::underlying_type<MAV_COMPONENT>::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.
Expand All @@ -677,7 +699,7 @@ static const std::unordered_map<typename std::underlying_type<MAV_COMPONENT>::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)
{
Expand Down
2 changes: 1 addition & 1 deletion mavros/src/lib/mavlink_diag.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
{
Expand Down
4 changes: 3 additions & 1 deletion mavros/src/plugins/global_position.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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),
Expand Down Expand Up @@ -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<geometry_msgs::PoseStamped>("gp_lp_offset", 10);
Expand All @@ -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;
Expand Down
8 changes: 8 additions & 0 deletions mavros_extras/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,14 @@
Changelog for package mavros_extras
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

1.17.0 (2023-09-09)
-------------------
* Merge pull request `#1865 <https://github.com/mavlink/mavros/issues/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 <https://github.com/mavlink/mavros/issues/1817>`_ from lucasw/pluginlib_hpp
Expand Down
1 change: 1 addition & 0 deletions mavros_extras/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,7 @@ catkin_package(
###########

include_directories(
SYSTEM
${catkin_INCLUDE_DIRS}
${mavlink_INCLUDE_DIRS}
)
Expand Down
2 changes: 1 addition & 1 deletion mavros_extras/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>mavros_extras</name>
<version>1.16.0</version>
<version>1.17.0</version>
<description>
Extra nodes and plugins for <a href="http://wiki.ros.org/mavros">MAVROS</a>.
</description>
Expand Down
8 changes: 4 additions & 4 deletions mavros_extras/src/plugins/landing_target.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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")
{ }

Expand Down
4 changes: 2 additions & 2 deletions mavros_extras/src/plugins/mount_control.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion mavros_extras/src/plugins/wheel_odometry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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),
Expand Down
5 changes: 5 additions & 0 deletions mavros_msgs/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -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)
-------------------

Expand Down
Loading

0 comments on commit a22bf59

Please sign in to comment.