diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index a25c472beb..49e0fc3f46 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -773,7 +773,7 @@ static void fifty_hz_loop() sonar_alt = sonar.read(); } - #if HIL_PROTOCOL == HIL_PROTOCOL_MAVLINK && HIL_MODE != HIL_MODE_DISABLED + #if HIL_PROTOCOL == HIL_PROTOCOL_MAVLINK && HIL_MODE != HIL_MODE_DISABLED && FRAME_CONFIG != HELI_FRAME // HIL for a copter needs very fast update of the servo values hil.send_message(MSG_RADIO_OUT); #endif diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 9dd7ee4a32..8e471c9bc9 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -989,6 +989,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) break; } #endif +*/ #if HIL_MODE == HIL_MODE_SENSORS case MAVLINK_MSG_ID_RAW_IMU: @@ -1036,7 +1037,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) break; } #endif // HIL_MODE -*/ } // end switch } // end handle mavlink diff --git a/ArduCopter/Mavlink_Common.h b/ArduCopter/Mavlink_Common.h index fea60d35c4..e2f4531fb4 100644 --- a/ArduCopter/Mavlink_Common.h +++ b/ArduCopter/Mavlink_Common.h @@ -135,17 +135,36 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan) const uint8_t rssi = 1; // normalized values scaled to -10000 to 10000 // This is used for HIL. Do not change without discussing with HIL maintainers - mavlink_msg_rc_channels_scaled_send( + + #if FRAME_CONFIG == HELI_FRAME + + mavlink_msg_rc_channels_scaled_send( chan, - 10000 * g.rc_1.norm_output(), - 10000 * g.rc_2.norm_output(), - 10000 * g.rc_3.norm_output(), - 10000 * g.rc_4.norm_output(), + g.rc_1.servo_out, + g.rc_2.servo_out, + g.rc_3.radio_out, + g.rc_4.servo_out, 0, 0, 0, 0, rssi); + + #else + + mavlink_msg_rc_channels_scaled_send( + 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_2.norm_output(), + 10000 * g.rc_3.norm_output(), + 10000 * g.rc_4.norm_output(), + rssi); + + #endif } static void NOINLINE send_radio_in(mavlink_channel_t chan)