mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
GCS_MAVLink: add send_ekf_origin
This commit is contained in:
parent
962f237db4
commit
07c195a865
@ -34,4 +34,9 @@ void GCS::send_home(const Location &home) const
|
||||
FOR_EACH_ACTIVE_CHANNEL(send_home(home));
|
||||
}
|
||||
|
||||
void GCS::send_ekf_origin(const Location &ekf_origin) const
|
||||
{
|
||||
FOR_EACH_ACTIVE_CHANNEL(send_ekf_origin(ekf_origin));
|
||||
}
|
||||
|
||||
#undef FOR_EACH_ACTIVE_CHANNEL
|
||||
|
@ -176,6 +176,7 @@ public:
|
||||
void send_local_position(const AP_AHRS &ahrs) const;
|
||||
void send_vibration(const AP_InertialSensor &ins) const;
|
||||
void send_home(const Location &home) const;
|
||||
void send_ekf_origin(const Location &ekf_origin) const;
|
||||
void send_heartbeat(uint8_t type, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status);
|
||||
void send_servo_output_raw(bool hil);
|
||||
static void send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour);
|
||||
@ -476,6 +477,7 @@ public:
|
||||
void send_message(enum ap_message id);
|
||||
void send_mission_item_reached_message(uint16_t mission_index);
|
||||
void send_home(const Location &home) const;
|
||||
void send_ekf_origin(const Location &ekf_origin) const;
|
||||
// push send_message() messages and queued statustext messages etc:
|
||||
void retry_deferred();
|
||||
void data_stream_send();
|
||||
|
@ -1480,6 +1480,17 @@ void GCS_MAVLINK::send_home(const Location &home) const
|
||||
}
|
||||
}
|
||||
|
||||
void GCS_MAVLINK::send_ekf_origin(const Location &ekf_origin) const
|
||||
{
|
||||
if (HAVE_PAYLOAD_SPACE(chan, GPS_GLOBAL_ORIGIN)) {
|
||||
mavlink_msg_gps_global_origin_send(
|
||||
chan,
|
||||
ekf_origin.lat,
|
||||
ekf_origin.lng,
|
||||
ekf_origin.alt * 10);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
wrapper for sending heartbeat
|
||||
*/
|
||||
|
Loading…
Reference in New Issue
Block a user