mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
APMrover2: adjust for 16 channels in SERVO_OUTPUT_RAW
This commit is contained in:
parent
53e71ccf12
commit
a4270b1bb6
@ -259,37 +259,6 @@ void Rover::send_servo_out(mavlink_channel_t chan)
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void Rover::send_radio_out(mavlink_channel_t chan)
|
|
||||||
{
|
|
||||||
#if HIL_MODE == HIL_MODE_DISABLED || HIL_SERVOS
|
|
||||||
mavlink_msg_servo_output_raw_send(
|
|
||||||
chan,
|
|
||||||
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));
|
|
||||||
#else
|
|
||||||
mavlink_msg_servo_output_raw_send(
|
|
||||||
chan,
|
|
||||||
micros(),
|
|
||||||
0, // port
|
|
||||||
RC_Channel::rc_channel(0)->get_radio_out(),
|
|
||||||
RC_Channel::rc_channel(1)->get_radio_out(),
|
|
||||||
RC_Channel::rc_channel(2)->get_radio_out(),
|
|
||||||
RC_Channel::rc_channel(3)->get_radio_out(),
|
|
||||||
RC_Channel::rc_channel(4)->get_radio_out(),
|
|
||||||
RC_Channel::rc_channel(5)->get_radio_out(),
|
|
||||||
RC_Channel::rc_channel(6)->get_radio_out(),
|
|
||||||
RC_Channel::rc_channel(7)->get_radio_out());
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
void Rover::send_vfr_hud(mavlink_channel_t chan)
|
void Rover::send_vfr_hud(mavlink_channel_t chan)
|
||||||
{
|
{
|
||||||
mavlink_msg_vfr_hud_send(
|
mavlink_msg_vfr_hud_send(
|
||||||
@ -480,7 +449,7 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
|
|||||||
|
|
||||||
case MSG_RADIO_OUT:
|
case MSG_RADIO_OUT:
|
||||||
CHECK_PAYLOAD_SIZE(SERVO_OUTPUT_RAW);
|
CHECK_PAYLOAD_SIZE(SERVO_OUTPUT_RAW);
|
||||||
rover.send_radio_out(chan);
|
send_servo_output_raw(false);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_VFR_HUD:
|
case MSG_VFR_HUD:
|
||||||
|
@ -396,7 +396,6 @@ private:
|
|||||||
void send_location(mavlink_channel_t chan);
|
void send_location(mavlink_channel_t chan);
|
||||||
void send_nav_controller_output(mavlink_channel_t chan);
|
void send_nav_controller_output(mavlink_channel_t chan);
|
||||||
void send_servo_out(mavlink_channel_t chan);
|
void send_servo_out(mavlink_channel_t chan);
|
||||||
void send_radio_out(mavlink_channel_t chan);
|
|
||||||
void send_vfr_hud(mavlink_channel_t chan);
|
void send_vfr_hud(mavlink_channel_t chan);
|
||||||
void send_simstate(mavlink_channel_t chan);
|
void send_simstate(mavlink_channel_t chan);
|
||||||
void send_hwstatus(mavlink_channel_t chan);
|
void send_hwstatus(mavlink_channel_t chan);
|
||||||
|
Loading…
Reference in New Issue
Block a user