|
|
@ -263,12 +263,12 @@ static mavlink_hil_state_t last_hil_state; |
|
|
|
#endif |
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
|
|
// report simulator state
|
|
|
|
// report simulator state
|
|
|
|
void Plane::send_simstate(mavlink_channel_t chan) |
|
|
|
void GCS_MAVLINK_Plane::send_simstate() const |
|
|
|
{ |
|
|
|
{ |
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL |
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL |
|
|
|
sitl.simstate_send(chan); |
|
|
|
GCS_MAVLINK::send_simstate(); |
|
|
|
#elif HIL_SUPPORT |
|
|
|
#elif HIL_SUPPORT |
|
|
|
if (g.hil_mode == 1) { |
|
|
|
if (plane.g.hil_mode == 1) { |
|
|
|
mavlink_msg_simstate_send(chan, |
|
|
|
mavlink_msg_simstate_send(chan, |
|
|
|
last_hil_state.roll, |
|
|
|
last_hil_state.roll, |
|
|
|
last_hil_state.pitch, |
|
|
|
last_hil_state.pitch, |
|
|
@ -430,13 +430,6 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id) |
|
|
|
#endif |
|
|
|
#endif |
|
|
|
break; |
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
case MSG_SIMSTATE: |
|
|
|
|
|
|
|
CHECK_PAYLOAD_SIZE(SIMSTATE); |
|
|
|
|
|
|
|
plane.send_simstate(chan); |
|
|
|
|
|
|
|
CHECK_PAYLOAD_SIZE2(AHRS2); |
|
|
|
|
|
|
|
send_ahrs2(); |
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
case MSG_TERRAIN: |
|
|
|
case MSG_TERRAIN: |
|
|
|
#if AP_TERRAIN_AVAILABLE |
|
|
|
#if AP_TERRAIN_AVAILABLE |
|
|
|
CHECK_PAYLOAD_SIZE(TERRAIN_REQUEST); |
|
|
|
CHECK_PAYLOAD_SIZE(TERRAIN_REQUEST); |
|
|
|