The is commit adds a new flight mode called 'Throw' to Copter that enables the copter to be thrown into the air to start motors. This mode can only be netered when the copters EKF has a valid position estimate and goes through the following states
Throw_Disarmed - The copter is disarmed and motors are off.
Throw_Detecting - The copter is armed, but motors will not spin unless THROW_MOT_START has been set to 1. The copter is waiting to detect the throw. A throw with an upwards velocity of at least 50cm/s is required to trigger the detector.
Throw_Uprighting - The throw has been detected and the copter is being uprighted with 50% throttle to maximise control authority. This state transitions when the copter is within 30 degrees of level.
Throw_HgtStabilise - The copter is kept level and height is stabilised about the target height which is 3m above the height at which the throw release was detected. This state transitions when the height is no more than 0.5m below the demanded height.
Throw_PosHold - The horizontal motion is arrested and the copter is kept at a constant position and height.
// @Description: This is the damping gain for the pitch demand loop. Increase to add damping to correct for oscillations in speed and height. If set to 0 then TECS_PTCH_DAMP will be used instead.
+ // @Description: This is the damping gain for the throttle demand loop during and auto-landing. Same as TECS_THR_DAMP but only in effect during an auto-land. Increase to add damping to correct for oscillations in speed and height. When set to 0 landing throttle damp is controlled by TECS_THR_DAMP.
Description: If battery wattage (voltage * current) exceeds this value then the system will reduce max throttle (THR_MAX and TKOFF_THR_MAX) to satisfy this limit. This helps limit high current to low C rated batteries regardless of battery voltage. The max throttle will slowly grow back to THR_MAX (or TKOFF_THR_MAX) if demanding the current max and under the watt max.
ERB - Emlid Reach Binary protocol.
That driver designed for communication between Reach
and ArduPilot.
Provided opportunities:
- Detection of the driver
- Parsing of input messages: status of transmitter
and navigation information.
- Inject GPS messages from base
Fix the following build error on clang:
../../APMrover2/test.cpp:164:4: fatal error: variable 'fail_test' is uninitialized when used here [-Wuninitialized]
fail_test++;
^~~~~~~~~
../../APMrover2/test.cpp:139:19: note: initialize the variable 'fail_test' to silence this warning
uint8_t fail_test;
^
Use an Euler yaw heading that switches between a 321 and 312 rotation
sequence to avoid areas of singularity. Using Euler yaw decouples the
observation from the roll and pitch states and prevents magnetic
disturbances from affecting roll and pitch via the magnetometer fusion
process.
This should actually use the install-prereq script so we don't duplicate
effort on the maintenance of these scripts. But let's at least install
the correct version for now.
That will make platform specific naming be ignored. We use a string instead, to
let Waf tweak the target name correctly for us. The '#' prefix is to tell Waf
that the path is relative to bld.bldnode (instead of bld.path, which is the
default).
We cherry-picked the upstream commit
f56f22bb "Prefix by # to have the artifacts at the root of the build directory"
on top of version 1.8.18.
That commit allows us to use '#' at the beginning of programs and libraries
target paths to tell Waf that the paths are relative to the build directory.
With that we don't need to pass a Node instance to our task generators and lose
the filename formatting done by C/C++ tools.
That feature will be on the 1.9 release. When that is out, we can update our
submodule to that release.