mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
Sub: move try_send_message of nav_controller_output up
This commit is contained in:
parent
de615ee11d
commit
57e5991fde
@ -213,17 +213,17 @@ void GCS_MAVLINK_Sub::get_sensor_status_flags(uint32_t &control_sensors_present,
|
||||
return sub.get_sensor_status_flags(control_sensors_present, control_sensors_enabled, control_sensors_health);
|
||||
}
|
||||
|
||||
void NOINLINE Sub::send_nav_controller_output(mavlink_channel_t chan)
|
||||
void GCS_MAVLINK_Sub::send_nav_controller_output() const
|
||||
{
|
||||
const Vector3f &targets = attitude_control.get_att_target_euler_cd();
|
||||
const Vector3f &targets = sub.attitude_control.get_att_target_euler_cd();
|
||||
mavlink_msg_nav_controller_output_send(
|
||||
chan,
|
||||
targets.x * 1.0e-2f,
|
||||
targets.y * 1.0e-2f,
|
||||
targets.z * 1.0e-2f,
|
||||
wp_nav.get_wp_bearing_to_destination() * 1.0e-2f,
|
||||
MIN(wp_nav.get_wp_distance_to_destination() * 1.0e-2f, UINT16_MAX),
|
||||
pos_control.get_alt_error() * 1.0e-2f,
|
||||
sub.wp_nav.get_wp_bearing_to_destination() * 1.0e-2f,
|
||||
MIN(sub.wp_nav.get_wp_distance_to_destination() * 1.0e-2f, UINT16_MAX),
|
||||
sub.pos_control.get_alt_error() * 1.0e-2f,
|
||||
0,
|
||||
0);
|
||||
}
|
||||
@ -381,11 +381,6 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
|
||||
send_info();
|
||||
break;
|
||||
|
||||
case MSG_NAV_CONTROLLER_OUTPUT:
|
||||
CHECK_PAYLOAD_SIZE(NAV_CONTROLLER_OUTPUT);
|
||||
sub.send_nav_controller_output(chan);
|
||||
break;
|
||||
|
||||
case MSG_RPM:
|
||||
#if RPM_ENABLED == ENABLED
|
||||
CHECK_PAYLOAD_SIZE(RPM);
|
||||
|
@ -35,6 +35,8 @@ protected:
|
||||
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
|
||||
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
|
||||
|
||||
void send_nav_controller_output() const override;
|
||||
|
||||
private:
|
||||
|
||||
void handleMessage(mavlink_message_t * msg) override;
|
||||
|
@ -478,7 +478,6 @@ private:
|
||||
void get_sensor_status_flags(uint32_t &control_sensors_present,
|
||||
uint32_t &control_sensors_enabled,
|
||||
uint32_t &control_sensors_health);
|
||||
void send_nav_controller_output(mavlink_channel_t chan);
|
||||
#if RPM_ENABLED == ENABLED
|
||||
void send_rpm(mavlink_channel_t chan);
|
||||
void rpm_update();
|
||||
|
Loading…
Reference in New Issue
Block a user