mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
heli hil config
This commit is contained in:
parent
108a89f617
commit
b33eaa8c9c
@ -989,6 +989,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
*/
|
||||||
#if HIL_MODE == HIL_MODE_SENSORS
|
#if HIL_MODE == HIL_MODE_SENSORS
|
||||||
|
|
||||||
case MAVLINK_MSG_ID_RAW_IMU:
|
case MAVLINK_MSG_ID_RAW_IMU:
|
||||||
@ -1036,7 +1037,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
#endif // HIL_MODE
|
#endif // HIL_MODE
|
||||||
*/
|
|
||||||
} // end switch
|
} // end switch
|
||||||
} // end handle mavlink
|
} // end handle mavlink
|
||||||
|
|
||||||
|
@ -154,14 +154,14 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan)
|
|||||||
|
|
||||||
mavlink_msg_rc_channels_scaled_send(
|
mavlink_msg_rc_channels_scaled_send(
|
||||||
chan,
|
chan,
|
||||||
|
g.rc_1.servo_out,
|
||||||
|
g.rc_2.servo_out,
|
||||||
|
g.rc_3.radio_out,
|
||||||
|
g.rc_4.servo_out,
|
||||||
10000 * g.rc_1.norm_output(),
|
10000 * g.rc_1.norm_output(),
|
||||||
10000 * g.rc_2.norm_output(),
|
10000 * g.rc_2.norm_output(),
|
||||||
10000 * g.rc_3.norm_output(),
|
10000 * g.rc_3.norm_output(),
|
||||||
10000 * g.rc_4.norm_output(),
|
10000 * g.rc_4.norm_output(),
|
||||||
0,
|
|
||||||
0,
|
|
||||||
0,
|
|
||||||
0,
|
|
||||||
rssi);
|
rssi);
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user