mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: implement set_desired_speed
This commit is contained in:
parent
a86d20c844
commit
f03bcb06c9
@ -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)
|
||||
|
@ -273,6 +273,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;
|
||||
|
Loading…
Reference in New Issue
Block a user