mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Tracker: eliminate gcs_send_message wraper
This commit is contained in:
parent
3b0a7703c4
commit
7865d467d3
@ -85,7 +85,7 @@ void Tracker::dataflash_periodic(void)
|
|||||||
void Tracker::one_second_loop()
|
void Tracker::one_second_loop()
|
||||||
{
|
{
|
||||||
// send a heartbeat
|
// send a heartbeat
|
||||||
gcs_send_message(MSG_HEARTBEAT);
|
gcs().send_message(MSG_HEARTBEAT);
|
||||||
|
|
||||||
// make it possible to change orientation at runtime
|
// make it possible to change orientation at runtime
|
||||||
ahrs.set_orientation();
|
ahrs.set_orientation();
|
||||||
|
@ -857,8 +857,8 @@ void Tracker::mavlink_delay_cb()
|
|||||||
uint32_t tnow = AP_HAL::millis();
|
uint32_t tnow = AP_HAL::millis();
|
||||||
if (tnow - last_1hz > 1000) {
|
if (tnow - last_1hz > 1000) {
|
||||||
last_1hz = tnow;
|
last_1hz = tnow;
|
||||||
gcs_send_message(MSG_HEARTBEAT);
|
gcs().send_message(MSG_HEARTBEAT);
|
||||||
gcs_send_message(MSG_EXTENDED_STATUS1);
|
gcs().send_message(MSG_EXTENDED_STATUS1);
|
||||||
}
|
}
|
||||||
if (tnow - last_50hz > 20) {
|
if (tnow - last_50hz > 20) {
|
||||||
last_50hz = tnow;
|
last_50hz = tnow;
|
||||||
@ -874,14 +874,6 @@ void Tracker::mavlink_delay_cb()
|
|||||||
tracker.in_mavlink_delay = false;
|
tracker.in_mavlink_delay = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
|
||||||
* send a message on both GCS links
|
|
||||||
*/
|
|
||||||
void Tracker::gcs_send_message(enum ap_message id)
|
|
||||||
{
|
|
||||||
gcs().send_message(id);
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* send data streams in the given rate range on both links
|
* send data streams in the given rate range on both links
|
||||||
*/
|
*/
|
||||||
@ -903,6 +895,6 @@ void Tracker::gcs_update(void)
|
|||||||
*/
|
*/
|
||||||
void Tracker::gcs_retry_deferred(void)
|
void Tracker::gcs_retry_deferred(void)
|
||||||
{
|
{
|
||||||
gcs_send_message(MSG_RETRY_DEFERRED);
|
gcs().send_message(MSG_RETRY_DEFERRED);
|
||||||
gcs().service_statustext();
|
gcs().service_statustext();
|
||||||
}
|
}
|
||||||
|
@ -204,7 +204,6 @@ private:
|
|||||||
void send_nav_controller_output(mavlink_channel_t chan);
|
void send_nav_controller_output(mavlink_channel_t chan);
|
||||||
void send_simstate(mavlink_channel_t chan);
|
void send_simstate(mavlink_channel_t chan);
|
||||||
void mavlink_check_target(const mavlink_message_t* msg);
|
void mavlink_check_target(const mavlink_message_t* msg);
|
||||||
void gcs_send_message(enum ap_message id);
|
|
||||||
void gcs_data_stream_send(void);
|
void gcs_data_stream_send(void);
|
||||||
void gcs_update(void);
|
void gcs_update(void);
|
||||||
void gcs_retry_deferred(void);
|
void gcs_retry_deferred(void);
|
||||||
|
Loading…
Reference in New Issue
Block a user