mirror of https://github.com/ArduPilot/ardupilot
Rover: send PID to GCS regardless of mode
Also add some comments
This commit is contained in:
parent
d3d46a7f2c
commit
5167ec7708
|
@ -222,7 +222,8 @@ void Rover::send_rangefinder(mavlink_channel_t chan)
|
|||
void Rover::send_pid_tuning(mavlink_channel_t chan)
|
||||
{
|
||||
const DataFlash_Class::PID_Info *pid_info;
|
||||
if ((g.gcs_pid_mask & 1) && (!control_mode->manual_steering())) {
|
||||
// steering PID
|
||||
if (g.gcs_pid_mask & 1) {
|
||||
pid_info = &g2.attitude_control.get_steering_rate_pid().get_pid_info();
|
||||
mavlink_msg_pid_tuning_send(chan, PID_TUNING_STEER,
|
||||
degrees(pid_info->desired),
|
||||
|
@ -235,7 +236,8 @@ void Rover::send_pid_tuning(mavlink_channel_t chan)
|
|||
return;
|
||||
}
|
||||
}
|
||||
if ((g.gcs_pid_mask & 2) && (control_mode->auto_throttle())) {
|
||||
// speed to throttle PID
|
||||
if (g.gcs_pid_mask & 2) {
|
||||
pid_info = &g2.attitude_control.get_throttle_speed_pid().get_pid_info();
|
||||
float speed = 0.0f;
|
||||
g2.attitude_control.get_forward_speed(speed);
|
||||
|
|
|
@ -42,9 +42,6 @@ public:
|
|||
// return if in non-manual mode : AUTO, GUIDED, RTL
|
||||
virtual bool is_autopilot_mode() const { return false; }
|
||||
|
||||
// returns true if steering is directly controlled by RC
|
||||
virtual bool manual_steering() const { return false; }
|
||||
|
||||
// returns true if the throttle is controlled automatically
|
||||
virtual bool auto_throttle() { return is_autopilot_mode(); }
|
||||
|
||||
|
@ -309,9 +306,6 @@ public:
|
|||
// methods that affect movement of the vehicle in this mode
|
||||
void update() override;
|
||||
|
||||
// attributes of the mode
|
||||
bool manual_steering() const override { return true; }
|
||||
|
||||
// attributes for mavlink system status reporting
|
||||
bool has_manual_input() const override { return true; }
|
||||
bool attitude_stabilized() const override { return false; }
|
||||
|
|
Loading…
Reference in New Issue