mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-27 02:04:00 -04:00
GCS_MAVLink: moving sending of sim state up
This commit is contained in:
parent
a137afd11b
commit
e9d2be143a
@ -177,6 +177,7 @@ public:
|
|||||||
virtual void send_scaled_pressure3(); // allow sub to override this
|
virtual void send_scaled_pressure3(); // allow sub to override this
|
||||||
void send_scaled_pressure();
|
void send_scaled_pressure();
|
||||||
void send_sensor_offsets();
|
void send_sensor_offsets();
|
||||||
|
virtual void send_simstate() const;
|
||||||
void send_ahrs();
|
void send_ahrs();
|
||||||
void send_battery2();
|
void send_battery2();
|
||||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||||
|
@ -36,6 +36,10 @@
|
|||||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
#include <SITL/SITL.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
uint32_t GCS_MAVLINK::last_radio_status_remrssi_ms;
|
uint32_t GCS_MAVLINK::last_radio_status_remrssi_ms;
|
||||||
@ -2352,6 +2356,17 @@ void GCS_MAVLINK::send_banner()
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void GCS_MAVLINK::send_simstate() const
|
||||||
|
{
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
SITL::SITL *sitl = AP::sitl();
|
||||||
|
if (sitl == nullptr) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
sitl->simstate_send(get_chan());
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
MAV_RESULT GCS_MAVLINK::handle_command_preflight_set_sensor_offsets(const mavlink_command_long_t &packet)
|
MAV_RESULT GCS_MAVLINK::handle_command_preflight_set_sensor_offsets(const mavlink_command_long_t &packet)
|
||||||
{
|
{
|
||||||
Compass *compass = get_compass();
|
Compass *compass = get_compass();
|
||||||
@ -2873,6 +2888,13 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
|||||||
send_servo_output_raw();
|
send_servo_output_raw();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MSG_SIMSTATE:
|
||||||
|
CHECK_PAYLOAD_SIZE(SIMSTATE);
|
||||||
|
send_simstate();
|
||||||
|
CHECK_PAYLOAD_SIZE(AHRS2);
|
||||||
|
send_ahrs2();
|
||||||
|
break;
|
||||||
|
|
||||||
case MSG_AHRS:
|
case MSG_AHRS:
|
||||||
CHECK_PAYLOAD_SIZE(AHRS);
|
CHECK_PAYLOAD_SIZE(AHRS);
|
||||||
send_ahrs();
|
send_ahrs();
|
||||||
|
Loading…
Reference in New Issue
Block a user