new param: LAND_ABORT_DEG
@Description: This parameter is used when using a rangefinder during landing for altitude correction from baro drift (RNGFND_LANDING=1) and the altitude correction indicates your altitude is higher than the intended slope path. Steeper slopes can result in crashes so this allows the option to remember the baro offset and self-abort the landing and come around for a another landing with the correct baro offset applied for a perfect slope. An auto-abort go-around will only happen once, next attempt will not auto-abort again. This operation happens entirely automatically in AUTO mode. This value is the delta degrees threshold to trigger the go-around. Example: if set to 5 deg and the mission planned slope is 15 deg then if the new slope is 21 then it will go-around. Set to 0 to disable. Requires LAND_SLOPE_RCALC > 0.
New param: LAND_SLOPE_RCALC
@Description: This parameter is used when using a rangefinder during landing for altitude correction from baro drift (RNGFND_LANDING=1) and the altitude correction indicates your altitude is lower than the intended slope path. This value is the threshold of the correction to re-calculate the landing approach slope. Set to zero to keep the original slope all the way down and any detected baro drift will be corrected by pitching/throttling up to snap back to resume the original slope path. Otherwise, when a rangefinder altitude correction exceeds this threshold it will trigger a slope re-calculate to give a shallower slope. This also smoothes out the approach when flying over objects such as trees. Recommend a value of 2m.
default value is 2 (so, enabled by default)
@Description: This parameter reduces the pitch minimum limit of an auto-takeoff just a few seconds before it reaches the target altitude. This reduces overshoot by allowing the flight controller to start leveling off a few seconds before reaching the target height. When set to zero, the mission pitch min is enforced all the way to and through the target altitude, otherwise the pitch min slowly reduces to zero in the final segment. This is the pitch_min, not the demand. The flight controller should still be commanding to gain altitude to finish the takeoff but with this param it is not forcing it higher than it wants to be. (+1 squashed commits)
// @Description: When enabled, after an autoland and auto-disarm via LAND_DISARMDELAY happens then set all servos to neutral. This is helpful when an aircraft has a rough landing upside down or a crazy angle causing the servos to strain.
Reverse thrust for controlled landings, even with much steeper approach slopes. This is achieved by allowing throttle demand to go negative to maintain a target airspeed. A Pre-Flare stage was added, triggered by an altitude, to allow for a slower airspeed just before land. That lower airspeed can be near stall.
new params LAND_PF_ALT, LAND_PF_SEC, LAND_PF_ARSPD, USE_REV_THRUST
@Description: X-Axis deceleration threshold to notify the crash detector that there was a possible impact which helps disarm the motor quickly after a crash. This value should be much higher than normal negative x-axis forces during normal flight, check flight log files to determine the average IMU.x values for your aircraft and motor type. Higher value means less sensative (triggers on higher impact). For electric planes that don't vibrate much during fight a value of 25 is good (that's about 2.5G). For petrol/nitro planes you'll want a higher value. Set to 0 to disable the collision detector.
- parse MAVLINK_MSG_ADSB_VEHICLE msg
- new 1Hz adsb_update task to compare list against for threat detection
- perform object avoidance via loiter or loiter_and_descend. More methods are welcome!
- enabled via new param LAND_ABORT_THR default is 0 (disabled)
- Triggered via 95% throttle during landing, a landing abort will take place.
- This copies all takeoff params for right now, we can make this better later if needed
- added mission item command to NAV_LAND which is the abort takeoff altitude. If 0 then use last takeoff if available, else use 30m
- hold heading, just like takeoff, until altitude is reached
- pitch is constrained to takeoff pitch, or else 10deg if not available
- After abort altitude is reached, the normal landing restart happens (DO_LAND_START or decrement mission)
- restart landing by jumping to DO_LAND_START or decrement mission on mode change
* Retains ability to read from Analog Pin
* Adds ability to read RSSI from PWM channel value as is done in OpenLRSng, EazyUHF, and various other LRS.
* Handles any type of RSSI that provides RSSI values inverted - i.e. when the low value is the best signal and the high value is the worst signal.
* Has different key names from all existing RSSI parameters to provide for a clean break and easier distinguishing.
* Existing parameters are marked as obsolete
add crash detection, allow disengage via param CRASH_DETECT
improved is_flying behavior
take off, landing and hard-landing improvements
add stillness check to is_flying and log it
minimum airspeed is determined ARSPD_FBW_MIN*0.75
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.
this disables using CLI by default, even if compiled in. This is
needed to make standard firmwares work well with companion computers
where the CLI may cause startup issues
initialise mount on startup
use mount.has_pan_control method
remove calls to unimplemented mount.configure_cmd
remove call to update_mount_type which is now handled by mount lib
this is used to prevent slow glide slopes being used for small
altitude changes in missions. This allows more accurate tracking of
altitude with terrain changes
this adds some down trim when at throttle levels below the trim
throttle in FBWA mode.
defaults to 200 centi-degrees. I may adjust based on flight tests
Although this wasn't a problem immediatley, if someone had added a
parameter after k_param_NavEKF it's position in eeprom could have moved
as AP_AHRS_NAVEKF_AVAILABLE was enabled/disabled
Added parameter RALLY_TOTAL.
Added handlers for new MAVLink messages RALLY_POINT and
RALLY_FETCH_POINT.
defines.h modified to make room in EEPROM to store rally points.
rally.pde added and is responsible for ensuring rally points get
stored in the correct spot in EEPROM.
Multiple Rally/RTL point support now done. If rally points have
been defined, then when RTL mode is entered, the closest Rally
point is chosend and the plane loiters at that point.
Note only 10 rally points can be defined; this is to save space in
the APM's EEPROM.
this is an unusual option that gives FBWA flight control in AUTO
mode. It is being added to support use of APM in an aerial robotics
competition where students need to pilot the plane, but they still
need waypoint triggering of payloads
this switches ArduPlane over to use the L1 navigation controller, via
a generic nav_controller object pointer.
Note that the nav_controller controls all types of navigation now,
including level flight and heading hold. This provides a cleaner
abstraction than the old method of special case navigation handling
Pair-Programmed-With: Paul Riseborough <p_riseborough@live.com.au>
this makes FBWB much less sensitive to airframe tuning. When the
elevator stick first goes neutral it locks in the current altitude as
the target altitude. When the elevator stick is off neutral, it moves
the target altitude in proportion to the elevator, at a rate goverened
by the new FBWB_CLIMB_RATE parameter
This prevents the aircraft from slowly drifting in altitude in FBWB,
and gives a more intuitive control mechanism for altitude.
Thanks to Chris Miser from Falcon UAV for help in designing this
change
this allows control over whether ArduPlane tries to hold heading
during auto takeoff. For hand launches it can be better to hold the
wings level and not attempt to hold heading during takeoff to prevent
the possibility of a stall during the climb out.
Thanks to Chris Miser from Falcon UAV for the feedback that led to
this option.
this allows direct passthru of throttle in STABILIZE and FBWA, which
is useful for nitro planes wher you have a throttle cut switch that
drops the throttle below normal minimum.
sanity checking added to accelerometer calibration routine.
user feedback is sent using gcs_send_text_fmt instead of Serial.printf.
moved ins parameters to new eeprom number to avoid conflicts with older parameters.
other small changes including renaming of functions and parameters.