Skip to content

Commit

Permalink
Imported upstream version '1.18.0' of 'upstream'
Browse files Browse the repository at this point in the history
  • Loading branch information
vooon committed Mar 3, 2024
1 parent a22bf59 commit eae036f
Show file tree
Hide file tree
Showing 15 changed files with 82 additions and 12 deletions.
3 changes: 3 additions & 0 deletions libmavconn/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package libmavconn
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

1.18.0 (2024-03-03)
-------------------

1.17.0 (2023-09-09)
-------------------
* Merge pull request `#1865 <https://github.com/mavlink/mavros/issues/1865>`_ from scoutdi/warnings
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.17.0</version>
<version>1.18.0</version>
<description>
MAVLink communication library.
This library provide unified connection handling classes
Expand Down
6 changes: 6 additions & 0 deletions mavros/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,12 @@
Changelog for package mavros
^^^^^^^^^^^^^^^^^^^^^^^^^^^^

1.18.0 (2024-03-03)
-------------------
* sys_status.cpp: improve timeout code
* sys_status.cpp: Add a SYS_STATUS message publisher
* Contributors: Dr.-Ing. Amilcar do Carmo Lucas

1.17.0 (2023-09-09)
-------------------
* cog: regenerate all
Expand Down
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.17.0</version>
<version>1.18.0</version>
<description>
MAVROS -- MAVLink extendable communication node for ROS
with proxy for Ground Control Station.
Expand Down
28 changes: 26 additions & 2 deletions mavros/src/plugins/sys_status.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
#include <mavros_msgs/VehicleInfo.h>
#include <mavros_msgs/VehicleInfoGet.h>
#include <mavros_msgs/MessageInterval.h>
#include <mavros_msgs/SysStatus.h>


#ifdef HAVE_SENSOR_MSGS_BATTERYSTATE_MSG
Expand Down Expand Up @@ -394,11 +395,12 @@ class MemInfo : public diagnostic_updater::DiagnosticTask
ros::Time last_rcd_;
last_rcd_.fromNSec(last_rcd.load());
constexpr int timeout = 10.0; // seconds
const ros::Duration timeout_duration = ros::Duration(timeout);

