mirror of https://github.com/ArduPilot/ardupilot
Copter: implement get_circle_radius, set_circle_rate
This commit is contained in:
parent
b8a1662ce1
commit
179b5db74d
|
@ -337,6 +337,20 @@ bool Copter::set_target_angle_and_climbrate(float roll_deg, float pitch_deg, flo
|
||||||
mode_guided.set_angle(q, climb_rate_ms*100, use_yaw_rate, radians(yaw_rate_degs), false);
|
mode_guided.set_angle(q, climb_rate_ms*100, use_yaw_rate, radians(yaw_rate_degs), false);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// circle mode controls
|
||||||
|
bool Copter::get_circle_radius(float &radius_m)
|
||||||
|
{
|
||||||
|
radius_m = circle_nav->get_radius() * 0.01f;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Copter::set_circle_rate(float rate_dps)
|
||||||
|
{
|
||||||
|
circle_nav->set_rate(rate_dps);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
#endif // ENABLE_SCRIPTING
|
#endif // ENABLE_SCRIPTING
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -648,6 +648,8 @@ private:
|
||||||
bool set_target_posvel_NED(const Vector3f& target_pos, const Vector3f& target_vel) override;
|
bool set_target_posvel_NED(const Vector3f& target_pos, const Vector3f& target_vel) override;
|
||||||
bool set_target_velocity_NED(const Vector3f& vel_ned) override;
|
bool set_target_velocity_NED(const Vector3f& vel_ned) override;
|
||||||
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 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;
|
||||||
#endif // ENABLE_SCRIPTING
|
#endif // ENABLE_SCRIPTING
|
||||||
void rc_loop();
|
void rc_loop();
|
||||||
void throttle_loop();
|
void throttle_loop();
|
||||||
|
|
Loading…
Reference in New Issue