mirror of https://github.com/ArduPilot/ardupilot
Added Xplane output option
This commit is contained in:
parent
467ef66a77
commit
28262dd825
|
@ -158,9 +158,36 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan)
|
|||
0,
|
||||
0,
|
||||
rssi);
|
||||
#else
|
||||
#if X_PLANE == ENABLED
|
||||
/* update by JLN for X-Plane HIL */
|
||||
if(motor_armed == true && motor_auto_armed == true){
|
||||
mavlink_msg_rc_channels_scaled_send(
|
||||
chan,
|
||||
g.rc_1.servo_out,
|
||||
g.rc_2.servo_out,
|
||||
10000 * g.rc_3.norm_output(),
|
||||
g.rc_4.servo_out,
|
||||
10000 * g.rc_1.norm_output(),
|
||||
10000 * g.rc_2.norm_output(),
|
||||
10000 * g.rc_3.norm_output(),
|
||||
10000 * g.rc_4.norm_output(),
|
||||
rssi);
|
||||
}else{
|
||||
mavlink_msg_rc_channels_scaled_send(
|
||||
chan,
|
||||
0,
|
||||
0,
|
||||
-10000,
|
||||
0,
|
||||
10000 * g.rc_1.norm_output(),
|
||||
10000 * g.rc_2.norm_output(),
|
||||
10000 * g.rc_3.norm_output(),
|
||||
10000 * g.rc_4.norm_output(),
|
||||
rssi);
|
||||
}
|
||||
|
||||
#else
|
||||
|
||||
mavlink_msg_rc_channels_scaled_send(
|
||||
chan,
|
||||
g.rc_1.servo_out,
|
||||
|
@ -172,7 +199,7 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan)
|
|||
10000 * g.rc_3.norm_output(),
|
||||
10000 * g.rc_4.norm_output(),
|
||||
rssi);
|
||||
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue