mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Copter: more complete RC output reporting to GCS
Radio outputs are pulled from hal.rcout instead of from motors library which provides more complete reporting because it includes output from sources like the camera and mount libraries.
This commit is contained in:
parent
10d6a9a34e
commit
a8929cd746
@ -413,18 +413,27 @@ static void NOINLINE send_radio_in(mavlink_channel_t chan)
|
||||
|
||||
static void NOINLINE send_radio_out(mavlink_channel_t chan)
|
||||
{
|
||||
uint8_t i;
|
||||
uint16_t rcout[8];
|
||||
hal.rcout->read(rcout,8);
|
||||
// clear out unreasonable values
|
||||
for (i=0; i<8; i++) {
|
||||
if (rcout[i] > 10000) {
|
||||
rcout[i] = 0;
|
||||
}
|
||||
}
|
||||
mavlink_msg_servo_output_raw_send(
|
||||
chan,
|
||||
micros(),
|
||||
0, // port
|
||||
motors.motor_out[AP_MOTORS_MOT_1],
|
||||
motors.motor_out[AP_MOTORS_MOT_2],
|
||||
motors.motor_out[AP_MOTORS_MOT_3],
|
||||
motors.motor_out[AP_MOTORS_MOT_4],
|
||||
motors.motor_out[AP_MOTORS_MOT_5],
|
||||
motors.motor_out[AP_MOTORS_MOT_6],
|
||||
motors.motor_out[AP_MOTORS_MOT_7],
|
||||
motors.motor_out[AP_MOTORS_MOT_8]);
|
||||
rcout[0],
|
||||
rcout[1],
|
||||
rcout[2],
|
||||
rcout[3],
|
||||
rcout[4],
|
||||
rcout[5],
|
||||
rcout[6],
|
||||
rcout[7]);
|
||||
}
|
||||
|
||||
static void NOINLINE send_vfr_hud(mavlink_channel_t chan)
|
||||
|
Loading…
Reference in New Issue
Block a user