Rover: implement get_steering_and_throttle

This commit is contained in:
Randy Mackay 2023-05-30 19:59:01 +09:00 committed by Andrew Tridgell
parent 1fd1a7f881
commit ce76e896dc
2 changed files with 9 additions and 0 deletions

View File

@ -207,6 +207,14 @@ bool Rover::set_steering_and_throttle(float steering, float throttle)
return true; return true;
} }
// get steering and throttle (-1 to +1) (for use by scripting)
bool Rover::get_steering_and_throttle(float& steering, float& throttle)
{
steering = g2.motors.get_steering() / 4500.0;
throttle = g2.motors.get_throttle() * 0.01;
return true;
}
// set desired turn rate (degrees/sec) and speed (m/s). Used for scripting // set desired turn rate (degrees/sec) and speed (m/s). Used for scripting
bool Rover::set_desired_turn_rate_and_speed(float turn_rate, float speed) bool Rover::set_desired_turn_rate_and_speed(float turn_rate, float speed)
{ {

View File

@ -258,6 +258,7 @@ private:
bool set_target_location(const Location& target_loc) override; bool set_target_location(const Location& target_loc) override;
bool set_target_velocity_NED(const Vector3f& vel_ned) override; bool set_target_velocity_NED(const Vector3f& vel_ned) override;
bool set_steering_and_throttle(float steering, float throttle) override; bool set_steering_and_throttle(float steering, float throttle) override;
bool get_steering_and_throttle(float& steering, float& throttle) override;
// set desired turn rate (degrees/sec) and speed (m/s). Used for scripting // 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_turn_rate_and_speed(float turn_rate, float speed) override;
bool set_desired_speed(float speed) override; bool set_desired_speed(float speed) override;