mirror of https://github.com/ArduPilot/ardupilot
Copter: implement get_target_location/update_target_location for lua
This commit is contained in:
parent
5ab2aaffff
commit
5f5e0e65e0
|
@ -446,6 +446,40 @@ bool Copter::has_ekf_failsafed() const
|
|||
return failsafe.ekf;
|
||||
}
|
||||
|
||||
// get target location (for use by scripting)
|
||||
bool Copter::get_target_location(Location& target_loc)
|
||||
{
|
||||
switch (flightmode->mode_number()) {
|
||||
case Mode::Number::RTL:
|
||||
case Mode::Number::SMART_RTL:
|
||||
case Mode::Number::AVOID_ADSB:
|
||||
case Mode::Number::GUIDED:
|
||||
case Mode::Number::AUTO:
|
||||
case Mode::Number::FOLLOW:
|
||||
return flightmode->get_wp(target_loc);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
/*
|
||||
update_target_location() acts as a wrapper for set_target_location
|
||||
*/
|
||||
bool Copter::update_target_location(const Location &old_loc, const Location &new_loc)
|
||||
{
|
||||
Location next_WP_loc;
|
||||
flightmode->get_wp(next_WP_loc);
|
||||
if (!old_loc.same_loc_as(next_WP_loc)) {
|
||||
return false;
|
||||
}
|
||||
next_WP_loc = new_loc;
|
||||
next_WP_loc.change_alt_frame(old_loc.get_alt_frame());
|
||||
|
||||
return set_target_location(next_WP_loc);
|
||||
}
|
||||
|
||||
#endif // AP_SCRIPTING_ENABLED
|
||||
|
||||
// returns true if vehicle is landing. Only used by Lua scripts
|
||||
|
|
|
@ -670,6 +670,8 @@ private:
|
|||
#if AP_SCRIPTING_ENABLED
|
||||
#if MODE_GUIDED_ENABLED == ENABLED
|
||||
bool start_takeoff(float alt) override;
|
||||
bool get_target_location(Location& target_loc) override;
|
||||
bool update_target_location(const Location &old_loc, const Location &new_loc) override;
|
||||
bool set_target_pos_NED(const Vector3f& target_pos, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative, bool terrain_alt) override;
|
||||
bool set_target_posvel_NED(const Vector3f& target_pos, const Vector3f& target_vel) override;
|
||||
bool set_target_posvelaccel_NED(const Vector3f& target_pos, const Vector3f& target_vel, const Vector3f& target_accel, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative) override;
|
||||
|
|
Loading…
Reference in New Issue