mirror of
https://github.com/ArduPilot/ardupilot.git
synced 2026-02-06 17:02:01 +08:00
Rover: update for changed signature of set_target_velocity_NED()
This commit is contained in:
@@ -172,7 +172,7 @@ bool Rover::set_target_location(const Location& target_loc)
|
||||
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
// set target velocity (for use by scripting)
|
||||
bool Rover::set_target_velocity_NED(const Vector3f& vel_ned)
|
||||
bool Rover::set_target_velocity_NED(const Vector3f& vel_ned, bool align_yaw_to_target)
|
||||
{
|
||||
// exit if vehicle is not in Guided mode or Auto-Guided mode
|
||||
if (!control_mode->in_guided_mode()) {
|
||||
|
||||
@@ -268,7 +268,7 @@ private:
|
||||
#endif
|
||||
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
bool set_target_velocity_NED(const Vector3f& vel_ned) override;
|
||||
bool set_target_velocity_NED(const Vector3f& vel_ned, bool align_yaw_to_target) 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
|
||||
|
||||
Reference in New Issue
Block a user