Browse Source

Plane: only send RC_CHANNELS_SCALED in HIL

saves a bit of telemetry bandwidth
mission-4.1.18
Andrew Tridgell 12 years ago
parent
commit
c4dcdcf5a2
  1. 4
      ArduPlane/GCS_Mavlink.pde

4
ArduPlane/GCS_Mavlink.pde

@ -309,6 +309,7 @@ static void NOINLINE send_gps_raw(mavlink_channel_t chan) @@ -309,6 +309,7 @@ static void NOINLINE send_gps_raw(mavlink_channel_t chan)
g_gps->num_sats);
}
#if HIL_MODE != HIL_MODE_DISABLED
static void NOINLINE send_servo_out(mavlink_channel_t chan)
{
// normalized values scaled to -10000 to 10000
@ -328,6 +329,7 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan) @@ -328,6 +329,7 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan)
0,
receiver_rssi);
}
#endif
static void NOINLINE send_radio_in(mavlink_channel_t chan)
{
@ -581,8 +583,10 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id, @@ -581,8 +583,10 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id,
break;
case MSG_SERVO_OUT:
#if HIL_MODE != HIL_MODE_DISABLED
CHECK_PAYLOAD_SIZE(RC_CHANNELS_SCALED);
send_servo_out(chan);
#endif
break;
case MSG_RADIO_IN:

Loading…
Cancel
Save