mirror of https://github.com/ArduPilot/ardupilot
ArduSub: make Location(Vector3f) require ALTFRAME
This commit is contained in:
parent
f65c4df358
commit
f7b39b19f0
|
@ -312,7 +312,7 @@ void Sub::do_loiter_unlimited(const AP_Mission::Mission_Command& cmd)
|
||||||
// To-Do: make this simpler
|
// To-Do: make this simpler
|
||||||
Vector3f temp_pos;
|
Vector3f temp_pos;
|
||||||
wp_nav.get_wp_stopping_point_xy(temp_pos);
|
wp_nav.get_wp_stopping_point_xy(temp_pos);
|
||||||
const Location temp_loc(temp_pos);
|
const Location temp_loc(temp_pos, Location::AltFrame::ABOVE_ORIGIN);
|
||||||
target_loc.lat = temp_loc.lat;
|
target_loc.lat = temp_loc.lat;
|
||||||
target_loc.lng = temp_loc.lng;
|
target_loc.lng = temp_loc.lng;
|
||||||
}
|
}
|
||||||
|
|
|
@ -273,7 +273,7 @@ void Sub::auto_circle_movetoedge_start(const Location &circle_center, float radi
|
||||||
auto_mode = Auto_CircleMoveToEdge;
|
auto_mode = Auto_CircleMoveToEdge;
|
||||||
|
|
||||||
// convert circle_edge_neu to Location
|
// convert circle_edge_neu to Location
|
||||||
Location circle_edge(circle_edge_neu);
|
Location circle_edge(circle_edge_neu, Location::AltFrame::ABOVE_ORIGIN);
|
||||||
|
|
||||||
// convert altitude to same as command
|
// convert altitude to same as command
|
||||||
circle_edge.set_alt_cm(circle_center.alt, circle_center.get_alt_frame());
|
circle_edge.set_alt_cm(circle_center.alt, circle_center.get_alt_frame());
|
||||||
|
|
|
@ -145,7 +145,7 @@ bool Sub::guided_set_destination(const Vector3f& destination)
|
||||||
|
|
||||||
#if AC_FENCE == ENABLED
|
#if AC_FENCE == ENABLED
|
||||||
// reject destination if outside the fence
|
// reject destination if outside the fence
|
||||||
const Location dest_loc(destination);
|
const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN);
|
||||||
if (!fence.check_destination_within_fence(dest_loc)) {
|
if (!fence.check_destination_within_fence(dest_loc)) {
|
||||||
AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);
|
AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);
|
||||||
// failure is propagated to GCS with NAK
|
// failure is propagated to GCS with NAK
|
||||||
|
@ -217,7 +217,7 @@ bool Sub::guided_set_destination_posvel(const Vector3f& destination, const Vecto
|
||||||
|
|
||||||
#if AC_FENCE == ENABLED
|
#if AC_FENCE == ENABLED
|
||||||
// reject destination if outside the fence
|
// reject destination if outside the fence
|
||||||
const Location dest_loc(destination);
|
const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN);
|
||||||
if (!fence.check_destination_within_fence(dest_loc)) {
|
if (!fence.check_destination_within_fence(dest_loc)) {
|
||||||
AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);
|
AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);
|
||||||
// failure is propagated to GCS with NAK
|
// failure is propagated to GCS with NAK
|
||||||
|
|
Loading…
Reference in New Issue