mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-18 20:43:56 -03:00
Copter: rename hybrid to poshold
This commit is contained in:
parent
0fc73a0a21
commit
65e5367619
@ -28,7 +28,7 @@
|
||||
//#define AC_FENCE DISABLED // disable fence to save 2k of flash
|
||||
//#define CAMERA DISABLED // disable camera trigger to save 1k of flash
|
||||
//#define CONFIG_SONAR DISABLED // disable sonar to save 1k of flash
|
||||
//#define HYBRID_ENABLED DISABLED // disable hybrid flight mode to save 4.5k of flash
|
||||
//#define POSHOLD_ENABLED DISABLED // disable PosHold flight mode to save 4.5k of flash
|
||||
|
||||
// features below are disabled by default on APM (but enabled on Pixhawk)
|
||||
//#define AC_RALLY ENABLED // disable rally points to save 2k of flash, and also frees rally point EEPROM for more mission commands
|
||||
|
@ -51,7 +51,7 @@
|
||||
* Jean-Louis Naudin :Auto Landing
|
||||
* John Arne Birkeland :PPM Encoder
|
||||
* Jose Julio :Stabilization Control laws, MPU6k driver
|
||||
* Julien Dubois :Hybrid flight mode
|
||||
* Julien Dubois :PosHold flight mode
|
||||
* Julian Oes :Pixhawk
|
||||
* Jonathan Challinger :Inertial Navigation, CompassMot, Spin-When-Armed
|
||||
* Kevin Hester :Andropilot GCS
|
||||
@ -65,7 +65,7 @@
|
||||
* Robert Lefebvre :Heli Support, Copter LEDs
|
||||
* Roberto Navoni :Library testing, Porting to VRBrain
|
||||
* Sandro Benigno :Camera support, MinimOSD
|
||||
* Sandro Tognana :Hybrid flight mode
|
||||
* Sandro Tognana :PosHold flight mode
|
||||
* ..and many more.
|
||||
*
|
||||
* Code commit statistics can be found here: https://github.com/diydrones/ardupilot/graphs/contributors
|
||||
|
@ -65,7 +65,7 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan)
|
||||
case LOITER:
|
||||
case GUIDED:
|
||||
case CIRCLE:
|
||||
case HYBRID:
|
||||
case POSHOLD:
|
||||
base_mode |= MAV_MODE_FLAG_GUIDED_ENABLED;
|
||||
// note that MAV_MODE_FLAG_AUTO_ENABLED does not match what
|
||||
// APM does in any mode, as that is defined as "system finds its own goal
|
||||
@ -173,7 +173,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
|
||||
case CIRCLE:
|
||||
case LAND:
|
||||
case OF_LOITER:
|
||||
case HYBRID:
|
||||
case POSHOLD:
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
|
||||
break;
|
||||
|
@ -109,8 +109,8 @@ public:
|
||||
k_param_rc_13,
|
||||
k_param_rc_14,
|
||||
k_param_rally,
|
||||
k_param_hybrid_brake_rate,
|
||||
k_param_hybrid_brake_angle_max,
|
||||
k_param_poshold_brake_rate,
|
||||
k_param_poshold_brake_angle_max,
|
||||
k_param_pilot_accel_z,
|
||||
k_param_serial0_baud,
|
||||
k_param_serial1_baud,
|
||||
@ -341,8 +341,8 @@ public:
|
||||
AP_Int8 wp_yaw_behavior; // controls how the autopilot controls yaw during missions
|
||||
AP_Int8 rc_feel_rp; // controls vehicle response to user input with 0 being extremely soft and 100 begin extremely crisp
|
||||
|
||||
AP_Int16 hybrid_brake_rate; // hybrid flight mode's rotation rate during braking in deg/sec
|
||||
AP_Int16 hybrid_brake_angle_max; // hybrid flight mode's max lean angle during braking in centi-degrees
|
||||
AP_Int16 poshold_brake_rate; // PosHold flight mode's rotation rate during braking in deg/sec
|
||||
AP_Int16 poshold_brake_angle_max; // PosHold flight mode's max lean angle during braking in centi-degrees
|
||||
|
||||
// Waypoints
|
||||
//
|
||||
|
@ -287,42 +287,42 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @Param: FLTMODE1
|
||||
// @DisplayName: Flight Mode 1
|
||||
// @Description: Flight mode when Channel 5 pwm is <= 1230
|
||||
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,16:Hybrid
|
||||
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,16:PosHold
|
||||
// @User: Standard
|
||||
GSCALAR(flight_mode1, "FLTMODE1", FLIGHT_MODE_1),
|
||||
|
||||
// @Param: FLTMODE2
|
||||
// @DisplayName: Flight Mode 2
|
||||
// @Description: Flight mode when Channel 5 pwm is >1230, <= 1360
|
||||
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,16:Hybrid
|
||||
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,16:PosHold
|
||||
// @User: Standard
|
||||
GSCALAR(flight_mode2, "FLTMODE2", FLIGHT_MODE_2),
|
||||
|
||||
// @Param: FLTMODE3
|
||||
// @DisplayName: Flight Mode 3
|
||||
// @Description: Flight mode when Channel 5 pwm is >1360, <= 1490
|
||||
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,16:Hybrid
|
||||
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,16:PosHold
|
||||
// @User: Standard
|
||||
GSCALAR(flight_mode3, "FLTMODE3", FLIGHT_MODE_3),
|
||||
|
||||
// @Param: FLTMODE4
|
||||
// @DisplayName: Flight Mode 4
|
||||
// @Description: Flight mode when Channel 5 pwm is >1490, <= 1620
|
||||
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,16:Hybrid
|
||||
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,16:PosHold
|
||||
// @User: Standard
|
||||
GSCALAR(flight_mode4, "FLTMODE4", FLIGHT_MODE_4),
|
||||
|
||||
// @Param: FLTMODE5
|
||||
// @DisplayName: Flight Mode 5
|
||||
// @Description: Flight mode when Channel 5 pwm is >1620, <= 1749
|
||||
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,16:Hybrid
|
||||
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,16:PosHold
|
||||
// @User: Standard
|
||||
GSCALAR(flight_mode5, "FLTMODE5", FLIGHT_MODE_5),
|
||||
|
||||
// @Param: FLTMODE6
|
||||
// @DisplayName: Flight Mode 6
|
||||
// @Description: Flight mode when Channel 5 pwm is >=1750
|
||||
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,16:Hybrid
|
||||
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,16:PosHold
|
||||
// @User: Standard
|
||||
GSCALAR(flight_mode6, "FLTMODE6", FLIGHT_MODE_6),
|
||||
|
||||
@ -409,21 +409,21 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @Values: 0:Very Soft, 25:Soft, 50:Medium, 75:Crisp, 100:Very Crisp
|
||||
GSCALAR(rc_feel_rp, "RC_FEEL_RP", RC_FEEL_RP_VERY_CRISP),
|
||||
|
||||
#if HYBRID_ENABLED == ENABLED
|
||||
// @Param: HYBR_BRAKE_RATE
|
||||
// @DisplayName: Hybrid braking rate
|
||||
// @Description: hybrid flight mode's rotation rate during braking in deg/sec
|
||||
#if POSHOLD_ENABLED == ENABLED
|
||||
// @Param: PHLD_BRAKE_RATE
|
||||
// @DisplayName: PosHold braking rate
|
||||
// @Description: PosHold flight mode's rotation rate during braking in deg/sec
|
||||
// @Range: 4 12
|
||||
// @User: Advanced
|
||||
GSCALAR(hybrid_brake_rate, "HYBR_BRAKE_RATE", HYBRID_BRAKE_RATE_DEFAULT),
|
||||
GSCALAR(poshold_brake_rate, "PHLD_BRAKE_RATE", POSHOLD_BRAKE_RATE_DEFAULT),
|
||||
|
||||
// @Param: HYBR_BRAKE_ANGLE
|
||||
// @DisplayName: Hybrid braking angle max
|
||||
// @Description: hybrid flight mode's max lean angle during braking in centi-degrees
|
||||
// @Param: PHLD_BRAKE_ANGLE
|
||||
// @DisplayName: PosHold braking angle max
|
||||
// @Description: PosHold flight mode's max lean angle during braking in centi-degrees
|
||||
// @Units: Centi-degrees
|
||||
// @Range: 2000 4500
|
||||
// @User: Advanced
|
||||
GSCALAR(hybrid_brake_angle_max, "HYBR_BRAKE_ANGLE", HYBRID_BRAKE_ANGLE_DEFAULT),
|
||||
GSCALAR(poshold_brake_angle_max, "PHLD_BRAKE_ANGLE", POSHOLD_BRAKE_ANGLE_DEFAULT),
|
||||
#endif
|
||||
|
||||
// @Param: LAND_REPOSITION
|
||||
|
@ -636,16 +636,16 @@
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Hybrid parameter defaults
|
||||
// PosHold parameter defaults
|
||||
//
|
||||
#ifndef HYBRID_ENABLED
|
||||
# define HYBRID_ENABLED ENABLED // hybrid flight mode enabled by default
|
||||
#ifndef POSHOLD_ENABLED
|
||||
# define POSHOLD_ENABLED ENABLED // PosHold flight mode enabled by default
|
||||
#endif
|
||||
#ifndef HYBRID_BRAKE_RATE_DEFAULT
|
||||
# define HYBRID_BRAKE_RATE_DEFAULT 8 // default HYBRID_BRAKE_RATE param value. Rotation rate during braking in deg/sec
|
||||
#ifndef POSHOLD_BRAKE_RATE_DEFAULT
|
||||
# define POSHOLD_BRAKE_RATE_DEFAULT 8 // default POSHOLD_BRAKE_RATE param value. Rotation rate during braking in deg/sec
|
||||
#endif
|
||||
#ifndef HYBRID_BRAKE_ANGLE_DEFAULT
|
||||
# define HYBRID_BRAKE_ANGLE_DEFAULT 3000 // default HYBRID_BRAKE_ANGLE param value. Max lean angle during braking in centi-degrees
|
||||
#ifndef POSHOLD_BRAKE_ANGLE_DEFAULT
|
||||
# define POSHOLD_BRAKE_ANGLE_DEFAULT 3000 // default POSHOLD_BRAKE_ANGLE param value. Max lean angle during braking in centi-degrees
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
@ -104,7 +104,7 @@
|
||||
#define SPORT 13 // earth frame rate control
|
||||
#define FLIP 14 // flip the vehicle on the roll axis
|
||||
#define AUTOTUNE 15 // autotune the vehicle's roll and pitch gains
|
||||
#define HYBRID 16 // hybrid - position hold with manual override
|
||||
#define POSHOLD 16 // position hold with manual override
|
||||
#define NUM_MODES 17
|
||||
|
||||
|
||||
|
@ -50,7 +50,7 @@ static void failsafe_radio_on_event()
|
||||
break;
|
||||
case LOITER:
|
||||
case ALT_HOLD:
|
||||
case HYBRID:
|
||||
case POSHOLD:
|
||||
// if landed with throttle at zero disarm, otherwise do the regular thing
|
||||
if (g.rc_3.control_in == 0 && ap.land_complete) {
|
||||
init_disarm_motors();
|
||||
@ -140,7 +140,7 @@ static void failsafe_battery_event(void)
|
||||
break;
|
||||
case LOITER:
|
||||
case ALT_HOLD:
|
||||
case HYBRID:
|
||||
case POSHOLD:
|
||||
// if landed with throttle at zero disarm, otherwise fall through to default handling
|
||||
if (g.rc_3.control_in == 0 && ap.land_complete) {
|
||||
init_disarm_motors();
|
||||
|
@ -87,9 +87,9 @@ static bool set_mode(uint8_t mode)
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if HYBRID_ENABLED == ENABLED
|
||||
case HYBRID:
|
||||
success = hybrid_init(ignore_checks);
|
||||
#if POSHOLD_ENABLED == ENABLED
|
||||
case POSHOLD:
|
||||
success = poshold_init(ignore_checks);
|
||||
break;
|
||||
#endif
|
||||
|
||||
@ -191,9 +191,9 @@ static void update_flight_mode()
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if HYBRID_ENABLED == ENABLED
|
||||
case HYBRID:
|
||||
hybrid_run();
|
||||
#if POSHOLD_ENABLED == ENABLED
|
||||
case POSHOLD:
|
||||
poshold_run();
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
@ -234,7 +234,7 @@ static bool mode_requires_GPS(uint8_t mode) {
|
||||
case RTL:
|
||||
case CIRCLE:
|
||||
case DRIFT:
|
||||
case HYBRID:
|
||||
case POSHOLD:
|
||||
return true;
|
||||
default:
|
||||
return false;
|
||||
@ -307,8 +307,8 @@ print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode)
|
||||
case AUTOTUNE:
|
||||
port->print_P(PSTR("AUTOTUNE"));
|
||||
break;
|
||||
case HYBRID:
|
||||
port->print_P(PSTR("HYBRID"));
|
||||
case POSHOLD:
|
||||
port->print_P(PSTR("POSHOLD"));
|
||||
break;
|
||||
default:
|
||||
port->printf_P(PSTR("Mode(%u)"), (unsigned)mode);
|
||||
|
@ -24,7 +24,7 @@ static void arm_motors_check()
|
||||
}
|
||||
|
||||
// allow arming/disarming in Loiter and AltHold if landed
|
||||
if (ap.land_complete && (control_mode == LOITER || control_mode == ALT_HOLD || control_mode == HYBRID || control_mode == AUTOTUNE)) {
|
||||
if (ap.land_complete && (control_mode == LOITER || control_mode == ALT_HOLD || control_mode == POSHOLD || control_mode == AUTOTUNE)) {
|
||||
allow_arming = true;
|
||||
}
|
||||
|
||||
@ -103,7 +103,7 @@ static void auto_disarm_check()
|
||||
}
|
||||
|
||||
// allow auto disarm in manual flight modes or Loiter/AltHold if we're landed
|
||||
if(manual_flight_mode(control_mode) || (ap.land_complete && (control_mode == LOITER || control_mode == ALT_HOLD || control_mode == HYBRID || control_mode == AUTOTUNE))) {
|
||||
if(manual_flight_mode(control_mode) || (ap.land_complete && (control_mode == LOITER || control_mode == ALT_HOLD || control_mode == POSHOLD || control_mode == AUTOTUNE))) {
|
||||
auto_disarming_counter++;
|
||||
|
||||
if(auto_disarming_counter >= AUTO_DISARMING_DELAY) {
|
||||
|
Loading…
Reference in New Issue
Block a user