mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_Motors: Added MOT_UNSAFE_THR parameter - Throttle setting used to signal that the copter is armed or otherwise unsafe to approach
This commit is contained in:
parent
81bb4f26a1
commit
ae2b1e3b7e
@ -125,7 +125,7 @@ void AP_MotorsMatrix::output_armed()
|
||||
if (_rc_throttle->servo_out == 0) {
|
||||
for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
||||
if (motor_enabled[i]) {
|
||||
motor_out[i] = _rc_throttle->radio_min;
|
||||
motor_out[i] = _rc_throttle->radio_min + constrain_int16(_throttle_unsafe,0,AP_MOTORS_THROTTLE_UNSAFE_MAX);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -34,6 +34,12 @@ const AP_Param::GroupInfo AP_Motors::var_info[] PROGMEM = {
|
||||
// @Description: Set to the lowest pwm position that produces the maximum thrust of the motors. Most motors produce maximum thrust below the maximum pwm value that they accept.
|
||||
// @Range: 20 80
|
||||
AP_GROUPINFO("TCRV_MAXPCT", 3, AP_Motors, _throttle_curve_max, THROTTLE_CURVE_MAX_THRUST),
|
||||
|
||||
// @Param: UNSAFE_THR
|
||||
// @DisplayName: Armed min throttle
|
||||
// @Description: Throttle setting used to signal that the copter is armed or otherwise unsafe to approach
|
||||
// @Range: 0 150
|
||||
AP_GROUPINFO("UNSAFE_THR", 4, AP_Motors, _throttle_unsafe, AP_MOTORS_THROTTLE_UNSAFE),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
@ -45,6 +45,9 @@
|
||||
#define THROTTLE_CURVE_MID_THRUST 52 // throttle which produces 1/2 the maximum thrust. expressed as a percentage of the full throttle range (i.e 0 ~ 100)
|
||||
#define THROTTLE_CURVE_MAX_THRUST 93 // throttle which produces the maximum thrust. expressed as a percentage of the full throttle range (i.e 0 ~ 100)
|
||||
|
||||
#define AP_MOTORS_THROTTLE_UNSAFE 75
|
||||
#define AP_MOTORS_THROTTLE_UNSAFE_MAX 150
|
||||
|
||||
// bit mask for recording which limits we have reached when outputting to motors
|
||||
#define AP_MOTOR_NO_LIMITS_REACHED 0x00
|
||||
#define AP_MOTOR_ROLLPITCH_LIMIT 0x01
|
||||
@ -149,5 +152,7 @@ protected:
|
||||
|
||||
// for new stability patch
|
||||
int16_t _hover_out; // the estimated hover throttle in pwm (i.e. 1000 ~ 2000). calculated from the THR_MID parameter
|
||||
//Throttle setting used to signal that the copter is armed or otherwise unsafe to approach
|
||||
AP_Int16 _throttle_unsafe;
|
||||
};
|
||||
#endif // __AP_MOTORS_CLASS_H__
|
||||
|
Loading…
Reference in New Issue
Block a user