aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink/mavlink_messages.cpp
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2015-01-28 07:58:42 +0100
committerThomas Gubler <thomasgubler@gmail.com>2015-01-28 16:31:41 +0100
commit2d124852c1881d5b993b3c2ec9f7a79e1e03da1b (patch)
treee8ef94b9255f78418d4da12d206b024cb2abfcff /src/modules/mavlink/mavlink_messages.cpp
parent01835a51a8a3a0b0f7e7362cdc25475bd029a9a8 (diff)
downloadpx4-firmware-2d124852c1881d5b993b3c2ec9f7a79e1e03da1b.tar.gz
px4-firmware-2d124852c1881d5b993b3c2ec9f7a79e1e03da1b.tar.bz2
px4-firmware-2d124852c1881d5b993b3c2ec9f7a79e1e03da1b.zip
propagate uorb contants change through all modules/drivers
Diffstat (limited to 'src/modules/mavlink/mavlink_messages.cpp')
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp56
1 files changed, 28 insertions, 28 deletions
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index 6765100c7..6642fb2ac 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -103,13 +103,13 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set
*mavlink_custom_mode = 0;
/* HIL */
- if (status->hil_state == HIL_STATE_ON) {
+ if (status->hil_state == vehicle_status_s::HIL_STATE_ON) {
*mavlink_base_mode |= MAV_MODE_FLAG_HIL_ENABLED;
}
/* arming state */
- if (status->arming_state == ARMING_STATE_ARMED
- || status->arming_state == ARMING_STATE_ARMED_ERROR) {
+ if (status->arming_state == vehicle_status_s::ARMING_STATE_ARMED
+ || status->arming_state == vehicle_status_s::ARMING_STATE_ARMED_ERROR) {
*mavlink_base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
}
@@ -121,31 +121,31 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set
switch (status->nav_state) {
- case NAVIGATION_STATE_MANUAL:
+ case vehicle_status_s::NAVIGATION_STATE_MANUAL:
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED
| (status->is_rotary_wing ? MAV_MODE_FLAG_STABILIZE_ENABLED : 0);
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_MANUAL;
break;
- case NAVIGATION_STATE_ACRO:
+ case vehicle_status_s::NAVIGATION_STATE_ACRO:
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_ACRO;
break;
- case NAVIGATION_STATE_ALTCTL:
+ case vehicle_status_s::NAVIGATION_STATE_ALTCTL:
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED
| MAV_MODE_FLAG_STABILIZE_ENABLED;
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_ALTCTL;
break;
- case NAVIGATION_STATE_POSCTL:
+ case vehicle_status_s::NAVIGATION_STATE_POSCTL:
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED
| MAV_MODE_FLAG_STABILIZE_ENABLED
| MAV_MODE_FLAG_GUIDED_ENABLED;
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_POSCTL;
break;
- case NAVIGATION_STATE_AUTO_MISSION:
+ case vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION:
*mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED
| MAV_MODE_FLAG_STABILIZE_ENABLED
| MAV_MODE_FLAG_GUIDED_ENABLED;
@@ -153,7 +153,7 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set
custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_MISSION;
break;
- case NAVIGATION_STATE_AUTO_LOITER:
+ case vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER:
*mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED
| MAV_MODE_FLAG_STABILIZE_ENABLED
| MAV_MODE_FLAG_GUIDED_ENABLED;
@@ -161,9 +161,9 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set
custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_LOITER;
break;
- case NAVIGATION_STATE_AUTO_RTL:
+ case vehicle_status_s::NAVIGATION_STATE_AUTO_RTL:
/* fallthrough */
- case NAVIGATION_STATE_AUTO_RCRECOVER:
+ case vehicle_status_s::NAVIGATION_STATE_AUTO_RCRECOVER:
*mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED
| MAV_MODE_FLAG_STABILIZE_ENABLED
| MAV_MODE_FLAG_GUIDED_ENABLED;
@@ -171,11 +171,11 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set
custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_RTL;
break;
- case NAVIGATION_STATE_LAND:
- case NAVIGATION_STATE_AUTO_LANDENGFAIL:
- case NAVIGATION_STATE_AUTO_LANDGPSFAIL:
+ case vehicle_status_s::NAVIGATION_STATE_LAND:
+ case vehicle_status_s::NAVIGATION_STATE_AUTO_LANDENGFAIL:
+ case vehicle_status_s::NAVIGATION_STATE_AUTO_LANDGPSFAIL:
/* fallthrough */
- case NAVIGATION_STATE_DESCEND:
+ case vehicle_status_s::NAVIGATION_STATE_DESCEND:
*mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED
| MAV_MODE_FLAG_STABILIZE_ENABLED
| MAV_MODE_FLAG_GUIDED_ENABLED;
@@ -183,7 +183,7 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set
custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_LAND;
break;
- case NAVIGATION_STATE_AUTO_RTGS:
+ case vehicle_status_s::NAVIGATION_STATE_AUTO_RTGS:
*mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED
| MAV_MODE_FLAG_STABILIZE_ENABLED
| MAV_MODE_FLAG_GUIDED_ENABLED;
@@ -191,19 +191,19 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set
custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_RTGS;
break;
- case NAVIGATION_STATE_TERMINATION:
+ case vehicle_status_s::NAVIGATION_STATE_TERMINATION:
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_MANUAL;
break;
- case NAVIGATION_STATE_OFFBOARD:
+ case vehicle_status_s::NAVIGATION_STATE_OFFBOARD:
*mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED
| MAV_MODE_FLAG_STABILIZE_ENABLED
| MAV_MODE_FLAG_GUIDED_ENABLED;
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_OFFBOARD;
break;
- case NAVIGATION_STATE_MAX:
+ case vehicle_status_s::NAVIGATION_STATE_MAX:
/* this is an unused case, ignore */
break;
@@ -212,21 +212,21 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set
*mavlink_custom_mode = custom_mode.data;
/* set system state */
- if (status->arming_state == ARMING_STATE_INIT
- || status->arming_state == ARMING_STATE_IN_AIR_RESTORE
- || status->arming_state == ARMING_STATE_STANDBY_ERROR) { // TODO review
+ if (status->arming_state == vehicle_status_s::ARMING_STATE_INIT
+ || status->arming_state == vehicle_status_s::ARMING_STATE_IN_AIR_RESTORE
+ || status->arming_state == vehicle_status_s::ARMING_STATE_STANDBY_ERROR) { // TODO review
*mavlink_state = MAV_STATE_UNINIT;
- } else if (status->arming_state == ARMING_STATE_ARMED) {
+ } else if (status->arming_state == vehicle_status_s::ARMING_STATE_ARMED) {
*mavlink_state = MAV_STATE_ACTIVE;
- } else if (status->arming_state == ARMING_STATE_ARMED_ERROR) {
+ } else if (status->arming_state == vehicle_status_s::ARMING_STATE_ARMED_ERROR) {
*mavlink_state = MAV_STATE_CRITICAL;
- } else if (status->arming_state == ARMING_STATE_STANDBY) {
+ } else if (status->arming_state == vehicle_status_s::ARMING_STATE_STANDBY) {
*mavlink_state = MAV_STATE_STANDBY;
- } else if (status->arming_state == ARMING_STATE_REBOOT) {
+ } else if (status->arming_state == vehicle_status_s::ARMING_STATE_REBOOT) {
*mavlink_state = MAV_STATE_POWEROFF;
} else {
@@ -1438,7 +1438,7 @@ protected:
updated |= _pos_sp_triplet_sub->update(&_pos_sp_triplet_time, &pos_sp_triplet);
updated |= _status_sub->update(&_status_time, &status);
- if (updated && (status.arming_state == ARMING_STATE_ARMED)) {
+ if (updated && (status.arming_state == vehicle_status_s::ARMING_STATE_ARMED)) {
/* translate the current syste state to mavlink state and mode */
uint8_t mavlink_state;
uint8_t mavlink_base_mode;
@@ -2205,7 +2205,7 @@ protected:
msg.param2 = 0;
msg.param3 = 0;
/* set camera capture ON/OFF depending on arming state */
- msg.param4 = (status.arming_state == ARMING_STATE_ARMED || status.arming_state == ARMING_STATE_ARMED_ERROR) ? 1 : 0;
+ msg.param4 = (status.arming_state == vehicle_status_s::ARMING_STATE_ARMED || status.arming_state == vehicle_status_s::ARMING_STATE_ARMED_ERROR) ? 1 : 0;
msg.param5 = 0;
msg.param6 = 0;
msg.param7 = 0;