mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-24 00:33:56 -04:00
Sub: adjust for Location_Class and Location unification
This commit is contained in:
parent
b258e89a2d
commit
d8e90ded90
ArduSub
@ -41,8 +41,6 @@ Sub::Sub()
|
||||
circle_nav(inertial_nav, ahrs_view, pos_control),
|
||||
param_loader(var_info)
|
||||
{
|
||||
memset(¤t_loc, 0, sizeof(current_loc));
|
||||
|
||||
// init sensor error logging flags
|
||||
sensor_health.baro = true;
|
||||
sensor_health.compass = true;
|
||||
|
@ -312,7 +312,7 @@ void Sub::do_loiter_unlimited(const AP_Mission::Mission_Command& cmd)
|
||||
// To-Do: make this simpler
|
||||
Vector3f temp_pos;
|
||||
wp_nav.get_wp_stopping_point_xy(temp_pos);
|
||||
Location temp_loc(temp_pos);
|
||||
const Location temp_loc(temp_pos);
|
||||
target_loc.lat = temp_loc.lat;
|
||||
target_loc.lng = temp_loc.lng;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user