mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
GCS_MAVLink: move try_send_message of nav_controller_output up
This commit is contained in:
parent
6dbe662941
commit
de615ee11d
@ -193,6 +193,7 @@ public:
|
|||||||
// found. Rover overrides this!
|
// found. Rover overrides this!
|
||||||
virtual void send_rangefinder() const;
|
virtual void send_rangefinder() const;
|
||||||
void send_proximity() const;
|
void send_proximity() const;
|
||||||
|
virtual void send_nav_controller_output() const = 0;
|
||||||
void send_ahrs2();
|
void send_ahrs2();
|
||||||
void send_ahrs3();
|
void send_ahrs3();
|
||||||
void send_system_time();
|
void send_system_time();
|
||||||
|
@ -4091,6 +4091,11 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
|||||||
send_ahrs3();
|
send_ahrs3();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MSG_NAV_CONTROLLER_OUTPUT:
|
||||||
|
CHECK_PAYLOAD_SIZE(NAV_CONTROLLER_OUTPUT);
|
||||||
|
send_nav_controller_output();
|
||||||
|
break;
|
||||||
|
|
||||||
case MSG_AHRS:
|
case MSG_AHRS:
|
||||||
CHECK_PAYLOAD_SIZE(AHRS);
|
CHECK_PAYLOAD_SIZE(AHRS);
|
||||||
send_ahrs();
|
send_ahrs();
|
||||||
|
@ -36,6 +36,8 @@ protected:
|
|||||||
|
|
||||||
bool set_home_to_current_location(bool lock) override { return false; }
|
bool set_home_to_current_location(bool lock) override { return false; }
|
||||||
bool set_home(const Location& loc, bool lock) override { return false; }
|
bool set_home(const Location& loc, bool lock) override { return false; }
|
||||||
|
|
||||||
|
void send_nav_controller_output() const override {};
|
||||||
};
|
};
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -39,6 +39,7 @@ protected:
|
|||||||
uint32_t custom_mode() const override { return 3; } // magic number
|
uint32_t custom_mode() const override { return 3; } // magic number
|
||||||
MAV_STATE system_status() const override { return MAV_STATE_CALIBRATING; }
|
MAV_STATE system_status() const override { return MAV_STATE_CALIBRATING; }
|
||||||
void get_sensor_status_flags(uint32_t &present, uint32_t &enabled, uint32_t &health) override { present = 0; enabled = 0; health = 0; }
|
void get_sensor_status_flags(uint32_t &present, uint32_t &enabled, uint32_t &health) override { present = 0; enabled = 0; health = 0; }
|
||||||
|
void send_nav_controller_output() const override {};
|
||||||
|
|
||||||
bool set_home_to_current_location(bool lock) override { return false; }
|
bool set_home_to_current_location(bool lock) override { return false; }
|
||||||
bool set_home(const Location& loc, bool lock) override { return false; }
|
bool set_home(const Location& loc, bool lock) override { return false; }
|
||||||
|
Loading…
Reference in New Issue
Block a user