AP_Motors: removed enable() API

all output channels are already enabled by SRC_Channels::enable_aux_servos()
This commit is contained in:
Andrew Tridgell 2017-04-17 17:12:49 +10:00
parent ed272833c3
commit 03e1f6967f
17 changed files with 2 additions and 109 deletions

View File

@ -72,18 +72,6 @@ void AP_MotorsCoax::set_update_rate( uint16_t speed_hz )
rc_set_freq(mask, _speed_hz);
}
// enable - starts allowing signals to be sent to motors
void AP_MotorsCoax::enable()
{
// enable output channels
rc_enable_ch(AP_MOTORS_MOT_1);
rc_enable_ch(AP_MOTORS_MOT_2);
rc_enable_ch(AP_MOTORS_MOT_3);
rc_enable_ch(AP_MOTORS_MOT_4);
rc_enable_ch(AP_MOTORS_MOT_5);
rc_enable_ch(AP_MOTORS_MOT_6);
}
void AP_MotorsCoax::output_to_motors()
{
switch (_spool_mode) {

View File

@ -37,9 +37,6 @@ public:
// set update rate to motors - a value in hertz
void set_update_rate( uint16_t speed_hz );
// enable - starts allowing signals to be sent to motors
virtual void enable();
// output_test - spin a motor at the pwm value specified
// motor_seq is the motor's sequence number from 1 to the number of motors on the frame
// pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000

View File

@ -68,9 +68,6 @@ public:
// set update rate to motors - a value in hertz
virtual void set_update_rate( uint16_t speed_hz ) = 0;
// enable - starts allowing signals to be sent to motors
virtual void enable() = 0;
// output_min - sets servos to neutral point with motors stopped
void output_min();

View File

@ -193,20 +193,6 @@ void AP_MotorsHeli_Dual::set_update_rate( uint16_t speed_hz )
rc_set_freq(mask, _speed_hz);
}
// enable - starts allowing signals to be sent to motors
void AP_MotorsHeli_Dual::enable()
{
// enable output channels
rc_enable_ch(AP_MOTORS_MOT_1);
rc_enable_ch(AP_MOTORS_MOT_2);
rc_enable_ch(AP_MOTORS_MOT_3);
rc_enable_ch(AP_MOTORS_MOT_4);
rc_enable_ch(AP_MOTORS_MOT_5);
rc_enable_ch(AP_MOTORS_MOT_6);
rc_enable_ch(AP_MOTORS_HELI_DUAL_RSC);
}
// init_outputs
bool AP_MotorsHeli_Dual::init_outputs()
{

View File

@ -54,9 +54,6 @@ public:
// set_update_rate - set update rate to motors
void set_update_rate( uint16_t speed_hz ) override;
// enable - starts allowing signals to be sent to motors
void enable() override;
// output_test - spin a motor at the pwm value specified
void output_test(uint8_t motor_seq, int16_t pwm) override;

View File

@ -157,18 +157,6 @@ void AP_MotorsHeli_Single::set_update_rate( uint16_t speed_hz )
rc_set_freq(mask, _speed_hz);
}
// enable - starts allowing signals to be sent to motors and servos
void AP_MotorsHeli_Single::enable()
{
// enable output channels
rc_enable_ch(AP_MOTORS_MOT_1); // swash servo 1
rc_enable_ch(AP_MOTORS_MOT_2); // swash servo 2
rc_enable_ch(AP_MOTORS_MOT_3); // swash servo 3
rc_enable_ch(AP_MOTORS_MOT_4); // yaw
rc_enable_ch(AP_MOTORS_HELI_SINGLE_AUX); // output for gyro gain or direct drive variable pitch tail motor
rc_enable_ch(AP_MOTORS_HELI_SINGLE_RSC); // output for main rotor esc
}
// init_outputs - initialise Servo/PWM ranges and endpoints
bool AP_MotorsHeli_Single::init_outputs()
{

View File

@ -57,9 +57,6 @@ public:
// set update rate to motors - a value in hertz
void set_update_rate(uint16_t speed_hz) override;
// enable - starts allowing signals to be sent to motors and servos
void enable() override;
// output_test - spin a motor at the pwm value specified
// motor_seq is the motor's sequence number from 1 to the number of motors on the frame
// pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000

View File

@ -72,19 +72,6 @@ void AP_MotorsMatrix::set_frame_class_and_type(motor_frame_class frame_class, mo
set_update_rate(_speed_hz);
}
// enable - starts allowing signals to be sent to motors
void AP_MotorsMatrix::enable()
{
int8_t i;
// enable output channels
for( i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
if( motor_enabled[i] ) {
rc_enable_ch(i);
}
}
}
void AP_MotorsMatrix::output_to_motors()
{
int8_t i;

View File

@ -29,9 +29,6 @@ public:
// you must have setup_motors before calling this
void set_update_rate(uint16_t speed_hz);
// enable - starts allowing signals to be sent to motors
void enable();
// output_test - spin a motor at the pwm value specified
// motor_seq is the motor's sequence number from 1 to the number of motors on the frame
// pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000

View File

@ -78,18 +78,6 @@ void AP_MotorsSingle::set_update_rate( uint16_t speed_hz )
rc_set_freq(mask, _speed_hz);
}
// enable - starts allowing signals to be sent to motors
void AP_MotorsSingle::enable()
{
// enable output channels
rc_enable_ch(AP_MOTORS_MOT_1);
rc_enable_ch(AP_MOTORS_MOT_2);
rc_enable_ch(AP_MOTORS_MOT_3);
rc_enable_ch(AP_MOTORS_MOT_4);
rc_enable_ch(AP_MOTORS_MOT_5);
rc_enable_ch(AP_MOTORS_MOT_6);
}
void AP_MotorsSingle::output_to_motors()
{
if (!_flags.initialised_ok) {

View File

@ -37,9 +37,6 @@ public:
// set update rate to motors - a value in hertz
void set_update_rate( uint16_t speed_hz );
// enable - starts allowing signals to be sent to motors
virtual void enable();
// output_test - spin a motor at the pwm value specified
// motor_seq is the motor's sequence number from 1 to the number of motors on the frame
// pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000

View File

@ -20,7 +20,6 @@ public:
// set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type) {}
void set_update_rate( uint16_t speed_hz ) {}
void enable() {}
void output_test(uint8_t motor_seq, int16_t pwm) {}

View File

@ -75,16 +75,6 @@ void AP_MotorsTri::set_update_rate( uint16_t speed_hz )
rc_set_freq(mask, _speed_hz);
}
// enable - starts allowing signals to be sent to motors
void AP_MotorsTri::enable()
{
// enable output channels
rc_enable_ch(AP_MOTORS_MOT_1);
rc_enable_ch(AP_MOTORS_MOT_2);
rc_enable_ch(AP_MOTORS_MOT_4);
rc_enable_ch(AP_MOTORS_CH_TRI_YAW);
}
void AP_MotorsTri::output_to_motors()
{
switch (_spool_mode) {

View File

@ -32,9 +32,6 @@ public:
// set update rate to motors - a value in hertz
void set_update_rate( uint16_t speed_hz );
// enable - starts allowing signals to be sent to motors
virtual void enable();
// output_test - spin a motor at the pwm value specified
// motor_seq is the motor's sequence number from 1 to the number of motors on the frame
// pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000

View File

@ -125,15 +125,6 @@ void AP_Motors::rc_set_freq(uint32_t mask, uint16_t freq_hz)
}
}
void AP_Motors::rc_enable_ch(uint8_t chan)
{
if (_motor_map_mask & (1U<<chan)) {
// we have a mapped motor number for this channel
chan = _motor_map[chan];
}
hal.rcout->enable_ch(chan);
}
/*
map an internal motor mask to real motor mask
*/

View File

@ -141,9 +141,6 @@ public:
// set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
virtual void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type) = 0;
// enable - starts allowing signals to be sent to motors
virtual void enable() = 0;
// output - sends commands to the motors
virtual void output() = 0;
@ -173,7 +170,6 @@ protected:
virtual void output_armed_stabilizing()=0;
virtual void rc_write(uint8_t chan, uint16_t pwm);
virtual void rc_set_freq(uint32_t mask, uint16_t freq_hz);
virtual void rc_enable_ch(uint8_t chan);
virtual uint32_t rc_map_mask(uint32_t mask) const;
// add a motor to the motor map

View File

@ -29,6 +29,7 @@
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
#include <AP_Scheduler/AP_Scheduler.h>
#include <SRV_Channel/SRV_Channel.h>
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
@ -64,7 +65,6 @@ void setup()
motors.set_throttle_range(1000,2000);
motors.set_throttle_avg_max(0.5f);
#endif
motors.enable();
motors.output_min();
// setup radio
@ -138,6 +138,7 @@ void stability_test()
// arm motors
motors.armed(true);
motors.set_interlock(true);
SRV_Channels::enable_aux_servos();
#if NUM_OUTPUTS <= 4
hal.console->printf("Roll,Pitch,Yaw,Thr,Mot1,Mot2,Mot3,Mot4,AvgOut,LimRP,LimY,LimThD,LimThU\n"); // quad