mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Motors: remove auto_armed
redundant flag that was already held in the main code which is where it belongs.
This commit is contained in:
parent
d2bd818b2d
commit
a656b619f5
@ -250,12 +250,6 @@ void AP_MotorsHeli::output_armed()
|
||||
// output_disarmed - sends commands to the motors
|
||||
void AP_MotorsHeli::output_disarmed()
|
||||
{
|
||||
if(_rc_throttle->control_in > 0) {
|
||||
// we have pushed up the throttle
|
||||
// remove safety
|
||||
_auto_armed = true;
|
||||
}
|
||||
|
||||
// for helis - armed or disarmed we allow servos to move
|
||||
output_armed();
|
||||
}
|
||||
|
@ -272,12 +272,6 @@ void AP_MotorsMatrix::output_armed()
|
||||
// output_disarmed - sends commands to the motors
|
||||
void AP_MotorsMatrix::output_disarmed()
|
||||
{
|
||||
if(_rc_throttle->control_in > 0) {
|
||||
// we have pushed up the throttle
|
||||
// remove safety for auto pilot
|
||||
_auto_armed = true;
|
||||
}
|
||||
|
||||
// Send minimum values to all motors
|
||||
output_min();
|
||||
}
|
||||
|
@ -149,12 +149,6 @@ void AP_MotorsTri::output_armed()
|
||||
// output_disarmed - sends commands to the motors
|
||||
void AP_MotorsTri::output_disarmed()
|
||||
{
|
||||
if(_rc_throttle->control_in > 0) {
|
||||
// we have pushed up the throttle
|
||||
// remove safety
|
||||
_auto_armed = true;
|
||||
}
|
||||
|
||||
// fill the motor_out[] array for HIL use
|
||||
for (unsigned char i = AP_MOTORS_MOT_1; i < AP_MOTORS_MOT_4; i++) {
|
||||
motor_out[i] = _rc_throttle->radio_min;
|
||||
|
@ -48,7 +48,6 @@ AP_Motors::AP_Motors( RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_
|
||||
_rc_yaw(rc_yaw),
|
||||
_speed_hz(speed_hz),
|
||||
_armed(false),
|
||||
_auto_armed(false),
|
||||
_frame_orientation(0),
|
||||
_min_throttle(AP_MOTORS_DEFAULT_MIN_THROTTLE),
|
||||
_max_throttle(AP_MOTORS_DEFAULT_MAX_THROTTLE)
|
||||
|
@ -97,15 +97,6 @@ public:
|
||||
_armed = arm;
|
||||
};
|
||||
|
||||
// check or set status of auto_armed - controls whether autopilot can take control of throttle
|
||||
// Note: this should probably be moved out of this class as it has little to do with the motors
|
||||
virtual bool auto_armed() {
|
||||
return _auto_armed;
|
||||
};
|
||||
virtual void auto_armed(bool arm) {
|
||||
_auto_armed = arm;
|
||||
};
|
||||
|
||||
// set_min_throttle - sets the minimum throttle that will be sent to the engines when they're not off (i.e. to prevents issues with some motors spinning and some not at very low throttle)
|
||||
virtual void set_min_throttle(uint16_t min_throttle) {
|
||||
_min_throttle = min_throttle;
|
||||
@ -116,7 +107,7 @@ public:
|
||||
|
||||
// output - sends commands to the motors
|
||||
virtual void output() {
|
||||
if( _armed && _auto_armed ) { output_armed(); }else{ output_disarmed(); }
|
||||
if( _armed ) { output_armed(); }else{ output_disarmed(); }
|
||||
};
|
||||
|
||||
// output_min - sends minimum values out to the motors
|
||||
@ -168,7 +159,6 @@ protected:
|
||||
uint8_t _motor_to_channel_map[AP_MOTORS_MAX_NUM_MOTORS]; // mapping of motor number (as received from upper APM code) to RC channel output - used to account for differences between APM1 and APM2
|
||||
uint16_t _speed_hz; // speed in hz to send updates to motors
|
||||
bool _armed; // true if motors are armed
|
||||
bool _auto_armed; // true is throttle is above zero, allows auto pilot to take control of throttle
|
||||
uint8_t _frame_orientation; // PLUS_FRAME 0, X_FRAME 1, V_FRAME 2
|
||||
int16_t _min_throttle; // the minimum throttle to be sent to the engines when they're on (prevents issues with some motors on while other off at very low throttle)
|
||||
int16_t _max_throttle; // the minimum throttle to be sent to the engines when they're on (prevents issues with some motors on while other off at very low throttle)
|
||||
|
Loading…
Reference in New Issue
Block a user