aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink
diff options
context:
space:
mode:
authorTrent Lukaczyk <aerialhedgehog@gmail.com>2015-02-05 20:19:04 -0800
committerTrent Lukaczyk <aerialhedgehog@gmail.com>2015-02-05 20:19:04 -0800
commit531eaa231486c6af46394f6842d420447cb0ee0e (patch)
treee7a90d8c50d700a2b7aff05c5a545162810d4967 /src/modules/mavlink
parent6798aee13a5bb885966960cdba6ab57b14278ab0 (diff)
parent7e6198b3dd517e1158431c8344c5912a6c28b363 (diff)
downloadpx4-firmware-531eaa231486c6af46394f6842d420447cb0ee0e.tar.gz
px4-firmware-531eaa231486c6af46394f6842d420447cb0ee0e.tar.bz2
px4-firmware-531eaa231486c6af46394f6842d420447cb0ee0e.zip
Merge remote-tracking branch 'upstream/master'
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r--src/modules/mavlink/mavlink_main.cpp2
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp56
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp8
3 files changed, 33 insertions, 33 deletions
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index 8eeeb5bd7..899a0d4a6 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -1431,7 +1431,7 @@ Mavlink::task_main(int argc, char *argv[])
if (status_sub->update(&status_time, &status)) {
/* switch HIL mode if required */
- set_hil_enabled(status.hil_state == HIL_STATE_ON);
+ set_hil_enabled(status.hil_state == vehicle_status_s::HIL_STATE_ON);
}
/* check for requested subscriptions */
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index 4a095a765..be7d91c65 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 {
@@ -1431,7 +1431,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;
@@ -2198,7 +2198,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;
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 16d0422c7..06153fdac 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -616,7 +616,7 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t
pos_sp_triplet.previous.valid = false;
pos_sp_triplet.next.valid = false;
pos_sp_triplet.current.valid = true;
- pos_sp_triplet.current.type = SETPOINT_TYPE_POSITION; //XXX support others
+ pos_sp_triplet.current.type = position_setpoint_s::SETPOINT_TYPE_POSITION; //XXX support others
/* set the local pos values if the setpoint type is 'local pos' and none
* of the local pos fields is set to 'ignore' */
@@ -798,7 +798,7 @@ MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg)
att_sp.timestamp = hrt_absolute_time();
mavlink_quaternion_to_euler(set_attitude_target.q,
&att_sp.roll_body, &att_sp.pitch_body, &att_sp.yaw_body);
- mavlink_quaternion_to_dcm(set_attitude_target.q, att_sp.R_body);
+ mavlink_quaternion_to_dcm(set_attitude_target.q, (float(*)[3])att_sp.R_body);
att_sp.R_valid = true;
att_sp.thrust = set_attitude_target.thrust;
memcpy(att_sp.q_d, set_attitude_target.q, sizeof(att_sp.q_d));
@@ -985,10 +985,10 @@ MavlinkReceiver::handle_message_timesync(mavlink_message_t *msg)
} else if (tsync.tc1 > 0) {
- int64_t offset_ns = (tsync.ts1 + now_ns - tsync.tc1*2)/2 ;
+ int64_t offset_ns = (tsync.ts1 + now_ns - tsync.tc1*2)/2 ;
int64_t dt = _time_offset - offset_ns;
- if (dt > 10000000LL || dt < -10000000LL) { // 10 millisecond skew
+ if (dt > 10000000LL || dt < -10000000LL) { // 10 millisecond skew
_time_offset = offset_ns;
warnx("[timesync] Hard setting offset.");
} else {