Copter: let AP_Vehicle base class worry about scheduler delay callback
This commit is contained in:
parent
024c86bdab
commit
9466126fa8
@ -976,7 +976,6 @@ private:
|
||||
void exit_mode(Mode *&old_flightmode, Mode *&new_flightmode);
|
||||
|
||||
public:
|
||||
void mavlink_delay_cb(); // GCS_Mavlink.cpp
|
||||
void failsafe_check(); // failsafe.cpp
|
||||
};
|
||||
|
||||
|
@ -1246,32 +1246,6 @@ void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg)
|
||||
* MAVLink to process packets while waiting for the initialisation to
|
||||
* complete
|
||||
*/
|
||||
void Copter::mavlink_delay_cb()
|
||||
{
|
||||
static uint32_t last_1hz, last_50hz, last_5s;
|
||||
|
||||
logger.EnableWrites(false);
|
||||
|
||||
uint32_t tnow = 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);
|
||||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK_Copter::handle_flight_termination(const mavlink_command_long_t &packet) {
|
||||
MAV_RESULT result = MAV_RESULT_FAILED;
|
||||
|
||||
|
@ -8,12 +8,6 @@
|
||||
*
|
||||
*****************************************************************************/
|
||||
|
||||
static void mavlink_delay_cb_static()
|
||||
{
|
||||
copter.mavlink_delay_cb();
|
||||
}
|
||||
|
||||
|
||||
static void failsafe_check_static()
|
||||
{
|
||||
copter.failsafe_check();
|
||||
@ -50,10 +44,8 @@ void Copter::init_ardupilot()
|
||||
// setup first port early to allow BoardConfig to report errors
|
||||
gcs().setup_console();
|
||||
|
||||
// Register mavlink_delay_cb, which will run anytime you have
|
||||
// more than 5ms remaining in your call to hal.scheduler->delay
|
||||
hal.scheduler->register_delay_callback(mavlink_delay_cb_static, 5);
|
||||
|
||||
register_scheduler_delay_callback();
|
||||
|
||||
BoardConfig.init();
|
||||
#if HAL_WITH_UAVCAN
|
||||
BoardConfig_CAN.init();
|
||||
|
Loading…
Reference in New Issue
Block a user