I’m seeing a bug with Ardupilot and Mission Planner when using the HIL mode for X-Plane: when the Ardupilot code commands a throttle between 0% and 50% X-Plane is sent a 0% throttle command, and an Ardupilot throttle command over 50% is mapped to a 0-100% X-Plane throttle command (50%->0%, 62.5%->25%, 75%->50%, 87.5%->75%, 100%-100%).
I’ve found this bug in multiple versions of the autopilot and Mission Planner code; I don’t believe I’ve found a version that works correctly.
This Ardupilot code sends the command data to the ground station:
ArduPlane\GCS_Mavlink.pde: void NOINLINE send_servo_out(mavlink_channel_t chan):
mavlink_msg_rc_channels_scaled_send(
chan,
millis(),
0, // port 0
10000 * channel_roll->norm_output() * (channel_roll->get_reverse()?-1:1),
10000 * channel_pitch->norm_output() * (channel_pitch->get_reverse()?-1:1),
10000 * channel_throttle->norm_output() * (channel_throttle->get_reverse()?-1:1),
10000 * channel_rudder->norm_output() * (channel_rudder->get_reverse()?-1:1),
0,
0,
0,
0,
receiver_rssi);
And this code in Mission Planner receives that data:
MissionPlanner\GCSViews\Simulation.cs: private void processArduPilot():
roll_out = (float)MainV2.comPort.MAV.cs.hilch1 / rollgain;
pitch_out = (float)MainV2.comPort.MAV.cs.hilch2 / pitchgain;
throttle_out = ((float)MainV2.comPort.MAV.cs.hilch3) / throttlegain;
rudder_out = (float)MainV2.comPort.MAV.cs.hilch4 / ruddergain;
roll_out = Constrain(roll_out, -1, 1);
pitch_out = Constrain(pitch_out, -1, 1);
rudder_out = Constrain(rudder_out, -1, 1);
throttle_out = Constrain(throttle_out, 0, 1);
The norm_output() function (in libraries\RC_Channel\RC_Channel.cpp), scales the channel output to a float between -1 and 1, so the send_servo_out sends a set of int16 between -10000 and 10000 to the ground station. Mission Planner scales those values back to the -1 to 1 range, and then, for the throttle channel, throws away the data between -1 and 0.
This issue can be fixed by changing either the Ardupilot code:
5000+5000 * channel_throttle->norm_output() * (channel_throttle->get_reverse()?-1:1),
or the Mission Planner code:
throttle_out = ((float)MainV2.comPort.MAV.cs.hilch3 + throttlegain) / (2*throttlegain);