mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: allow tricopter motor 7 to be moved to any output
This commit is contained in:
parent
0e775f595d
commit
f2c63e24c5
|
@ -325,15 +325,8 @@ void AP_MotorsMatrix::add_motor_raw(int8_t motor_num, float roll_fac, float pitc
|
|||
// set order that motor appears in test
|
||||
_test_order[motor_num] = testing_order;
|
||||
|
||||
uint8_t chan;
|
||||
if (RC_Channel_aux::find_channel((RC_Channel_aux::Aux_servo_function_t)(RC_Channel_aux::k_motor1+motor_num),
|
||||
chan)) {
|
||||
_motor_map[motor_num] = chan;
|
||||
_motor_map_mask |= 1U<<motor_num;
|
||||
} else {
|
||||
// disable this channel from being used by RC_Channel_aux
|
||||
RC_Channel_aux::disable_aux_channel(motor_num);
|
||||
}
|
||||
// call parent class method
|
||||
add_motor_num(motor_num);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -80,8 +80,8 @@ void AP_MotorsSingle::Init()
|
|||
_servo3.set_angle(AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
|
||||
_servo4.set_angle(AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
|
||||
|
||||
// disable CH7 from being used as an aux output (i.e. for camera gimbal, etc)
|
||||
RC_Channel_aux::disable_aux_channel(CH_7);
|
||||
// allow mapping of motor7
|
||||
add_motor_num(CH_7);
|
||||
}
|
||||
|
||||
// set update rate to motors - a value in hertz
|
||||
|
|
|
@ -90,8 +90,8 @@ void AP_MotorsTri::Init()
|
|||
motor_enabled[AP_MOTORS_MOT_2] = true;
|
||||
motor_enabled[AP_MOTORS_MOT_4] = true;
|
||||
|
||||
// disable CH7 from being used as an aux output (i.e. for camera gimbal, etc)
|
||||
RC_Channel_aux::disable_aux_channel(AP_MOTORS_CH_TRI_YAW);
|
||||
// allow mapping of motor7
|
||||
add_motor_num(AP_MOTORS_CH_TRI_YAW);
|
||||
}
|
||||
|
||||
// set update rate to motors - a value in hertz
|
||||
|
@ -158,10 +158,10 @@ void AP_MotorsTri::output_to_motors()
|
|||
uint16_t AP_MotorsTri::get_motor_mask()
|
||||
{
|
||||
// tri copter uses channels 1,2,4 and 7
|
||||
return rc_map_mask(1U << AP_MOTORS_MOT_1) |
|
||||
(1U << AP_MOTORS_MOT_2) |
|
||||
(1U << AP_MOTORS_MOT_4) |
|
||||
(1U << AP_MOTORS_CH_TRI_YAW);
|
||||
return rc_map_mask((1U << AP_MOTORS_MOT_1) |
|
||||
(1U << AP_MOTORS_MOT_2) |
|
||||
(1U << AP_MOTORS_MOT_4) |
|
||||
(1U << AP_MOTORS_CH_TRI_YAW));
|
||||
}
|
||||
|
||||
// output_armed - sends commands to the motors
|
||||
|
|
|
@ -173,3 +173,22 @@ int16_t AP_Motors::calc_pwm_output_0to1(float input, const RC_Channel& servo)
|
|||
|
||||
return constrain_int16(ret, servo.radio_min, servo.radio_max);
|
||||
}
|
||||
|
||||
/*
|
||||
add a motor, setting up _motor_map and _motor_map_mask as needed
|
||||
*/
|
||||
void AP_Motors::add_motor_num(int8_t motor_num)
|
||||
{
|
||||
// ensure valid motor number is provided
|
||||
if( motor_num >= 0 && motor_num < AP_MOTORS_MAX_NUM_MOTORS ) {
|
||||
uint8_t chan;
|
||||
if (RC_Channel_aux::find_channel((RC_Channel_aux::Aux_servo_function_t)(RC_Channel_aux::k_motor1+motor_num),
|
||||
chan)) {
|
||||
_motor_map[motor_num] = chan;
|
||||
_motor_map_mask |= 1U<<motor_num;
|
||||
} else {
|
||||
// disable this channel from being used by RC_Channel_aux
|
||||
RC_Channel_aux::disable_aux_channel(motor_num);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -137,6 +137,9 @@ protected:
|
|||
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
|
||||
void add_motor_num(int8_t motor_num);
|
||||
|
||||
// update the throttle input filter
|
||||
virtual void update_throttle_filter() = 0;
|
||||
|
|
Loading…
Reference in New Issue