Browse Source

Sub: let AP_Vehicle base class worry about scheduler delay callback

c415-sdk
Peter Barker 5 years ago committed by Andrew Tridgell
parent
commit
e97582add0
  1. 26
      ArduSub/GCS_Mavlink.cpp
  2. 1
      ArduSub/Sub.h
  3. 10
      ArduSub/system.cpp

26
ArduSub/GCS_Mavlink.cpp

@ -792,32 +792,6 @@ void GCS_MAVLINK_Sub::handle_rc_channels_override(const mavlink_message_t &msg)
* MAVLink to process packets while waiting for the initialisation to * MAVLink to process packets while waiting for the initialisation to
* complete * complete
*/ */
void Sub::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);
}
MAV_RESULT GCS_MAVLINK_Sub::handle_flight_termination(const mavlink_command_long_t &packet) { MAV_RESULT GCS_MAVLINK_Sub::handle_flight_termination(const mavlink_command_long_t &packet) {
if (packet.param1 > 0.5f) { if (packet.param1 > 0.5f) {
sub.arming.disarm(); sub.arming.disarm();

1
ArduSub/Sub.h

@ -665,7 +665,6 @@ private:
public: public:
void mavlink_delay_cb();
void mainloop_failsafe_check(); void mainloop_failsafe_check();
}; };

10
ArduSub/system.cpp

@ -7,11 +7,6 @@
* *
*****************************************************************************/ *****************************************************************************/
static void mavlink_delay_cb_static()
{
sub.mavlink_delay_cb();
}
static void failsafe_check_static() static void failsafe_check_static()
{ {
sub.mainloop_failsafe_check(); sub.mainloop_failsafe_check();
@ -78,10 +73,7 @@ void Sub::init_ardupilot()
barometer.init(); barometer.init();
// Register the mavlink service callback. This will run register_scheduler_delay_callback();
// anytime there are more than 5ms remaining in a call to
// hal.scheduler->delay.
hal.scheduler->register_delay_callback(mavlink_delay_cb_static, 5);
// setup telem slots with serial ports // setup telem slots with serial ports
gcs().setup_uarts(); gcs().setup_uarts();

Loading…
Cancel
Save