// summarize the results
if (last_rcd_.isZero()) {
stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Not initialised");
} else if (ros::Time::now().toSec() - last_rcd_.toSec() > timeout) {
} else if (ros::Time::now() - last_rcd_ > timeout_duration) {
stat.summary(diagnostic_msgs::DiagnosticStatus::STALE, "Not received for more than " + std::to_string(timeout) + "s");
} else {
if (freemem == UINT32_MAX)
Expand Down Expand Up @@ -444,9 +446,10 @@ class HwStatus : public diagnostic_updater::DiagnosticTask
{
std::lock_guard<std::mutex> lock(mutex);
constexpr int timeout = 10.0; // seconds
const ros::Duration timeout_duration = ros::Duration(timeout);
if (last_rcd.isZero()) {
stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Not initialised");
} else if (ros::Time::now().toSec() - last_rcd.toSec() > timeout) {
} else if (ros::Time::now() - last_rcd > timeout_duration) {
stat.summary(diagnostic_msgs::DiagnosticStatus::STALE, "Not received for more than " + std::to_string(timeout) + "s");
} else {
if (vcc < 0)
Expand Down Expand Up @@ -556,6 +559,7 @@ class SystemStatusPlugin : public plugin::PluginBase
batt_pub = nh.advertise<BatteryMsg>("battery", 10);
estimator_status_pub = nh.advertise<mavros_msgs::EstimatorStatus>("estimator_status", 10);
statustext_pub = nh.advertise<mavros_msgs::StatusText>("statustext/recv", 10);
sys_status_pub = nh.advertise<mavros_msgs::SysStatus>("sys_status", 10);
statustext_sub = nh.subscribe("statustext/send", 10, &SystemStatusPlugin::statustext_cb, this);
rate_srv = nh.advertiseService("set_stream_rate", &SystemStatusPlugin::set_rate_cb, this);
mode_srv = nh.advertiseService("set_mode", &SystemStatusPlugin::set_mode_cb, this);
Expand Down Expand Up @@ -598,6 +602,7 @@ class SystemStatusPlugin : public plugin::PluginBase
ros::Publisher batt_pub;
ros::Publisher estimator_status_pub;
ros::Publisher statustext_pub;
ros::Publisher sys_status_pub;
ros::Subscriber statustext_sub;
ros::ServiceServer rate_srv;
ros::ServiceServer mode_srv;
Expand Down Expand Up @@ -832,6 +837,25 @@ class SystemStatusPlugin : public plugin::PluginBase

sys_diag.set(stat);

mavros_msgs::SysStatus sys_status;
sys_status.header.stamp = ros::Time::now();
sys_status.sensors_present = stat.onboard_control_sensors_present;
sys_status.sensors_enabled = stat.onboard_control_sensors_enabled;
sys_status.sensors_health = stat.onboard_control_sensors_health;

sys_status.load = stat.load;
sys_status.voltage_battery = stat.voltage_battery;
sys_status.current_battery = stat.current_battery;
sys_status.battery_remaining = stat.battery_remaining;
sys_status.drop_rate_comm = stat.drop_rate_comm;
sys_status.errors_comm = stat.errors_comm;
sys_status.errors_count1 = stat.errors_count1;
sys_status.errors_count2 = stat.errors_count2;
sys_status.errors_count3 = stat.errors_count3;
sys_status.errors_count4 = stat.errors_count4;

sys_status_pub.publish(sys_status);

if (has_battery_status0)
return;

Expand Down
9 changes: 9 additions & 0 deletions mavros_extras/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,15 @@
Changelog for package mavros_extras
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

1.18.0 (2024-03-03)
-------------------
* [camera plugin] Fix image_index and capture_result not properly filled
* Fix missing semi-colon
* GPS_STATUS Plugin: Fill in available messages for ROS1 legacy
Filled in available fields in GPS_RAW_INT & GPS2_RAW messages
p.s. seems GPS2_RAW more complete than original GPS_RAW_INT
* Contributors: Beniamino Pozzan, Seunghwan Jo

1.17.0 (2023-09-09)
-------------------
* Merge pull request `#1865 <https://github.com/mavlink/mavros/issues/1865>`_ from scoutdi/warnings
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.17.0</version>
<version>1.18.0</version>
<description>
Extra nodes and plugins for <a href="http://wiki.ros.org/mavros">MAVROS</a>.
</description>
Expand Down
2 changes: 2 additions & 0 deletions mavros_extras/src/plugins/camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,8 @@ class CameraPlugin : public plugin::PluginBase {
ic->relative_alt = mo.relative_alt / 1E3;
auto q = ftf::mavlink_to_quaternion(mo.q);
tf::quaternionEigenToMsg(q, ic->orientation);
ic->image_index = mo.image_index;
ic->capture_result = mo.capture_result;
ic->file_url = mavlink::to_string(mo.file_url);

camera_image_captured_pub.publish(ic);
Expand Down
12 changes: 7 additions & 5 deletions mavros_extras/src/plugins/gps_status.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,7 @@ class GpsStatusPlugin : public plugin::PluginBase {
ros_msg->hdg_acc = mav_msg.hdg_acc;
ros_msg->dgps_numch = UINT8_MAX; // information not available in GPS_RAW_INT mavlink message
ros_msg->dgps_age = UINT32_MAX;// information not available in GPS_RAW_INT mavlink message
ros_msg->yaw = mav_msg.yaw;

gps1_raw_pub.publish(ros_msg);
}
Expand All @@ -103,13 +104,14 @@ class GpsStatusPlugin : public plugin::PluginBase {
ros_msg->vel = mav_msg.vel;
ros_msg->cog = mav_msg.cog;
ros_msg->satellites_visible = mav_msg.satellites_visible;
ros_msg->alt_ellipsoid = INT32_MAX; // information not available in GPS2_RAW mavlink message
ros_msg->h_acc = UINT32_MAX;// information not available in GPS2_RAW mavlink message
ros_msg->v_acc = UINT32_MAX;// information not available in GPS2_RAW mavlink message
ros_msg->vel_acc = UINT32_MAX;// information not available in GPS2_RAW mavlink message
ros_msg->hdg_acc = UINT32_MAX;// information not available in GPS2_RAW mavlink message
ros_msg->alt_ellipsoid = mav_msg.alt_ellipsoid;
ros_msg->h_acc = mav_msg.h_acc;
ros_msg->v_acc = mav_msg.v_acc;
ros_msg->vel_acc = mav_msg.vel_acc;
ros_msg->hdg_acc = mav_msg.hdg_acc;
ros_msg->dgps_numch = mav_msg.dgps_numch;
ros_msg->dgps_age = mav_msg.dgps_age;
ros_msg->yaw = mav_msg.yaw;

gps2_raw_pub.publish(ros_msg);
}
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.18.0 (2024-03-03)
-------------------
* sys_status.cpp: Add a SYS_STATUS message publisher
* Contributors: Dr.-Ing. Amilcar do Carmo Lucas

1.17.0 (2023-09-09)
-------------------
* cog: regenerate all
Expand Down
1 change: 1 addition & 0 deletions mavros_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,7 @@ add_message_files(
RTKBaseline.msg
State.msg
StatusText.msg
SysStatus.msg
TerrainReport.msg
Thrust.msg
TimesyncStatus.msg
Expand Down
15 changes: 15 additions & 0 deletions mavros_msgs/msg/SysStatus.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
std_msgs/Header header

uint32 sensors_present
uint32 sensors_enabled
uint32 sensors_health
uint16 load
uint16 voltage_battery
int16 current_battery
int8 battery_remaining
uint16 drop_rate_comm
uint16 errors_comm
uint16 errors_count1
uint16 errors_count2
uint16 errors_count3
uint16 errors_count4
2 changes: 1 addition & 1 deletion mavros_msgs/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_msgs</name>
<version>1.17.0</version>
<version>1.18.0</version>
<description>
mavros_msgs defines messages for <a href="http://wiki.ros.org/mavros">MAVROS</a>.
</description>
Expand Down
3 changes: 3 additions & 0 deletions test_mavros/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package test_mavros
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

1.18.0 (2024-03-03)
-------------------

1.17.0 (2023-09-09)
-------------------
* Merge pull request `#1865 <https://github.com/mavlink/mavros/issues/1865>`_ from scoutdi/warnings
Expand Down
2 changes: 1 addition & 1 deletion test_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>test_mavros</name>
<version>1.17.0</version>
<version>1.18.0</version>
<description>Tests for MAVROS package</description>

<maintainer email="[email protected]">Vladimir Ermakov</maintainer>
Expand Down

0 comments on commit eae036f

Please sign in to comment.