Rover: implement set_desired_speed

This commit is contained in:
Yuri 2022-06-30 13:45:14 -05:00 committed by Randy Mackay
parent a97a17cce4
commit f1d6574fe5
2 changed files with 7 additions and 0 deletions

View File

@ -214,6 +214,12 @@ bool Rover::set_desired_turn_rate_and_speed(float turn_rate, float speed)
return true;
}
// set desired nav speed (m/s). Used for scripting.
bool Rover::set_desired_speed(float speed)
{
return control_mode->set_desired_speed(speed);
}
// get control output (for use in scripting)
// returns true on success and control_value is set to a value in the range -1 to +1
bool Rover::get_control_output(AP_Vehicle::ControlOutput control_output, float &control_value)

View File

@ -238,6 +238,7 @@ private:
bool set_steering_and_throttle(float steering, float throttle) override;
// set desired turn rate (degrees/sec) and speed (m/s). Used for scripting
bool set_desired_turn_rate_and_speed(float turn_rate, float speed) override;
bool set_desired_speed(float speed) override;
bool get_control_output(AP_Vehicle::ControlOutput control_output, float &control_value) override;
bool nav_scripting_enable(uint8_t mode) override;
bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2) override;