This commit changes the way libraries headers are included in source files:
- If the header is in the same directory the source belongs to, so the
notation '#include ""' is used with the path relative to the directory
containing the source.
- If the header is outside the directory containing the source, then we use
the notation '#include <>' with the path relative to libraries folder.
Some of the advantages of such approach:
- Only one search path for libraries headers.
- OSs like Windows may have a better lookup time.
per Randy's suggestion, fast_atan2() is no longer necessary over atan2() because only copter uses it and copter is no longer supported on future builds of APM
ccd578664f (commitcomment-11025083)
This shifts the origin to the vehicle's current position and should be
called just before take-off to ensure there are no sudden roll or pitch
moves on takeoff.
Previous permissible descent speed of 10m/s was unnecessarily lenient.
Users can still bypass the suggested range through the MP's full
parameter list if they really want a very high descent speed.
First part of this fix is freezing the position controller's xy-axis
feed foward as we transition to the new segment.
Second part is work-around for straight line segments in that we allow
the target point to actually overshoot the end of the segment by up to
2m if the segment is a "fast waypoint". Ideally we would instead notice
the waypoint has been completed and take any left over time or distance
and move our target along the track towards the next waypoint but that
would require a much larger change to allow the wpnav lib to hold the
next two waypoints.
We only use the current target position as origin if the waypoint
controller is active (i..e has been used in the past 1 second). This is
consistent with how we initialise straight line waypoints
Loiter is only a horizontal position controller so it should not set the
z-axis position.
Moved pos_control.set_speed and accel functions so order matches
init_loiter_targets function order
AC_PosControl::init_xy_controller() has been added to PosControl and is
called by init_loiter_target.
Hybrid is currently using set_loiter_target function to init the loiter
controller. So we have to call init_xy_controller() by set_loiter_target
function.
What happens otherwise?
In AC_PosControl::update_xy_controller, we update "now" with
now = hal.scheduler->millis();
and, as _last_update_xy_ms has not been updated previously by
init_xy_controller(), we just call init_xy_controller().
So, _dt_xy will be negative and used anyways in all the functions and
PID called by update_xy_controller.
That will avoid at least _accel_target.x/y to be set to 0 but I'm not
sure for the high values, probably an I_term that is not reset and
reached very high value.
Or maybe a cast error somewhere... no clue at all
Limit accel output from loiter controller.
Call new pos_control.init_xy_controller when loiter starts
Remove sudden stop when pilot requested acceleration is zero
Pair programmed with Randy