Skip to content

Commit

Permalink
mavros: use mavlink::minimal:: after incompatible changes in mavlink …
Browse files Browse the repository at this point in the history
…package

Incompatible change: mavlink/mavlink#1463

Fix: #1483, mavlink/mavlink#1474
  • Loading branch information
vooon committed Sep 11, 2020
1 parent 89026f9 commit 2702c04
Show file tree
Hide file tree
Showing 8 changed files with 33 additions and 31 deletions.
8 changes: 4 additions & 4 deletions mavros/include/mavros/mavros_uas.h
Original file line number Diff line number Diff line change
Expand Up @@ -67,10 +67,10 @@ namespace mavros {
class UAS {
public:
// common enums used by UAS
using MAV_TYPE = mavlink::common::MAV_TYPE;
using MAV_AUTOPILOT = mavlink::common::MAV_AUTOPILOT;
using MAV_MODE_FLAG = mavlink::common::MAV_MODE_FLAG;
using MAV_STATE = mavlink::common::MAV_STATE;
using MAV_TYPE = mavlink::minimal::MAV_TYPE;
using MAV_AUTOPILOT = mavlink::minimal::MAV_AUTOPILOT;
using MAV_MODE_FLAG = mavlink::minimal::MAV_MODE_FLAG;
using MAV_STATE = mavlink::minimal::MAV_STATE;
using MAV_CAP = mavlink::common::MAV_PROTOCOL_CAPABILITY;
using timesync_mode = utils::timesync_mode;

Expand Down
10 changes: 5 additions & 5 deletions mavros/include/mavros/utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -67,10 +67,10 @@ std::string to_string(timesync_mode e);
*/
std::string to_string(mavlink::common::MAV_SENSOR_ORIENTATION e);

std::string to_string(mavlink::common::MAV_AUTOPILOT e);
std::string to_string(mavlink::common::MAV_TYPE e);
std::string to_string(mavlink::common::MAV_STATE e);
std::string to_string(mavlink::common::MAV_COMPONENT e);
std::string to_string(mavlink::minimal::MAV_AUTOPILOT e);
std::string to_string(mavlink::minimal::MAV_TYPE e);
std::string to_string(mavlink::minimal::MAV_STATE e);
std::string to_string(mavlink::minimal::MAV_COMPONENT e);
std::string to_string(mavlink::common::MAV_ESTIMATOR_TYPE e);
std::string to_string(mavlink::common::ADSB_ALTITUDE_TYPE e);
std::string to_string(mavlink::common::ADSB_EMITTER_TYPE e);
Expand Down Expand Up @@ -111,7 +111,7 @@ mavlink::common::MAV_FRAME mav_frame_from_str(const std::string &mav_frame);
/**
* @brief Retreive MAV_TYPE from name
*/
mavlink::common::MAV_TYPE mav_type_from_str(const std::string &mav_type);
mavlink::minimal::MAV_TYPE mav_type_from_str(const std::string &mav_type);

/**
* @brief Retrieve landing target type from alias name
Expand Down
8 changes: 4 additions & 4 deletions mavros/src/lib/enum_to_string.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,10 +21,10 @@

namespace mavros {
namespace utils {
using mavlink::common::MAV_AUTOPILOT;
using mavlink::common::MAV_TYPE;
using mavlink::common::MAV_STATE;
using mavlink::common::MAV_COMPONENT;
using mavlink::minimal::MAV_AUTOPILOT;
using mavlink::minimal::MAV_TYPE;
using mavlink::minimal::MAV_STATE;
using mavlink::minimal::MAV_COMPONENT;
using mavlink::common::MAV_ESTIMATOR_TYPE;
using mavlink::common::ADSB_ALTITUDE_TYPE;
using mavlink::common::ADSB_EMITTER_TYPE;
Expand Down
2 changes: 1 addition & 1 deletion mavros/src/lib/mavros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,7 @@ MavRos::MavRos() :
plugin_route_cb(msg, framing);

if (gcs_link) {
if (this->gcs_quiet_mode && msg->msgid != mavlink::common::msg::HEARTBEAT::MSG_ID &&
if (this->gcs_quiet_mode && msg->msgid != mavlink::minimal::msg::HEARTBEAT::MSG_ID &&
(ros::Time::now() - this->last_message_received_from_gcs > this->conn_timeout)) {
return;
}
Expand Down
2 changes: 1 addition & 1 deletion mavros/src/plugins/command.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -233,7 +233,7 @@ class CommandPlugin : public plugin::PluginBase {
template<typename MsgT>
inline void set_target(MsgT &cmd, bool broadcast)
{
using mavlink::common::MAV_COMPONENT;
using mavlink::minimal::MAV_COMPONENT;

const uint8_t tgt_sys_id = (broadcast) ? 0 : m_uas->get_tgt_system();
const uint8_t tgt_comp_id = (broadcast) ? 0 :
Expand Down
2 changes: 1 addition & 1 deletion mavros/src/plugins/dummy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ class DummyPlugin : public plugin::PluginBase {
private:
ros::NodeHandle nh;

void handle_heartbeat(const mavlink::mavlink_message_t *msg, mavlink::common::msg::HEARTBEAT &hb) {
void handle_heartbeat(const mavlink::mavlink_message_t *msg, mavlink::minimal::msg::HEARTBEAT &hb) {
ROS_INFO_STREAM_NAMED("dummy", "Dummy::handle_heartbeat: " << hb.to_yaml());
}

Expand Down
16 changes: 8 additions & 8 deletions mavros/src/plugins/sys_status.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,9 +38,9 @@ using BatteryMsg = mavros_msgs::BatteryStatus;

namespace mavros {
namespace std_plugins {
using mavlink::common::MAV_TYPE;
using mavlink::common::MAV_AUTOPILOT;
using mavlink::common::MAV_STATE;
using mavlink::minimal::MAV_TYPE;
using mavlink::minimal::MAV_AUTOPILOT;
using mavlink::minimal::MAV_STATE;
using utils::enum_value;

/**
Expand Down Expand Up @@ -688,9 +688,9 @@ class SystemStatusPlugin : public plugin::PluginBase

/* -*- message handlers -*- */

void handle_heartbeat(const mavlink::mavlink_message_t *msg, mavlink::common::msg::HEARTBEAT &hb)
void handle_heartbeat(const mavlink::mavlink_message_t *msg, mavlink::minimal::msg::HEARTBEAT &hb)
{
using mavlink::common::MAV_MODE_FLAG;
using mavlink::minimal::MAV_MODE_FLAG;

// Store generic info of all heartbeats seen
auto it = find_or_create_vehicle_info(msg->sysid, msg->compid);
Expand Down Expand Up @@ -952,7 +952,7 @@ class SystemStatusPlugin : public plugin::PluginBase
est_status_msg->gps_glitch_status_flag = !!(status.flags & enum_value(ESF::GPS_GLITCH));
est_status_msg->accel_error_status_flag = !!(status.flags & enum_value(ESF::ACCEL_ERROR));
// [[[end]]] (checksum: 7828381ee4002ea6b61a8f528ae4d12d)

estimator_status_pub.publish(est_status_msg);
}

Expand All @@ -967,7 +967,7 @@ class SystemStatusPlugin : public plugin::PluginBase
{
using mavlink::common::MAV_MODE;

mavlink::common::msg::HEARTBEAT hb {};
mavlink::minimal::msg::HEARTBEAT hb {};

hb.type = enum_value(conn_heartbeat_mav_type); //! @todo patch PX4 so it can also handle this type as datalink
hb.autopilot = enum_value(MAV_AUTOPILOT::INVALID);
Expand Down Expand Up @@ -1086,7 +1086,7 @@ class SystemStatusPlugin : public plugin::PluginBase
bool set_mode_cb(mavros_msgs::SetMode::Request &req,
mavros_msgs::SetMode::Response &res)
{
using mavlink::common::MAV_MODE_FLAG;
using mavlink::minimal::MAV_MODE_FLAG;

uint8_t base_mode = req.base_mode;
uint32_t custom_mode = 0;
Expand Down
16 changes: 9 additions & 7 deletions mavros_extras/src/plugins/companion_process_status.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,9 +22,11 @@ namespace mavros {
namespace extra_plugins {

//! Mavlink enumerations
using mavlink::common::MAV_TYPE;
using mavlink::common::MAV_STATE;
using mavlink::common::MAV_COMPONENT;
using mavlink::minimal::MAV_TYPE;
using mavlink::minimal::MAV_STATE;
using mavlink::minimal::MAV_COMPONENT;
using mavlink::minimal::MAV_AUTOPILOT;
using mavlink::minimal::MAV_MODE_FLAG;
using utils::enum_value;

/**
Expand Down Expand Up @@ -63,11 +65,11 @@ class CompanionProcessStatusPlugin : public plugin::PluginBase {
*/
void status_cb(const mavros_msgs::CompanionProcessStatus::ConstPtr &req)
{
mavlink::common::msg::HEARTBEAT heartbeat {};
mavlink::minimal::msg::HEARTBEAT heartbeat {};

heartbeat.type = enum_value(mavlink::common::MAV_TYPE::ONBOARD_CONTROLLER);
heartbeat.autopilot = enum_value(mavlink::common::MAV_AUTOPILOT::PX4);
heartbeat.base_mode = enum_value(mavlink::common::MAV_MODE_FLAG::CUSTOM_MODE_ENABLED);
heartbeat.type = enum_value(MAV_TYPE::ONBOARD_CONTROLLER);
heartbeat.autopilot = enum_value(MAV_AUTOPILOT::PX4);
heartbeat.base_mode = enum_value(MAV_MODE_FLAG::CUSTOM_MODE_ENABLED);
heartbeat.system_status = req->state; //enum="MAV_STATE" System status flag

ROS_DEBUG_STREAM_NAMED("companion_process_status", "companion process component id: " <<
Expand Down

0 comments on commit 2702c04

Please sign in to comment.