Rover: move sending of send_pid_tuning up

This commit is contained in:
Peter Barker 2019-03-01 10:31:59 +11:00 committed by Andrew Tridgell
parent 74702b8688
commit 1debd88083
3 changed files with 7 additions and 7 deletions

View File

@ -171,9 +171,14 @@ void Rover::send_rpm(mavlink_channel_t chan)
/* /*
send PID tuning message send PID tuning message
*/ */
void Rover::send_pid_tuning(mavlink_channel_t chan) void GCS_MAVLINK_Rover::send_pid_tuning()
{ {
Parameters &g = rover.g;
ParametersG2 &g2 = rover.g2;
const AP_AHRS &ahrs = AP::ahrs();
const AP_Logger::PID_Info *pid_info; const AP_Logger::PID_Info *pid_info;
// steering PID // steering PID
if (g.gcs_pid_mask & 1) { if (g.gcs_pid_mask & 1) {
pid_info = &g2.attitude_control.get_steering_rate_pid().get_pid_info(); pid_info = &g2.attitude_control.get_steering_rate_pid().get_pid_info();
@ -333,11 +338,6 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
rover.g2.windvane.send_wind(chan); rover.g2.windvane.send_wind(chan);
break; break;
case MSG_PID_TUNING:
CHECK_PAYLOAD_SIZE(PID_TUNING);
rover.send_pid_tuning(chan);
break;
default: default:
return GCS_MAVLINK::try_send_message(id); return GCS_MAVLINK::try_send_message(id);
} }

View File

@ -35,6 +35,7 @@ protected:
uint64_t capabilities() const override; uint64_t capabilities() const override;
void send_nav_controller_output() const override; void send_nav_controller_output() const override;
void send_pid_tuning() override;
private: private:

View File

@ -436,7 +436,6 @@ private:
// GCS_Mavlink.cpp // GCS_Mavlink.cpp
void send_servo_out(mavlink_channel_t chan); void send_servo_out(mavlink_channel_t chan);
void send_pid_tuning(mavlink_channel_t chan);
void send_rpm(mavlink_channel_t chan); void send_rpm(mavlink_channel_t chan);
void send_wheel_encoder_distance(mavlink_channel_t chan); void send_wheel_encoder_distance(mavlink_channel_t chan);