mirror of https://github.com/ArduPilot/ardupilot
Copter: implement set_target_posvel_NED method for use in scripting
This commit is contained in:
parent
858d69ca0e
commit
d5715292a3
|
@ -296,6 +296,20 @@ bool Copter::set_target_location(const Location& target_loc)
|
|||
return mode_guided.set_destination(target_loc);
|
||||
}
|
||||
|
||||
// set target position and velocity (for use by scripting)
|
||||
bool Copter::set_target_posvel_NED(const Vector3f& target_pos, const Vector3f& target_vel)
|
||||
{
|
||||
// exit if vehicle is not in Guided mode or Auto-Guided mode
|
||||
if (!flightmode->in_guided_mode()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
const Vector3f pos_neu_cm(target_pos.x * 100.0f, target_pos.y * 100.0f, -target_pos.z * 100.0f);
|
||||
const Vector3f vel_neu_cms(target_vel.x * 100.0f, target_vel.y * 100.0f, -target_vel.z * 100.0f);
|
||||
|
||||
return mode_guided.set_destination_posvel(pos_neu_cm, vel_neu_cms);
|
||||
}
|
||||
|
||||
bool Copter::set_target_velocity_NED(const Vector3f& vel_ned)
|
||||
{
|
||||
// exit if vehicle is not in Guided mode or Auto-Guided mode
|
||||
|
|
|
@ -648,6 +648,7 @@ private:
|
|||
void fast_loop() override;
|
||||
bool start_takeoff(float alt) override;
|
||||
bool set_target_location(const Location& target_loc) 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_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;
|
||||
void rc_loop();
|
||||
|
|
Loading…
Reference in New Issue