mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
Sub: move sending of send_pid_tuning up
This commit is contained in:
parent
94899bd2ed
commit
b04d084a50
@ -166,8 +166,12 @@ bool GCS_MAVLINK_Sub::send_info()
|
|||||||
/*
|
/*
|
||||||
send PID tuning message
|
send PID tuning message
|
||||||
*/
|
*/
|
||||||
void Sub::send_pid_tuning(mavlink_channel_t chan)
|
void GCS_MAVLINK_Sub::send_pid_tuning()
|
||||||
{
|
{
|
||||||
|
const Parameters &g = sub.g;
|
||||||
|
AP_AHRS &ahrs = AP::ahrs();
|
||||||
|
AC_AttitudeControl_Sub &attitude_control = sub.attitude_control;
|
||||||
|
|
||||||
const Vector3f &gyro = ahrs.get_gyro();
|
const Vector3f &gyro = ahrs.get_gyro();
|
||||||
if (g.gcs_pid_mask & 1) {
|
if (g.gcs_pid_mask & 1) {
|
||||||
const AP_Logger::PID_Info &pid_info = attitude_control.get_rate_roll_pid().get_pid_info();
|
const AP_Logger::PID_Info &pid_info = attitude_control.get_rate_roll_pid().get_pid_info();
|
||||||
@ -209,7 +213,7 @@ void Sub::send_pid_tuning(mavlink_channel_t chan)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (g.gcs_pid_mask & 8) {
|
if (g.gcs_pid_mask & 8) {
|
||||||
const AP_Logger::PID_Info &pid_info = pos_control.get_accel_z_pid().get_pid_info();
|
const AP_Logger::PID_Info &pid_info = sub.pos_control.get_accel_z_pid().get_pid_info();
|
||||||
mavlink_msg_pid_tuning_send(chan, PID_TUNING_ACCZ,
|
mavlink_msg_pid_tuning_send(chan, PID_TUNING_ACCZ,
|
||||||
pid_info.desired*0.01f,
|
pid_info.desired*0.01f,
|
||||||
-(ahrs.get_accel_ef_blended().z + GRAVITY_MSS),
|
-(ahrs.get_accel_ef_blended().z + GRAVITY_MSS),
|
||||||
@ -263,11 +267,6 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
|
|||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_PID_TUNING:
|
|
||||||
CHECK_PAYLOAD_SIZE(PID_TUNING);
|
|
||||||
sub.send_pid_tuning(chan);
|
|
||||||
break;
|
|
||||||
|
|
||||||
default:
|
default:
|
||||||
return GCS_MAVLINK::try_send_message(id);
|
return GCS_MAVLINK::try_send_message(id);
|
||||||
}
|
}
|
||||||
|
@ -36,6 +36,8 @@ protected:
|
|||||||
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_nav_controller_output() const override;
|
void send_nav_controller_output() const override;
|
||||||
|
void send_pid_tuning() override;
|
||||||
|
|
||||||
uint64_t capabilities() const override;
|
uint64_t capabilities() const override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
@ -483,7 +483,6 @@ private:
|
|||||||
void send_rpm(mavlink_channel_t chan);
|
void send_rpm(mavlink_channel_t chan);
|
||||||
void rpm_update();
|
void rpm_update();
|
||||||
#endif
|
#endif
|
||||||
void send_pid_tuning(mavlink_channel_t chan);
|
|
||||||
void Log_Write_Control_Tuning();
|
void Log_Write_Control_Tuning();
|
||||||
void Log_Write_Performance();
|
void Log_Write_Performance();
|
||||||
void Log_Write_Attitude();
|
void Log_Write_Attitude();
|
||||||
|
Loading…
Reference in New Issue
Block a user