mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Sub: show frame class as part of banner
Similar to how Copter does in its equivalent method. frame type is not used on Sub ATM
This commit is contained in:
parent
85a8536243
commit
840bdbba62
@ -76,6 +76,12 @@ MAV_STATE GCS_MAVLINK_Sub::vehicle_system_status() const
|
|||||||
return MAV_STATE_STANDBY;
|
return MAV_STATE_STANDBY;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void GCS_MAVLINK_Sub::send_banner()
|
||||||
|
{
|
||||||
|
GCS_MAVLINK::send_banner();
|
||||||
|
send_text(MAV_SEVERITY_INFO, "Frame: %s", sub.motors.get_frame_string());
|
||||||
|
}
|
||||||
|
|
||||||
void GCS_MAVLINK_Sub::send_nav_controller_output() const
|
void GCS_MAVLINK_Sub::send_nav_controller_output() const
|
||||||
{
|
{
|
||||||
const Vector3f &targets = sub.attitude_control.get_att_target_euler_cd();
|
const Vector3f &targets = sub.attitude_control.get_att_target_euler_cd();
|
||||||
|
@ -32,6 +32,8 @@ protected:
|
|||||||
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
|
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
|
||||||
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
|
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
|
||||||
|
|
||||||
|
void send_banner() override;
|
||||||
|
|
||||||
void send_nav_controller_output() const override;
|
void send_nav_controller_output() const override;
|
||||||
void send_pid_tuning() override;
|
void send_pid_tuning() override;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user