mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: Reduce inerital nav dependence
This commit is contained in:
parent
13840337ec
commit
22598b1a4b
@ -166,7 +166,7 @@ void Plane::ahrs_update()
|
|||||||
quadplane.check_yaw_reset();
|
quadplane.check_yaw_reset();
|
||||||
|
|
||||||
// update inertial_nav for quadplane
|
// update inertial_nav for quadplane
|
||||||
quadplane.inertial_nav.update(G_Dt);
|
quadplane.inertial_nav.update();
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -2254,7 +2254,10 @@ void QuadPlane::vtol_position_controller(void)
|
|||||||
void QuadPlane::setup_target_position(void)
|
void QuadPlane::setup_target_position(void)
|
||||||
{
|
{
|
||||||
const Location &loc = plane.next_WP_loc;
|
const Location &loc = plane.next_WP_loc;
|
||||||
Location origin = inertial_nav.get_origin();
|
Location origin;
|
||||||
|
if (!ahrs.get_origin(origin)) {
|
||||||
|
origin.zero();
|
||||||
|
}
|
||||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
|
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
|
||||||
|
|
||||||
const Vector2f diff2d = origin.get_distance_NE(loc);
|
const Vector2f diff2d = origin.get_distance_NE(loc);
|
||||||
|
Loading…
Reference in New Issue
Block a user