mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Tracker: let AP_Vehicle base class worry about scheduler delay callback
This commit is contained in:
parent
09669bdc66
commit
0c355bef90
@ -623,31 +623,6 @@ mission_failed:
|
|||||||
* MAVLink to process packets while waiting for the initialisation to
|
* MAVLink to process packets while waiting for the initialisation to
|
||||||
* complete
|
* complete
|
||||||
*/
|
*/
|
||||||
void Tracker::mavlink_delay_cb()
|
|
||||||
{
|
|
||||||
static uint32_t last_1hz, last_50hz, last_5s;
|
|
||||||
|
|
||||||
logger.EnableWrites(false);
|
|
||||||
|
|
||||||
uint32_t tnow = AP_HAL::millis();
|
|
||||||
if (tnow - last_1hz > 1000) {
|
|
||||||
last_1hz = tnow;
|
|
||||||
gcs().send_message(MSG_HEARTBEAT);
|
|
||||||
gcs().send_message(MSG_SYS_STATUS);
|
|
||||||
}
|
|
||||||
if (tnow - last_50hz > 20) {
|
|
||||||
last_50hz = tnow;
|
|
||||||
gcs().update_receive();
|
|
||||||
gcs().update_send();
|
|
||||||
notify.update();
|
|
||||||
}
|
|
||||||
if (tnow - last_5s > 5000) {
|
|
||||||
last_5s = tnow;
|
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Initialising APM");
|
|
||||||
}
|
|
||||||
logger.EnableWrites(true);
|
|
||||||
}
|
|
||||||
|
|
||||||
// send position tracker is using
|
// send position tracker is using
|
||||||
void GCS_MAVLINK_Tracker::send_global_position_int()
|
void GCS_MAVLINK_Tracker::send_global_position_int()
|
||||||
{
|
{
|
||||||
|
@ -245,8 +245,6 @@ private:
|
|||||||
FUNCTOR_BIND_MEMBER(&Tracker::start_command_callback, bool, const AP_Mission::Mission_Command &),
|
FUNCTOR_BIND_MEMBER(&Tracker::start_command_callback, bool, const AP_Mission::Mission_Command &),
|
||||||
FUNCTOR_BIND_MEMBER(&Tracker::verify_command_callback, bool, const AP_Mission::Mission_Command &),
|
FUNCTOR_BIND_MEMBER(&Tracker::verify_command_callback, bool, const AP_Mission::Mission_Command &),
|
||||||
FUNCTOR_BIND_MEMBER(&Tracker::exit_mission_callback, void)};
|
FUNCTOR_BIND_MEMBER(&Tracker::exit_mission_callback, void)};
|
||||||
public:
|
|
||||||
void mavlink_delay_cb();
|
|
||||||
};
|
};
|
||||||
|
|
||||||
extern Tracker tracker;
|
extern Tracker tracker;
|
||||||
|
@ -3,11 +3,6 @@
|
|||||||
// mission storage
|
// mission storage
|
||||||
static const StorageAccess wp_storage(StorageManager::StorageMission);
|
static const StorageAccess wp_storage(StorageManager::StorageMission);
|
||||||
|
|
||||||
static void mavlink_delay_cb_static()
|
|
||||||
{
|
|
||||||
tracker.mavlink_delay_cb();
|
|
||||||
}
|
|
||||||
|
|
||||||
void Tracker::init_tracker()
|
void Tracker::init_tracker()
|
||||||
{
|
{
|
||||||
// initialise console serial port
|
// initialise console serial port
|
||||||
@ -31,9 +26,7 @@ void Tracker::init_tracker()
|
|||||||
// setup first port early to allow BoardConfig to report errors
|
// setup first port early to allow BoardConfig to report errors
|
||||||
gcs().setup_console();
|
gcs().setup_console();
|
||||||
|
|
||||||
// Register mavlink_delay_cb, which will run anytime you have
|
register_scheduler_delay_callback();
|
||||||
// more than 5ms remaining in your call to hal.scheduler->delay
|
|
||||||
hal.scheduler->register_delay_callback(mavlink_delay_cb_static, 5);
|
|
||||||
|
|
||||||
BoardConfig.init();
|
BoardConfig.init();
|
||||||
#if HAL_WITH_UAVCAN
|
#if HAL_WITH_UAVCAN
|
||||||
|
Loading…
Reference in New Issue
Block a user