Skip to content

Commit

Permalink
Plugins: system_status change status field to system_status
Browse files Browse the repository at this point in the history
Add comment to State.msg for system_status enum
  • Loading branch information
khancyr authored and vooon committed Dec 14, 2016
1 parent 3b22ac0 commit d94c15c
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 3 deletions.
4 changes: 2 additions & 2 deletions mavros/src/plugins/sys_status.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -623,7 +623,7 @@ class SystemStatusPlugin : public plugin::PluginBase
state_msg->armed = false;
state_msg->guided = false;
state_msg->mode = "";
state_msg->status = enum_value(MAV_STATE::UNINIT);
state_msg->system_status = enum_value(MAV_STATE::UNINIT);

state_pub.publish(state_msg);
}
Expand Down Expand Up @@ -652,7 +652,7 @@ class SystemStatusPlugin : public plugin::PluginBase
state_msg->armed = hb.base_mode & enum_value(MAV_MODE_FLAG::SAFETY_ARMED);
state_msg->guided = hb.base_mode & enum_value(MAV_MODE_FLAG::GUIDED_ENABLED);
state_msg->mode = m_uas->str_mode_v10(hb.base_mode, hb.custom_mode);
state_msg->status = hb.system_status;
state_msg->system_status = hb.system_status;

state_pub.publish(state_msg);
hb_diag.tick(hb.type, hb.autopilot, state_msg->mode, hb.system_status);
Expand Down
6 changes: 5 additions & 1 deletion mavros_msgs/msg/State.msg
Original file line number Diff line number Diff line change
Expand Up @@ -2,10 +2,14 @@
#
# Known modes listed here:
# http://wiki.ros.org/mavros/CustomModes
#
# For system_status values
# see http://mavlink.org/messages/common MAV_STATE
#

std_msgs/Header header
bool connected
bool armed
bool guided
string mode
uint8 status
uint8 system_status

0 comments on commit d94c15c

Please sign in to comment.