mirror of https://github.com/ArduPilot/ardupilot
Rover: Allow lua script access to turn rate guided command
This commit is contained in:
parent
48124c1c4b
commit
7265e11b53
|
@ -204,6 +204,19 @@ bool Rover::set_steering_and_throttle(float steering, float throttle)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// 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)
|
||||||
|
{
|
||||||
|
// exit if vehicle is not in Guided mode or Auto-Guided mode
|
||||||
|
if (!control_mode->in_guided_mode()) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// set turn rate and speed. Turn rate is expected in centidegrees/s and speed in meters/s
|
||||||
|
mode_guided.set_desired_turn_rate_and_speed(turn_rate * 100.0f, speed);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
// get control output (for use in scripting)
|
// 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
|
// 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)
|
bool Rover::get_control_output(AP_Vehicle::ControlOutput control_output, float &control_value)
|
||||||
|
|
|
@ -271,6 +271,8 @@ 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;
|
||||||
|
// 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 get_control_output(AP_Vehicle::ControlOutput control_output, float &control_value) override;
|
bool get_control_output(AP_Vehicle::ControlOutput control_output, float &control_value) override;
|
||||||
#endif // AP_SCRIPTING_ENABLED
|
#endif // AP_SCRIPTING_ENABLED
|
||||||
void stats_update();
|
void stats_update();
|
||||||
|
|
Loading…
Reference in New Issue