aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink/mavlink_messages.cpp
diff options
context:
space:
mode:
authorJulian Oes <julian@oes.ch>2014-05-07 21:11:21 +0200
committerJulian Oes <julian@oes.ch>2014-05-07 21:11:21 +0200
commit26f5e550c492fc00341d5a0ae445710325269813 (patch)
treed4136cbb97dd391ccce638103cd2a7b07ee2231c /src/modules/mavlink/mavlink_messages.cpp
parent470513d9bb67bc19bd0ac70d209c681dc321ddfb (diff)
parent23937150bce38463612ac170803a06a3424d480d (diff)
downloadpx4-firmware-26f5e550c492fc00341d5a0ae445710325269813.tar.gz
px4-firmware-26f5e550c492fc00341d5a0ae445710325269813.tar.bz2
px4-firmware-26f5e550c492fc00341d5a0ae445710325269813.zip
Merge remote-tracking branch 'px4/ekf_params' into navigator_cleanup_ekf_params
Conflicts: src/modules/ekf_att_pos_estimator/fw_att_pos_estimator_main.cpp
Diffstat (limited to 'src/modules/mavlink/mavlink_messages.cpp')
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp33
1 files changed, 17 insertions, 16 deletions
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index 67ded1230..ec90cf599 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -820,11 +820,11 @@ protected:
void send(const hrt_abstime t)
{
- bool updated = status_sub->update(t);
- updated |= pos_sp_triplet_sub->update(t);
- updated |= act_sub->update(t);
+ bool updated = act_sub->update(t);
+ (void)pos_sp_triplet_sub->update(t);
+ (void)status_sub->update(t);
- if (updated) {
+ if (updated && (status->arming_state == ARMING_STATE_ARMED)) {
/* translate the current syste state to mavlink state and mode */
uint8_t mavlink_state;
uint8_t mavlink_base_mode;
@@ -1340,22 +1340,23 @@ protected:
void send(const hrt_abstime t)
{
- (void)range_sub->update(t);
+ if (range_sub->update(t)) {
- uint8_t type;
+ uint8_t type;
- switch (range->type) {
- case RANGE_FINDER_TYPE_LASER:
- type = MAV_DISTANCE_SENSOR_LASER;
- break;
- }
+ switch (range->type) {
+ case RANGE_FINDER_TYPE_LASER:
+ type = MAV_DISTANCE_SENSOR_LASER;
+ break;
+ }
- uint8_t id = 0;
- uint8_t orientation = 0;
- uint8_t covariance = 20;
+ uint8_t id = 0;
+ uint8_t orientation = 0;
+ uint8_t covariance = 20;
- mavlink_msg_distance_sensor_send(_channel, range->timestamp / 1000, type, id, orientation,
- range->minimum_distance*100, range->maximum_distance*100, range->distance*100, covariance);
+ mavlink_msg_distance_sensor_send(_channel, range->timestamp / 1000, type, id, orientation,
+ range->minimum_distance*100, range->maximum_distance*100, range->distance*100, covariance);
+ }
}
};