aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink/mavlink_messages.cpp
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-05-07 14:14:31 +0200
committerLorenz Meier <lm@inf.ethz.ch>2014-05-07 14:14:31 +0200
commit6a6feaf96cc6c4cfb6fdae25c9a0ac8a4e5809cc (patch)
tree654f7a648ee00f12ec25ee28143a74e6041c18a6 /src/modules/mavlink/mavlink_messages.cpp
parent319ce3de1005d7199a992b227c7e75acb9db376b (diff)
parent9f2d65eff53e88f1c0674766f2f9ef6be04875c0 (diff)
downloadpx4-firmware-6a6feaf96cc6c4cfb6fdae25c9a0ac8a4e5809cc.tar.gz
px4-firmware-6a6feaf96cc6c4cfb6fdae25c9a0ac8a4e5809cc.tar.bz2
px4-firmware-6a6feaf96cc6c4cfb6fdae25c9a0ac8a4e5809cc.zip
Merged master
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 678ce1645..9c552515d 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -819,11 +819,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;
@@ -1339,22 +1339,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);
+ }
}
};