aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2013-11-13 22:30:39 +0400
committerAnton Babushkin <anton.babushkin@me.com>2013-11-13 22:30:39 +0400
commit185bdb05a69aad9d809e068ea2168df5f7eb0a44 (patch)
tree2d5727538ffe50dfde100b114e72af7537544beb /src/modules
parentc9fcdb3c31c5557bca281954a67d0c3f9ad3b4ec (diff)
downloadpx4-firmware-185bdb05a69aad9d809e068ea2168df5f7eb0a44.tar.gz
px4-firmware-185bdb05a69aad9d809e068ea2168df5f7eb0a44.tar.bz2
px4-firmware-185bdb05a69aad9d809e068ea2168df5f7eb0a44.zip
Mavlink VFR message publication fix
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/mavlink/orb_listener.c28
1 files changed, 16 insertions, 12 deletions
diff --git a/src/modules/mavlink/orb_listener.c b/src/modules/mavlink/orb_listener.c
index f6860930c..abc91d34f 100644
--- a/src/modules/mavlink/orb_listener.c
+++ b/src/modules/mavlink/orb_listener.c
@@ -75,6 +75,7 @@ struct actuator_armed_s armed;
struct actuator_controls_effective_s actuators_effective_0;
struct actuator_controls_s actuators_0;
struct vehicle_attitude_s att;
+struct airspeed_s airspeed;
struct mavlink_subscriptions mavlink_subs;
@@ -92,6 +93,8 @@ static unsigned int gps_counter;
*/
static uint64_t last_sensor_timestamp;
+static hrt_abstime last_sent_vfr = 0;
+
static void *uorb_receive_thread(void *arg);
struct listener {
@@ -229,7 +232,7 @@ l_vehicle_attitude(const struct listener *l)
/* copy attitude data into local buffer */
orb_copy(ORB_ID(vehicle_attitude), mavlink_subs.att_sub, &att);
- if (gcs_link)
+ if (gcs_link) {
/* send sensor values */
mavlink_msg_attitude_send(MAVLINK_COMM_0,
last_sensor_timestamp / 1000,
@@ -240,6 +243,17 @@ l_vehicle_attitude(const struct listener *l)
att.pitchspeed,
att.yawspeed);
+ /* limit VFR message rate to 10Hz */
+ hrt_abstime t = hrt_absolute_time();
+ if (t >= last_sent_vfr + 100000) {
+ last_sent_vfr = t;
+ float groundspeed = sqrtf(global_pos.vx * global_pos.vx + global_pos.vy * global_pos.vy);
+ uint16_t heading = (att.yaw + M_PI_F) / M_PI_F * 180.0f;
+ float throttle = actuators_effective_0.control_effective[3] * (UINT16_MAX - 1);
+ mavlink_msg_vfr_hud_send(MAVLINK_COMM_0, airspeed.true_airspeed_m_s, groundspeed, heading, throttle, global_pos.alt, -global_pos.vz);
+ }
+ }
+
attitude_counter++;
}
@@ -681,17 +695,7 @@ l_home(const struct listener *l)
void
l_airspeed(const struct listener *l)
{
- struct airspeed_s airspeed;
-
orb_copy(ORB_ID(airspeed), mavlink_subs.airspeed_sub, &airspeed);
-
- float groundspeed = sqrtf(global_pos.vx * global_pos.vx + global_pos.vy * global_pos.vy);
- uint16_t heading = (att.yaw + M_PI_F) / M_PI_F * 180.0f;
- float throttle = actuators_effective_0.control_effective[3] * (UINT16_MAX - 1);
- float alt = global_pos.relative_alt;
- float climb = -global_pos.vz;
-
- mavlink_msg_vfr_hud_send(MAVLINK_COMM_0, airspeed.true_airspeed_m_s, groundspeed, heading, throttle, alt, climb);
}
void
@@ -849,7 +853,7 @@ uorb_receive_start(void)
mavlink_subs.optical_flow = orb_subscribe(ORB_ID(optical_flow));
orb_set_interval(mavlink_subs.optical_flow, 200); /* 5Hz updates */
- /* --- AIRSPEED / VFR / HUD --- */
+ /* --- AIRSPEED --- */
mavlink_subs.airspeed_sub = orb_subscribe(ORB_ID(airspeed));
orb_set_interval(mavlink_subs.airspeed_sub, 200); /* 5Hz updates */