AP_MotorsSingle: support 4 servo outputs

This commit is contained in:
Leonard Hall 2016-01-20 13:43:57 +09:00 committed by Randy Mackay
parent f53d6e95e8
commit cffdced838
2 changed files with 40 additions and 8 deletions

View File

@ -68,7 +68,8 @@ void AP_MotorsSingle::Init()
set_update_rate(_speed_hz);
// set the motor_enabled flag so that the main ESC can be calibrated like other frame types
motor_enabled[AP_MOTORS_MOT_7] = true;
motor_enabled[AP_MOTORS_MOT_5] = true;
motor_enabled[AP_MOTORS_MOT_6] = true;
// we set four servos to angle
_servo1.set_type(RC_CHANNEL_TYPE_ANGLE);
@ -97,7 +98,9 @@ void AP_MotorsSingle::set_update_rate( uint16_t speed_hz )
1U << AP_MOTORS_MOT_3 |
1U << AP_MOTORS_MOT_4 ;
rc_set_freq(mask, _servo_speed);
uint32_t mask2 = 1U << AP_MOTORS_MOT_7;
uint32_t mask2 =
1U << AP_MOTORS_MOT_5 |
1U << AP_MOTORS_MOT_6 ;
rc_set_freq(mask2, _speed_hz);
}
@ -109,7 +112,8 @@ void AP_MotorsSingle::enable()
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_7);
rc_enable_ch(AP_MOTORS_MOT_5);
rc_enable_ch(AP_MOTORS_MOT_6);
}
// output_min - sends minimum values out to the motor and trim values to the servos
@ -121,7 +125,8 @@ void AP_MotorsSingle::output_min()
rc_write(AP_MOTORS_MOT_2, _servo2.radio_trim);
rc_write(AP_MOTORS_MOT_3, _servo3.radio_trim);
rc_write(AP_MOTORS_MOT_4, _servo4.radio_trim);
rc_write(AP_MOTORS_MOT_7, _throttle_radio_min);
rc_write(AP_MOTORS_MOT_5, _throttle_radio_min);
rc_write(AP_MOTORS_MOT_6, _throttle_radio_min);
hal.rcout->push();
}
@ -129,8 +134,14 @@ void AP_MotorsSingle::output_min()
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
uint16_t AP_MotorsSingle::get_motor_mask()
{
// single copter uses channels 1,2,3,4 and 7
return rc_map_mask(1U << 0 | 1U << 1 | 1U << 2 | 1U << 3 | 1U << 6);
uint32_t mask =
1U << AP_MOTORS_MOT_1 |
1U << AP_MOTORS_MOT_2 |
1U << AP_MOTORS_MOT_3 |
1U << AP_MOTORS_MOT_4 |
1U << AP_MOTORS_MOT_5 |
1U << AP_MOTORS_MOT_6;
return rc_map_mask(mask);
}
// sends commands to the motors
@ -220,8 +231,12 @@ void AP_MotorsSingle::output_test(uint8_t motor_seq, int16_t pwm)
rc_write(AP_MOTORS_MOT_4, pwm);
break;
case 5:
// spin main motor
rc_write(AP_MOTORS_MOT_7, pwm);
// spin motor 1
rc_write(AP_MOTORS_MOT_5, pwm);
break;
case 6:
// spin motor 2
rc_write(AP_MOTORS_MOT_6, pwm);
break;
default:
// do nothing

View File

@ -70,4 +70,21 @@ protected:
RC_Channel& _servo2;
RC_Channel& _servo3;
RC_Channel& _servo4;
AP_Int8 _servo_1_reverse; // Roll servo signal reversing
AP_Int16 _servo_1_trim; // Trim or center position of roll servo
AP_Int16 _servo_1_min; // Minimum angle limit of roll servo
AP_Int16 _servo_1_max; // Maximum angle limit of roll servo
AP_Int8 _servo_2_reverse; // Pitch servo signal reversing
AP_Int16 _servo_2_trim; // Trim or center position of pitch servo
AP_Int16 _servo_2_min; // Minimum angle limit of pitch servo
AP_Int16 _servo_2_max; // Maximum angle limit of pitch servo
AP_Int8 _servo_3_reverse; // Pitch servo signal reversing
AP_Int16 _servo_3_trim; // Trim or center position of pitch servo
AP_Int16 _servo_3_min; // Minimum angle limit of pitch servo
AP_Int16 _servo_3_max; // Maximum angle limit of pitch servo
AP_Int8 _servo_4_reverse; // Pitch servo signal reversing
AP_Int16 _servo_4_trim; // Trim or center position of pitch servo
AP_Int16 _servo_4_min; // Minimum angle limit of pitch servo
AP_Int16 _servo_4_max; // Maximum angle limit of pitch servo
};