|
|
|
@ -103,22 +103,6 @@ void Tracker::send_location(mavlink_channel_t chan)
@@ -103,22 +103,6 @@ void Tracker::send_location(mavlink_channel_t chan)
|
|
|
|
|
ahrs.yaw_sensor); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void Tracker::send_radio_out(mavlink_channel_t chan) |
|
|
|
|
{ |
|
|
|
|
mavlink_msg_servo_output_raw_send( |
|
|
|
|
chan, |
|
|
|
|
AP_HAL::micros(), |
|
|
|
|
0, // port
|
|
|
|
|
hal.rcout->read(0), |
|
|
|
|
hal.rcout->read(1), |
|
|
|
|
hal.rcout->read(2), |
|
|
|
|
hal.rcout->read(3), |
|
|
|
|
hal.rcout->read(4), |
|
|
|
|
hal.rcout->read(5), |
|
|
|
|
hal.rcout->read(6), |
|
|
|
|
hal.rcout->read(7)); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void Tracker::send_hwstatus(mavlink_channel_t chan) |
|
|
|
|
{ |
|
|
|
|
mavlink_msg_hwstatus_send( |
|
|
|
@ -210,7 +194,7 @@ bool GCS_MAVLINK_Tracker::try_send_message(enum ap_message id)
@@ -210,7 +194,7 @@ bool GCS_MAVLINK_Tracker::try_send_message(enum ap_message id)
|
|
|
|
|
|
|
|
|
|
case MSG_RADIO_OUT: |
|
|
|
|
CHECK_PAYLOAD_SIZE(SERVO_OUTPUT_RAW); |
|
|
|
|
tracker.send_radio_out(chan); |
|
|
|
|
send_servo_output_raw(false); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case MSG_RAW_IMU1: |
|
|
|
|