1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-20 06:45:14 +03:00

Improved configuration and state split

This commit is contained in:
Pawel Spychalski (DzikuVx) 2018-05-07 15:47:10 +02:00
parent 4d8fea95f7
commit 6a7995a028
4 changed files with 45 additions and 18 deletions

View file

@ -100,11 +100,8 @@ typedef enum {
ACCELEROMETER_CALIBRATED= (1 << 9), ACCELEROMETER_CALIBRATED= (1 << 9),
PWM_DRIVER_AVAILABLE = (1 << 10), PWM_DRIVER_AVAILABLE = (1 << 10),
HELICOPTER = (1 << 11), HELICOPTER = (1 << 11),
NAV_CRUISE_ACCELERATING = (1 << 12), NAV_CRUISE_BRAKING = (1 << 12),
NAV_CRUISE_BRAKING = (1 << 13), NAV_CRUISE_BRAKING_BOOST = (1 << 13),
NAV_HIGHSPEED_CRUISE = (1 << 14),
NAV_CRUISE_STOPPED = (1 << 15),
NAV_CRUISE_STORE_POSITION = (1 << 16)
} stateFlags_t; } stateFlags_t;
#define DISABLE_STATE(mask) (stateFlags &= ~(mask)) #define DISABLE_STATE(mask) (stateFlags &= ~(mask))

View file

@ -1246,12 +1246,31 @@ groups:
- name: nav_mc_braking_speed_threshold - name: nav_mc_braking_speed_threshold
field: mc.braking_speed_threshold field: mc.braking_speed_threshold
min: 0 min: 0
max: 1000 max: 1000
- name: nav_mc_braking_disengage_speed
field: mc.braking_disengage_speed
min: 0
max: 1000
- name: nav_mc_braking_timeout
field: mc.braking_timeout
min: 100
max: 5000
- name: nav_mc_braking_boost_factor - name: nav_mc_braking_boost_factor
field: mc.braking_boost_factor field: mc.braking_boost_factor
min: 0 min: 0
max: 200 max: 200
- name: nav_mc_braking_boost_timeout
field: mc.braking_boost_timeout
min: 0
max: 5000
- name: nav_mc_braking_boost_speed_threshold
field: mc.braking_boost_speed_threshold
min: 100
max: 1000
- name: nav_mc_braking_boost_disengage_speed
field: mc.braking_boost_disengage_speed
min: 0
max: 1000
- name: nav_fw_cruise_thr - name: nav_fw_cruise_thr
field: fw.cruise_throttle field: fw.cruise_throttle
min: 1000 min: 1000

View file

@ -76,7 +76,7 @@ PG_DECLARE_ARRAY(navWaypoint_t, NAV_MAX_WAYPOINTS, nonVolatileWaypointList);
PG_REGISTER_ARRAY(navWaypoint_t, NAV_MAX_WAYPOINTS, nonVolatileWaypointList, PG_WAYPOINT_MISSION_STORAGE, 0); PG_REGISTER_ARRAY(navWaypoint_t, NAV_MAX_WAYPOINTS, nonVolatileWaypointList, PG_WAYPOINT_MISSION_STORAGE, 0);
#endif #endif
PG_REGISTER_WITH_RESET_TEMPLATE(navConfig_t, navConfig, PG_NAV_CONFIG, 1); PG_REGISTER_WITH_RESET_TEMPLATE(navConfig_t, navConfig, PG_NAV_CONFIG, 2);
PG_RESET_TEMPLATE(navConfig_t, navConfig, PG_RESET_TEMPLATE(navConfig_t, navConfig,
.general = { .general = {
@ -116,8 +116,13 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig,
.max_bank_angle = 30, // 30 deg .max_bank_angle = 30, // 30 deg
.hover_throttle = 1500, .hover_throttle = 1500,
.auto_disarm_delay = 2000, .auto_disarm_delay = 2000,
.braking_speed_threshold = 100, .braking_speed_threshold = 100, // Braking can become active above 1m/s
.braking_boost_factor = 0, .braking_disengage_speed = 75, // Stop when speed goes below 0.75m/s
.braking_timeout = 2000, // Timeout barking after 2s
.braking_boost_factor = 0, // By default do not use boost factor
.braking_boost_timeout = 750, // Timout boost after 750ms
.braking_boost_speed_threshold = 200, //Boost can happen only above 2m/s
.braking_boost_disengage_speed = 100, //Disable boost at 1m/s
}, },
// Fixed wing // Fixed wing
@ -1960,6 +1965,7 @@ static bool adjustPositionFromRCInput(void)
{ {
bool retValue; bool retValue;
static uint32_t brakingModeDisengageAt = 0; static uint32_t brakingModeDisengageAt = 0;
static uint32_t brakingBoostModeDisengageAt = 0;
if (STATE(FIXED_WING)) { if (STATE(FIXED_WING)) {
retValue = adjustFixedWingPositionFromRCInput(); retValue = adjustFixedWingPositionFromRCInput();
@ -1993,7 +1999,7 @@ static bool adjustPositionFromRCInput(void)
DEBUG_SET(DEBUG_BRAKING, 0, 1); DEBUG_SET(DEBUG_BRAKING, 0, 1);
//Set forced BRAKING disengage moment //Set forced BRAKING disengage moment
brakingModeDisengageAt = millis() + 500; brakingModeDisengageAt = millis() + navConfig()->mc.braking_timeout;
} }
//Forced BRAKING disengage routine //Forced BRAKING disengage routine
@ -2009,7 +2015,7 @@ static bool adjustPositionFromRCInput(void)
* Case when we were braking but copter finally stopped or we started to move the sticks * Case when we were braking but copter finally stopped or we started to move the sticks
*/ */
if (STATE(NAV_CRUISE_BRAKING) && ( if (STATE(NAV_CRUISE_BRAKING) && (
posControl.actualState.velXY <= navConfig()->mc.braking_speed_threshold || posControl.actualState.velXY <= navConfig()->mc.braking_disengage_speed ||
rcPitchAdjustment || rcPitchAdjustment ||
rcRollAdjustment rcRollAdjustment
)) { )) {

View file

@ -138,11 +138,16 @@ typedef struct navConfig_s {
} general; } general;
struct { struct {
uint8_t max_bank_angle; // multicopter max banking angle (deg) uint8_t max_bank_angle; // multicopter max banking angle (deg)
uint16_t hover_throttle; // multicopter hover throttle uint16_t hover_throttle; // multicopter hover throttle
uint16_t auto_disarm_delay; // multicopter safety delay for landing detector uint16_t auto_disarm_delay; // multicopter safety delay for landing detector
uint16_t braking_speed_threshold; // above this speed braking routine might kick in uint16_t braking_speed_threshold; // above this speed braking routine might kick in
uint8_t braking_boost_factor; uint16_t braking_disengage_speed; // below this speed braking will be disengaged
uint16_t braking_timeout; // Timeout for braking mode
uint8_t braking_boost_factor; // Acceleration boost multiplier at max speed
uint16_t braking_boost_timeout; // Timeout for boost mode
uint16_t braking_boost_speed_threshold; // Above this speed braking boost mode can engage
uint16_t braking_boost_disengage_speed; // Below this speed braking boost will disengage
} mc; } mc;
struct { struct {