mirror of https://github.com/ArduPilot/ardupilot
Copter: implement set_desired_speed
This commit is contained in:
parent
bc8bdc18c9
commit
a97a17cce4
|
@ -392,6 +392,18 @@ bool Copter::set_circle_rate(float rate_dps)
|
|||
return true;
|
||||
}
|
||||
|
||||
// set desired speed (m/s). Used for scripting.
|
||||
bool Copter::set_desired_speed(float speed)
|
||||
{
|
||||
// exit if vehicle is not in auto mode
|
||||
if (!flightmode->is_autopilot()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
wp_nav->set_speed_xy(speed * 100.0f);
|
||||
return true;
|
||||
}
|
||||
|
||||
// returns true if mode supports NAV_SCRIPT_TIME mission commands
|
||||
bool Copter::nav_scripting_enable(uint8_t mode)
|
||||
{
|
||||
|
|
|
@ -652,6 +652,7 @@ private:
|
|||
bool set_target_angle_and_climbrate(float roll_deg, float pitch_deg, float yaw_deg, float climb_rate_ms, bool use_yaw_rate, float yaw_rate_degs) override;
|
||||
bool get_circle_radius(float &radius_m) override;
|
||||
bool set_circle_rate(float rate_dps) override;
|
||||
bool set_desired_speed(float speed) override;
|
||||
bool nav_scripting_enable(uint8_t mode) override;
|
||||
bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2) override;
|
||||
void nav_script_time_done(uint16_t id) override;
|
||||
|
|
Loading…
Reference in New Issue