@ -74,33 +74,33 @@ void AP_MotorsTri::output_min()
@@ -74,33 +74,33 @@ void AP_MotorsTri::output_min()
limit . throttle_lower = true ;
// send minimum value to each motor
hal . rcout - > write ( _motor_to_channel_map [ AP_MOTORS_MOT_1 ] , _rc_throttle - > radio_min ) ;
hal . rcout - > write ( _motor_to_channel_map [ AP_MOTORS_MOT_2 ] , _rc_throttle - > radio_min ) ;
hal . rcout - > write ( _motor_to_channel_map [ AP_MOTORS_MOT_4 ] , _rc_throttle - > radio_min ) ;
hal . rcout - > write ( _motor_to_channel_map [ AP_MOTORS_CH_TRI_YAW ] , _rc_yaw - > radio_trim ) ;
hal . rcout - > write ( _motor_to_channel_map [ AP_MOTORS_MOT_1 ] , _rc_throttle . radio_min ) ;
hal . rcout - > write ( _motor_to_channel_map [ AP_MOTORS_MOT_2 ] , _rc_throttle . radio_min ) ;
hal . rcout - > write ( _motor_to_channel_map [ AP_MOTORS_MOT_4 ] , _rc_throttle . radio_min ) ;
hal . rcout - > write ( _motor_to_channel_map [ AP_MOTORS_CH_TRI_YAW ] , _rc_yaw . radio_trim ) ;
}
// output_armed - sends commands to the motors
void AP_MotorsTri : : output_armed ( )
{
int16_t out_min = _rc_throttle - > radio_min + _min_throttle ;
int16_t out_max = _rc_throttle - > radio_max ;
int16_t out_min = _rc_throttle . radio_min + _min_throttle ;
int16_t out_max = _rc_throttle . radio_max ;
int16_t motor_out [ AP_MOTORS_MOT_4 + 1 ] ;
// initialize lower limit flag
limit . throttle_lower = false ;
// Throttle is 0 to 1000 only
_rc_throttle - > servo_out = constrain_int16 ( _rc_throttle - > servo_out , 0 , _max_throttle ) ;
_rc_throttle . servo_out = constrain_int16 ( _rc_throttle . servo_out , 0 , _max_throttle ) ;
// capture desired roll, pitch, yaw and throttle from receiver
_rc_roll - > calc_pwm ( ) ;
_rc_pitch - > calc_pwm ( ) ;
_rc_throttle - > calc_pwm ( ) ;
_rc_yaw - > calc_pwm ( ) ;
_rc_roll . calc_pwm ( ) ;
_rc_pitch . calc_pwm ( ) ;
_rc_throttle . calc_pwm ( ) ;
_rc_yaw . calc_pwm ( ) ;
// if we are not sending a throttle output, we cut the motors
if ( _rc_throttle - > servo_out = = 0 ) {
if ( _rc_throttle . servo_out = = 0 ) {
// range check spin_when_armed
if ( _spin_when_armed_ramped < 0 ) {
_spin_when_armed_ramped = 0 ;
@ -108,27 +108,27 @@ void AP_MotorsTri::output_armed()
@@ -108,27 +108,27 @@ void AP_MotorsTri::output_armed()
if ( _spin_when_armed_ramped > _min_throttle ) {
_spin_when_armed_ramped = _min_throttle ;
}
motor_out [ AP_MOTORS_MOT_1 ] = _rc_throttle - > radio_min + _spin_when_armed_ramped ;
motor_out [ AP_MOTORS_MOT_2 ] = _rc_throttle - > radio_min + _spin_when_armed_ramped ;
motor_out [ AP_MOTORS_MOT_4 ] = _rc_throttle - > radio_min + _spin_when_armed_ramped ;
motor_out [ AP_MOTORS_MOT_1 ] = _rc_throttle . radio_min + _spin_when_armed_ramped ;
motor_out [ AP_MOTORS_MOT_2 ] = _rc_throttle . radio_min + _spin_when_armed_ramped ;
motor_out [ AP_MOTORS_MOT_4 ] = _rc_throttle . radio_min + _spin_when_armed_ramped ;
// Every thing is limited
limit . throttle_lower = true ;
} else {
int16_t roll_out = ( float ) _rc_roll - > pwm_out * 0.866f ;
int16_t pitch_out = _rc_pitch - > pwm_out / 2 ;
int16_t roll_out = ( float ) _rc_roll . pwm_out * 0.866f ;
int16_t pitch_out = _rc_pitch . pwm_out / 2 ;
// check if throttle is below limit
if ( _rc_throttle - > radio_out < = out_min ) {
if ( _rc_throttle . radio_out < = out_min ) {
limit . throttle_lower = true ;
}
//left front
motor_out [ AP_MOTORS_MOT_2 ] = _rc_throttle - > radio_out + roll_out + pitch_out ;
motor_out [ AP_MOTORS_MOT_2 ] = _rc_throttle . radio_out + roll_out + pitch_out ;
//right front
motor_out [ AP_MOTORS_MOT_1 ] = _rc_throttle - > radio_out - roll_out + pitch_out ;
motor_out [ AP_MOTORS_MOT_1 ] = _rc_throttle . radio_out - roll_out + pitch_out ;
// rear
motor_out [ AP_MOTORS_MOT_4 ] = _rc_throttle - > radio_out - _rc_pitch - > pwm_out ;
motor_out [ AP_MOTORS_MOT_4 ] = _rc_throttle . radio_out - _rc_pitch . pwm_out ;
// Tridge's stability patch
if ( motor_out [ AP_MOTORS_MOT_1 ] > out_max ) {
@ -171,10 +171,10 @@ void AP_MotorsTri::output_armed()
@@ -171,10 +171,10 @@ void AP_MotorsTri::output_armed()
// note we do not save the radio_out to the motor_out array so it may not appear in the ch7out in the status screen of the mission planner
// note: we use _rc_tail's (aka channel 7's) REV parameter to control whether the servo is reversed or not but this is a bit nonsensical.
// a separate servo object (including min, max settings etc) would be better or at least a separate parameter to specify the direction of the tail servo
if ( _rc_tail - > get_reverse ( ) = = true ) {
hal . rcout - > write ( AP_MOTORS_CH_TRI_YAW , _rc_yaw - > radio_trim - ( _rc_yaw - > radio_out - _rc_yaw - > radio_trim ) ) ;
if ( _rc_tail . get_reverse ( ) = = true ) {
hal . rcout - > write ( AP_MOTORS_CH_TRI_YAW , _rc_yaw . radio_trim - ( _rc_yaw . radio_out - _rc_yaw . radio_trim ) ) ;
} else {
hal . rcout - > write ( AP_MOTORS_CH_TRI_YAW , _rc_yaw - > radio_out ) ;
hal . rcout - > write ( AP_MOTORS_CH_TRI_YAW , _rc_yaw . radio_out ) ;
}
}
@ -191,19 +191,19 @@ void AP_MotorsTri::output_test()
@@ -191,19 +191,19 @@ void AP_MotorsTri::output_test()
// Send minimum values to all motors
output_min ( ) ;
hal . rcout - > write ( _motor_to_channel_map [ AP_MOTORS_MOT_2 ] , _rc_throttle - > radio_min ) ;
hal . rcout - > write ( _motor_to_channel_map [ AP_MOTORS_MOT_2 ] , _rc_throttle . radio_min ) ;
hal . scheduler - > delay ( 4000 ) ;
hal . rcout - > write ( _motor_to_channel_map [ AP_MOTORS_MOT_1 ] , _rc_throttle - > radio_min + _min_throttle ) ;
hal . rcout - > write ( _motor_to_channel_map [ AP_MOTORS_MOT_1 ] , _rc_throttle . radio_min + _min_throttle ) ;
hal . scheduler - > delay ( 300 ) ;
hal . rcout - > write ( _motor_to_channel_map [ AP_MOTORS_MOT_1 ] , _rc_throttle - > radio_min ) ;
hal . rcout - > write ( _motor_to_channel_map [ AP_MOTORS_MOT_1 ] , _rc_throttle . radio_min ) ;
hal . scheduler - > delay ( 2000 ) ;
hal . rcout - > write ( _motor_to_channel_map [ AP_MOTORS_MOT_4 ] , _rc_throttle - > radio_min + _min_throttle ) ;
hal . rcout - > write ( _motor_to_channel_map [ AP_MOTORS_MOT_4 ] , _rc_throttle . radio_min + _min_throttle ) ;
hal . scheduler - > delay ( 300 ) ;
hal . rcout - > write ( _motor_to_channel_map [ AP_MOTORS_MOT_4 ] , _rc_throttle - > radio_min ) ;
hal . rcout - > write ( _motor_to_channel_map [ AP_MOTORS_MOT_4 ] , _rc_throttle . radio_min ) ;
hal . scheduler - > delay ( 2000 ) ;
hal . rcout - > write ( _motor_to_channel_map [ AP_MOTORS_MOT_2 ] , _rc_throttle - > radio_min + _min_throttle ) ;
hal . rcout - > write ( _motor_to_channel_map [ AP_MOTORS_MOT_2 ] , _rc_throttle . radio_min + _min_throttle ) ;
hal . scheduler - > delay ( 300 ) ;
// Send minimum values to all motors