mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Copter: renamed MOT_UNSAFE_THR to MOT_SPIN_ARMED
Removed special purpose spin_unsafe function renamed _throttle_unsafe to _spin_when_armed and changed to an AP_Int8
This commit is contained in:
parent
e6412b6996
commit
6477c746cd
@ -124,8 +124,13 @@ void AP_MotorsMatrix::output_armed()
|
|||||||
// if we are not sending a throttle output, we cut the motors
|
// if we are not sending a throttle output, we cut the motors
|
||||||
if (_rc_throttle->servo_out == 0) {
|
if (_rc_throttle->servo_out == 0) {
|
||||||
for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
||||||
|
// range check spin_when_armed
|
||||||
|
if (_spin_when_armed < 0) {
|
||||||
|
_spin_when_armed = 0;
|
||||||
|
}
|
||||||
|
// spin motors at minimum
|
||||||
if (motor_enabled[i]) {
|
if (motor_enabled[i]) {
|
||||||
motor_out[i] = _rc_throttle->radio_min + constrain_int16(_throttle_unsafe,0,AP_MOTORS_THROTTLE_UNSAFE_MAX);
|
motor_out[i] = _rc_throttle->radio_min + _spin_when_armed;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -453,19 +458,6 @@ void AP_MotorsMatrix::output_disarmed()
|
|||||||
output_min();
|
output_min();
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_MotorsMatrix::output_unsafe()
|
|
||||||
{
|
|
||||||
int8_t i;
|
|
||||||
|
|
||||||
// fill the motor_out[] array for HIL use and send minimum value to each motor
|
|
||||||
for( i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
|
|
||||||
if( motor_enabled[i] ) {
|
|
||||||
motor_out[i] = _rc_throttle->radio_min + constrain_int16(_throttle_unsafe,0,AP_MOTORS_THROTTLE_UNSAFE_MAX);;
|
|
||||||
hal.rcout->write(_motor_to_channel_map[i], motor_out[i]);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// output_disarmed - sends commands to the motors
|
// output_disarmed - sends commands to the motors
|
||||||
void AP_MotorsMatrix::output_test()
|
void AP_MotorsMatrix::output_test()
|
||||||
{
|
{
|
||||||
|
@ -50,8 +50,6 @@ public:
|
|||||||
|
|
||||||
// add_motor using just position and yaw_factor (or prop direction)
|
// add_motor using just position and yaw_factor (or prop direction)
|
||||||
void add_motor(int8_t motor_num, float angle_degrees, float yaw_factor, uint8_t testing_order);
|
void add_motor(int8_t motor_num, float angle_degrees, float yaw_factor, uint8_t testing_order);
|
||||||
|
|
||||||
void output_unsafe();
|
|
||||||
|
|
||||||
// remove_motor
|
// remove_motor
|
||||||
void remove_motor(int8_t motor_num);
|
void remove_motor(int8_t motor_num);
|
||||||
|
@ -35,11 +35,11 @@ const AP_Param::GroupInfo AP_Motors::var_info[] PROGMEM = {
|
|||||||
// @Range: 20 80
|
// @Range: 20 80
|
||||||
AP_GROUPINFO("TCRV_MAXPCT", 3, AP_Motors, _throttle_curve_max, THROTTLE_CURVE_MAX_THRUST),
|
AP_GROUPINFO("TCRV_MAXPCT", 3, AP_Motors, _throttle_curve_max, THROTTLE_CURVE_MAX_THRUST),
|
||||||
|
|
||||||
// @Param: UNSAFE_THR
|
// @Param: SPIN_ARMED
|
||||||
// @DisplayName: Armed min throttle
|
// @DisplayName: Motors always spin when armed
|
||||||
// @Description: Throttle setting used to signal that the copter is armed or otherwise unsafe to approach
|
// @Description: Controls whether motors always spin when armed
|
||||||
// @Range: 0 150
|
// @Values: 0:Do Not Spin,50:Slow,90:Medium,130:Fast
|
||||||
AP_GROUPINFO("UNSAFE_THR", 4, AP_Motors, _throttle_unsafe, AP_MOTORS_THROTTLE_UNSAFE),
|
AP_GROUPINFO("SPIN_ARMED", 4, AP_Motors, _spin_when_armed, AP_MOTORS_SPIN_WHEN_ARMED),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
@ -45,8 +45,7 @@
|
|||||||
#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_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 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_SPIN_WHEN_ARMED 0 // spin motors when armed disabled by default
|
||||||
#define AP_MOTORS_THROTTLE_UNSAFE_MAX 150
|
|
||||||
|
|
||||||
// bit mask for recording which limits we have reached when outputting to motors
|
// bit mask for recording which limits we have reached when outputting to motors
|
||||||
#define AP_MOTOR_NO_LIMITS_REACHED 0x00
|
#define AP_MOTOR_NO_LIMITS_REACHED 0x00
|
||||||
@ -85,8 +84,6 @@ public:
|
|||||||
|
|
||||||
// enable - starts allowing signals to be sent to motors
|
// enable - starts allowing signals to be sent to motors
|
||||||
virtual void enable() = 0;
|
virtual void enable() = 0;
|
||||||
|
|
||||||
virtual void output_unsafe() = 0;
|
|
||||||
|
|
||||||
// arm, disarm or check status status of motors
|
// arm, disarm or check status status of motors
|
||||||
bool armed() { return _armed; };
|
bool armed() { return _armed; };
|
||||||
@ -154,7 +151,7 @@ protected:
|
|||||||
|
|
||||||
// for new stability patch
|
// for new stability patch
|
||||||
int16_t _hover_out; // the estimated hover throttle in pwm (i.e. 1000 ~ 2000). calculated from the THR_MID parameter
|
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;
|
AP_Int8 _spin_when_armed; // used to control whether the motors always spin when armed. pwm value above radio_min
|
||||||
};
|
};
|
||||||
#endif // __AP_MOTORS_CLASS_H__
|
#endif // __AP_MOTORS_CLASS_H__
|
||||||
|
Loading…
Reference in New Issue
Block a user