mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 01:28:29 -04:00
Copter: add Hybrid parameters
This commit is contained in:
parent
754bae5748
commit
f467d7bc20
@ -108,7 +108,9 @@ public:
|
|||||||
k_param_mission, // mission library
|
k_param_mission, // mission library
|
||||||
k_param_rc_13,
|
k_param_rc_13,
|
||||||
k_param_rc_14,
|
k_param_rc_14,
|
||||||
k_param_rally, // 45
|
k_param_rally,
|
||||||
|
k_param_hybrid_brake_rate,
|
||||||
|
k_param_hybrid_brake_angle_max, // 47
|
||||||
|
|
||||||
// 65: AP_Limits Library
|
// 65: AP_Limits Library
|
||||||
k_param_limits = 65, // deprecated - remove
|
k_param_limits = 65, // deprecated - remove
|
||||||
@ -335,6 +337,9 @@ public:
|
|||||||
AP_Float rssi_range; // allows to set max voltage for rssi pin such as 5.0, 3.3 etc.
|
AP_Float rssi_range; // allows to set max voltage for rssi pin such as 5.0, 3.3 etc.
|
||||||
AP_Int8 wp_yaw_behavior; // controls how the autopilot controls yaw during missions
|
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_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
|
||||||
|
|
||||||
// Waypoints
|
// Waypoints
|
||||||
//
|
//
|
||||||
|
@ -407,6 +407,21 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @Values: 0:Very Soft, 25:Soft, 50:Medium, 75:Crisp, 100:Very Crisp
|
// @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),
|
GSCALAR(rc_feel_rp, "RC_FEEL_RP", RC_FEEL_RP_VERY_CRISP),
|
||||||
|
|
||||||
|
// @Param: HYBR_BRAKE_RATE
|
||||||
|
// @DisplayName: Hybrid braking rate
|
||||||
|
// @Description: hybrid flight mode's rotation rate during braking in deg/sec
|
||||||
|
// @Range: 5 8
|
||||||
|
// @User: Advanced
|
||||||
|
GSCALAR(hybrid_brake_rate, "HYBR_BRAKE_RATE", HYBRID_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
|
||||||
|
// @Units: Centi-degrees
|
||||||
|
// @Range: 500 2000
|
||||||
|
// @User: Advanced
|
||||||
|
GSCALAR(hybrid_brake_angle_max, "HYBR_BRAKE_ANGLE", HYBRID_BRAKE_ANGLE_DEFAULT),
|
||||||
|
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
// @Group: HS1_
|
// @Group: HS1_
|
||||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
|
||||||
|
@ -632,6 +632,16 @@
|
|||||||
# define LOITER_RATE_IMAX 400 // maximum acceleration from I term build-up in cm/s/s
|
# define LOITER_RATE_IMAX 400 // maximum acceleration from I term build-up in cm/s/s
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
// Hybrid parameter defaults
|
||||||
|
//
|
||||||
|
#ifndef HYBRID_BRAKE_RATE_DEFAULT
|
||||||
|
# define HYBRID_BRAKE_RATE_DEFAULT 8 // default HYBRID_BRAKE_RATE param value. Rotation rate during braking in deg/sec
|
||||||
|
#endif
|
||||||
|
#ifndef HYBRID_BRAKE_ANGLE_DEFAULT
|
||||||
|
# define HYBRID_BRAKE_ANGLE_DEFAULT 2000 // default HYBRID_BRAKE_ANGLE param value. Max lean angle during braking in centi-degrees
|
||||||
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Throttle control gains
|
// Throttle control gains
|
||||||
//
|
//
|
||||||
|
Loading…
Reference in New Issue
Block a user