mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-26 01:35:35 +03:00
add Cli.md description for rth home offsets
This commit is contained in:
parent
af6d5ee76d
commit
41b2d112b8
4 changed files with 7 additions and 5 deletions
|
@ -200,6 +200,8 @@ A shorter form is also supported to enable and disable functions using `serial <
|
||||||
| nav_rth_altitude | 1000 | Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters) |
|
| nav_rth_altitude | 1000 | Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters) |
|
||||||
| nav_rth_home_altitude | 0 | Aircraft will climb/descend to this altitude after reaching home if landing is not enabled. Set to 0 to stay at `nav_rth_altitude` (default) [cm] |
|
| nav_rth_home_altitude | 0 | Aircraft will climb/descend to this altitude after reaching home if landing is not enabled. Set to 0 to stay at `nav_rth_altitude` (default) [cm] |
|
||||||
| nav_rth_abort_threshold | 50000 | RTH sanity checking feature will notice if distance to home is increasing during RTH and once amount of increase exceeds the threshold defined by this parameter, instead of continuing RTH machine will enter emergency landing, self-level and go down safely. Default is 500m which is safe enough for both multirotor machines and airplanes. [cm] |
|
| nav_rth_abort_threshold | 50000 | RTH sanity checking feature will notice if distance to home is increasing during RTH and once amount of increase exceeds the threshold defined by this parameter, instead of continuing RTH machine will enter emergency landing, self-level and go down safely. Default is 500m which is safe enough for both multirotor machines and airplanes. [cm] |
|
||||||
|
| nav_rth_home_offset_distance | 0 | Distance offset from GPS established home to "safe" position used for RTH (metre, 0 disables) |
|
||||||
|
| nav_rth_home_offset_direction | 0 | Direction offset from GPS established home to "safe" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance) |
|
||||||
| nav_mc_bank_angle | 30 | Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude |
|
| nav_mc_bank_angle | 30 | Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude |
|
||||||
| nav_mc_hover_thr | 1500 | Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering. |
|
| nav_mc_hover_thr | 1500 | Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering. |
|
||||||
| nav_mc_auto_disarm_delay | 2000 | |
|
| nav_mc_auto_disarm_delay | 2000 | |
|
||||||
|
@ -421,7 +423,7 @@ A shorter form is also supported to enable and disable functions using `serial <
|
||||||
| dyn_notch_width_percent | 8 | Distance in % of the attenuated frequency for double dynamic filter notched. When set to `0` single dynamic notch filter is used |
|
| dyn_notch_width_percent | 8 | Distance in % of the attenuated frequency for double dynamic filter notched. When set to `0` single dynamic notch filter is used |
|
||||||
| dyn_notch_range | MEDIUM | Dynamic gyro filter range. Possible values `LOW` `MEDIUM` `HIGH`. `MEDIUM` should work best for 5-6" multirotors. `LOW` should work best with 7" and bigger. `HIGH` should work with everything below 4" |
|
| dyn_notch_range | MEDIUM | Dynamic gyro filter range. Possible values `LOW` `MEDIUM` `HIGH`. `MEDIUM` should work best for 5-6" multirotors. `LOW` should work best with 7" and bigger. `HIGH` should work with everything below 4" |
|
||||||
| dyn_notch_q | 120 | Q factor for dynamic notches |
|
| dyn_notch_q | 120 | Q factor for dynamic notches |
|
||||||
| dyn_notch_min_hz | 150 | Minimum frequency for dynamic notches. Default value of `150` works best with 5" multirors. Should be lowered with increased size of propellers. Values around `100` work fine on 7" drones. 10" can go down to `60` - `70` |
|
| dyn_notch_min_hz | 150 | Minimum frequency for dynamic notches. Default value of `150` works best with 5" multirors. Should be lowered with increased size of propellers. Values around `100` work fine on 7" drones. 10" can go down to `60` - `70` |
|
||||||
| gyro_stage2_lowpass_hz | 0 | Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz). Currently experimental |
|
| gyro_stage2_lowpass_hz | 0 | Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz). Currently experimental |
|
||||||
| pidsum_limit | 500 | A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch/Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help |
|
| pidsum_limit | 500 | A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch/Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help |
|
||||||
| yaw_p_limit | 300 | |
|
| yaw_p_limit | 300 | |
|
||||||
|
|
|
@ -1448,6 +1448,7 @@ groups:
|
||||||
- name: nav_rth_home_offset_direction
|
- name: nav_rth_home_offset_direction
|
||||||
field: general.rth_home_offset_direction
|
field: general.rth_home_offset_direction
|
||||||
max: 359
|
max: 359
|
||||||
|
|
||||||
- name: nav_mc_bank_angle
|
- name: nav_mc_bank_angle
|
||||||
field: mc.max_bank_angle
|
field: mc.max_bank_angle
|
||||||
min: 15
|
min: 15
|
||||||
|
|
|
@ -56,6 +56,7 @@
|
||||||
#include "sensors/acceleration.h"
|
#include "sensors/acceleration.h"
|
||||||
#include "sensors/boardalignment.h"
|
#include "sensors/boardalignment.h"
|
||||||
|
|
||||||
|
|
||||||
// Multirotors:
|
// Multirotors:
|
||||||
#define MR_RTH_CLIMB_OVERSHOOT_CM 100 // target this amount of cm *above* the target altitude to ensure it is actually reached (Vz > 0 at target alt)
|
#define MR_RTH_CLIMB_OVERSHOOT_CM 100 // target this amount of cm *above* the target altitude to ensure it is actually reached (Vz > 0 at target alt)
|
||||||
#define MR_RTH_CLIMB_MARGIN_MIN_CM 100 // start cruising home this amount of cm *before* reaching the cruise altitude (while continuing the ascend)
|
#define MR_RTH_CLIMB_MARGIN_MIN_CM 100 // start cruising home this amount of cm *before* reaching the cruise altitude (while continuing the ascend)
|
||||||
|
@ -2221,7 +2222,6 @@ static navigationHomeFlags_t navigationActualStateHomeValidity(void)
|
||||||
/*-----------------------------------------------------------
|
/*-----------------------------------------------------------
|
||||||
* Update home position, calculate distance and bearing to home
|
* Update home position, calculate distance and bearing to home
|
||||||
*-----------------------------------------------------------*/
|
*-----------------------------------------------------------*/
|
||||||
|
|
||||||
void updateHomePosition(void)
|
void updateHomePosition(void)
|
||||||
{
|
{
|
||||||
// Disarmed and have a valid position, constantly update home
|
// Disarmed and have a valid position, constantly update home
|
||||||
|
@ -2566,7 +2566,6 @@ void setWaypoint(uint8_t wpNumber, const navWaypoint_t * wpData)
|
||||||
// WP #0 - special waypoint - HOME
|
// WP #0 - special waypoint - HOME
|
||||||
if ((wpNumber == 0) && ARMING_FLAG(ARMED) && (posControl.flags.estPosStatus >= EST_USABLE) && posControl.gpsOrigin.valid && posControl.flags.isGCSAssistedNavigationEnabled) {
|
if ((wpNumber == 0) && ARMING_FLAG(ARMED) && (posControl.flags.estPosStatus >= EST_USABLE) && posControl.gpsOrigin.valid && posControl.flags.isGCSAssistedNavigationEnabled) {
|
||||||
// Forcibly set home position. Note that this is only valid if already armed, otherwise home will be reset instantly
|
// Forcibly set home position. Note that this is only valid if already armed, otherwise home will be reset instantly
|
||||||
|
|
||||||
geoConvertGeodeticToLocal(&wpPos.pos, &posControl.gpsOrigin, &wpLLH, GEO_ALT_RELATIVE);
|
geoConvertGeodeticToLocal(&wpPos.pos, &posControl.gpsOrigin, &wpLLH, GEO_ALT_RELATIVE);
|
||||||
setHomePosition(&wpPos.pos, 0, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING, NAV_HOME_VALID_ALL);
|
setHomePosition(&wpPos.pos, 0, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING, NAV_HOME_VALID_ALL);
|
||||||
}
|
}
|
||||||
|
|
|
@ -171,8 +171,8 @@ typedef struct navConfig_s {
|
||||||
uint16_t min_rth_distance; // 0 Disables. Minimal distance for RTH in cm, otherwise it will just autoland
|
uint16_t min_rth_distance; // 0 Disables. Minimal distance for RTH in cm, otherwise it will just autoland
|
||||||
uint16_t rth_abort_threshold; // Initiate emergency landing if during RTH we get this much [cm] away from home
|
uint16_t rth_abort_threshold; // Initiate emergency landing if during RTH we get this much [cm] away from home
|
||||||
uint16_t max_terrain_follow_altitude; // Max altitude to be used in SURFACE TRACKING mode
|
uint16_t max_terrain_follow_altitude; // Max altitude to be used in SURFACE TRACKING mode
|
||||||
uint16_t rth_home_offset_distance; // Distance offset from GPS established home to "safe" position used for RTH (metre, 0 disables)
|
uint16_t rth_home_offset_distance; // Distance offset from GPS established home to "safe" position used for RTH (metre, 0 disables)
|
||||||
uint16_t rth_home_offset_direction; // Direction offset from GPS established home to "safe" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance)
|
uint16_t rth_home_offset_direction; // Direction offset from GPS established home to "safe" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance)
|
||||||
} general;
|
} general;
|
||||||
|
|
||||||
struct {
|
struct {
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue