2013-05-29 20:51:34 -03:00
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2013-08-29 02:34:34 -03:00
/*
This program is free software : you can redistribute it and / or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation , either version 3 of the License , or
( at your option ) any later version .
This program is distributed in the hope that it will be useful ,
but WITHOUT ANY WARRANTY ; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE . See the
GNU General Public License for more details .
You should have received a copy of the GNU General Public License
along with this program . If not , see < http : //www.gnu.org/licenses/>.
*/
2012-04-02 05:26:37 -03:00
/*
2012-08-17 03:20:26 -03:00
* AP_MotorsTri . cpp - ArduCopter motors library
* Code by RandyMackay . DIYDrones . com
*
*/
2012-10-26 20:59:07 -03:00
# include <AP_HAL.h>
# include <AP_Math.h>
2012-04-02 05:26:37 -03:00
# include "AP_MotorsTri.h"
2012-10-26 20:59:07 -03:00
extern const AP_HAL : : HAL & hal ;
2012-04-02 05:26:37 -03:00
// init
void AP_MotorsTri : : Init ( )
{
2012-09-18 11:05:08 -03:00
// call parent Init function to set-up throttle curve
AP_Motors : : Init ( ) ;
2012-08-17 03:20:26 -03:00
// set update rate for the 3 motors (but not the servo on channel 7)
set_update_rate ( _speed_hz ) ;
2013-05-19 05:28:39 -03:00
// set the motor_enabled flag so that the ESCs can be calibrated like other frame types
motor_enabled [ AP_MOTORS_MOT_1 ] = true ;
motor_enabled [ AP_MOTORS_MOT_2 ] = true ;
motor_enabled [ AP_MOTORS_MOT_4 ] = true ;
2014-02-07 09:02:31 -04:00
// 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 ) ;
2012-04-02 05:26:37 -03:00
}
2012-09-13 09:31:13 -03:00
// set update rate to motors - a value in hertz
2012-04-02 05:26:37 -03:00
void AP_MotorsTri : : set_update_rate ( uint16_t speed_hz )
{
2012-08-17 03:20:26 -03:00
// record requested speed
_speed_hz = speed_hz ;
2012-04-02 05:26:37 -03:00
2012-08-17 03:20:26 -03:00
// set update rate for the 3 motors (but not the servo on channel 7)
2013-01-10 00:52:46 -04:00
uint32_t mask =
2014-02-10 02:59:02 -04:00
1U < < pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_1 ] ) |
1U < < pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_2 ] ) |
1U < < pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_4 ] ) ;
2013-01-10 00:52:46 -04:00
hal . rcout - > set_freq ( mask , _speed_hz ) ;
2012-04-02 05:26:37 -03:00
}
2012-08-17 03:20:26 -03:00
// enable - starts allowing signals to be sent to motors
2012-04-02 05:26:37 -03:00
void AP_MotorsTri : : enable ( )
{
2012-08-17 03:20:26 -03:00
// enable output channels
2014-02-10 02:59:02 -04:00
hal . rcout - > enable_ch ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_1 ] ) ) ;
hal . rcout - > enable_ch ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_2 ] ) ) ;
hal . rcout - > enable_ch ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_4 ] ) ) ;
2012-10-26 20:59:07 -03:00
hal . rcout - > enable_ch ( AP_MOTORS_CH_TRI_YAW ) ;
2012-04-02 05:26:37 -03:00
}
// output_min - sends minimum values out to the motors
void AP_MotorsTri : : output_min ( )
{
2013-09-12 14:36:58 -03:00
// set lower limit flag
limit . throttle_lower = true ;
2013-11-27 08:57:32 -04:00
2012-08-17 03:20:26 -03:00
// send minimum value to each motor
2014-02-10 02:59:02 -04:00
hal . rcout - > write ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_1 ] ) , _rc_throttle . radio_min ) ;
hal . rcout - > write ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_2 ] ) , _rc_throttle . radio_min ) ;
hal . rcout - > write ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_4 ] ) , _rc_throttle . radio_min ) ;
2015-04-05 20:25:27 -03:00
hal . rcout - > write ( AP_MOTORS_CH_TRI_YAW , _rc_yaw . radio_trim ) ;
2012-04-02 05:26:37 -03:00
}
2014-07-26 04:27:39 -03:00
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
uint16_t AP_MotorsTri : : get_motor_mask ( )
{
// tri copter uses channels 1,2,4 and 7
2015-04-05 20:25:27 -03:00
return ( 1U < < pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_1 ] ) ) |
( 1U < < pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_2 ] ) ) |
( 1U < < pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_4 ] ) ) |
( 1U < < AP_MOTORS_CH_TRI_YAW ) ;
2014-07-26 04:27:39 -03:00
}
2015-04-02 17:54:15 -03:00
void AP_MotorsTri : : output_armed_not_stabilizing ( )
2012-04-02 05:26:37 -03:00
{
2014-02-10 00:23:09 -04:00
int16_t out_min = _rc_throttle . radio_min + _min_throttle ;
int16_t out_max = _rc_throttle . radio_max ;
2014-02-09 04:48:10 -04:00
int16_t motor_out [ AP_MOTORS_MOT_4 + 1 ] ;
2012-08-17 03:20:26 -03:00
2015-04-02 17:54:15 -03:00
// initialize limits flags
limit . roll_pitch = true ;
limit . yaw = true ;
2013-09-12 14:36:58 -03:00
limit . throttle_lower = false ;
2015-04-02 17:54:15 -03:00
limit . throttle_upper = false ;
int16_t min_thr = rel_pwm_to_thr_range ( _spin_when_armed_ramped ) ;
if ( _rc_throttle . servo_out < = min_thr ) {
_rc_throttle . servo_out = min_thr ;
limit . throttle_lower = true ;
}
if ( _rc_throttle . servo_out > = _hover_out ) {
_rc_throttle . servo_out = _hover_out ;
limit . throttle_upper = true ;
}
_rc_yaw . servo_out = 0 ;
_rc_yaw . calc_pwm ( ) ;
_rc_throttle . calc_pwm ( ) ;
motor_out [ AP_MOTORS_MOT_1 ] = _rc_throttle . radio_out ;
motor_out [ AP_MOTORS_MOT_2 ] = _rc_throttle . radio_out ;
motor_out [ AP_MOTORS_MOT_4 ] = _rc_throttle . radio_out ;
if ( _rc_throttle . radio_out > = out_min ) {
// adjust for thrust curve and voltage scaling
motor_out [ AP_MOTORS_MOT_1 ] = apply_thrust_curve_and_volt_scaling ( motor_out [ AP_MOTORS_MOT_1 ] , out_min , out_max ) ;
motor_out [ AP_MOTORS_MOT_2 ] = apply_thrust_curve_and_volt_scaling ( motor_out [ AP_MOTORS_MOT_2 ] , out_min , out_max ) ;
motor_out [ AP_MOTORS_MOT_4 ] = apply_thrust_curve_and_volt_scaling ( motor_out [ AP_MOTORS_MOT_4 ] , out_min , out_max ) ;
}
// send output to each motor
hal . rcout - > write ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_1 ] ) , motor_out [ AP_MOTORS_MOT_1 ] ) ;
hal . rcout - > write ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_2 ] ) , motor_out [ AP_MOTORS_MOT_2 ] ) ;
hal . rcout - > write ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_4 ] ) , motor_out [ AP_MOTORS_MOT_4 ] ) ;
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 ) ;
}
}
// sends commands to the motors
// TODO pull code that is common to output_armed_not_stabilizing into helper functions
void AP_MotorsTri : : output_armed_stabilizing ( )
{
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 limits flags
limit . roll_pitch = false ;
limit . yaw = false ;
limit . throttle_lower = false ;
limit . throttle_upper = false ;
2013-09-12 14:36:58 -03:00
2012-08-17 03:20:26 -03:00
// Throttle is 0 to 1000 only
2014-10-04 11:27:11 -03:00
if ( _rc_throttle . servo_out < = 0 ) {
_rc_throttle . servo_out = 0 ;
limit . throttle_lower = true ;
}
if ( _rc_throttle . servo_out > = _max_throttle ) {
_rc_throttle . servo_out = _max_throttle ;
limit . throttle_upper = true ;
}
2012-08-17 03:20:26 -03:00
2015-01-21 07:16:34 -04:00
// tricopters limit throttle to 80%
// To-Do: implement improved stability patch and remove this limit
if ( _rc_throttle . servo_out > 800 ) {
_rc_throttle . servo_out = 800 ;
limit . throttle_upper = true ;
}
2012-08-17 03:20:26 -03:00
// capture desired roll, pitch, yaw and throttle from receiver
2014-02-10 00:23:09 -04:00
_rc_roll . calc_pwm ( ) ;
_rc_pitch . calc_pwm ( ) ;
_rc_throttle . calc_pwm ( ) ;
_rc_yaw . calc_pwm ( ) ;
2012-08-17 03:20:26 -03:00
// if we are not sending a throttle output, we cut the motors
2014-02-10 00:23:09 -04:00
if ( _rc_throttle . servo_out = = 0 ) {
2013-07-16 00:46:34 -03:00
// range check spin_when_armed
2013-10-20 02:51:35 -03:00
if ( _spin_when_armed_ramped < 0 ) {
_spin_when_armed_ramped = 0 ;
2013-07-16 00:46:34 -03:00
}
2013-10-20 02:51:35 -03:00
if ( _spin_when_armed_ramped > _min_throttle ) {
_spin_when_armed_ramped = _min_throttle ;
2013-07-16 03:25:57 -03:00
}
2014-02-10 00:23:09 -04:00
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 ;
2013-09-12 14:36:58 -03:00
2013-07-16 00:46:34 -03:00
} else {
2014-02-10 00:23:09 -04:00
int16_t roll_out = ( float ) _rc_roll . pwm_out * 0.866f ;
int16_t pitch_out = _rc_pitch . pwm_out / 2 ;
2013-07-16 00:46:34 -03:00
2013-09-12 14:36:58 -03:00
// check if throttle is below limit
2014-10-04 11:27:11 -03:00
if ( _rc_throttle . servo_out < = _min_throttle ) {
2013-09-12 14:36:58 -03:00
limit . throttle_lower = true ;
2015-03-16 01:42:34 -03:00
_rc_throttle . servo_out = _min_throttle ;
_rc_throttle . calc_pwm ( ) ; // recalculate radio.out
2013-09-12 14:36:58 -03:00
}
2015-04-02 17:54:15 -03:00
// TODO: set limits.roll_pitch and limits.yaw
2013-07-16 00:46:34 -03:00
//left front
2014-02-10 00:23:09 -04:00
motor_out [ AP_MOTORS_MOT_2 ] = _rc_throttle . radio_out + roll_out + pitch_out ;
2013-07-16 00:46:34 -03:00
//right front
2014-02-10 00:23:09 -04:00
motor_out [ AP_MOTORS_MOT_1 ] = _rc_throttle . radio_out - roll_out + pitch_out ;
2013-07-16 00:46:34 -03:00
// rear
2014-02-10 00:23:09 -04:00
motor_out [ AP_MOTORS_MOT_4 ] = _rc_throttle . radio_out - _rc_pitch . pwm_out ;
2013-07-16 00:46:34 -03:00
// Tridge's stability patch
if ( motor_out [ AP_MOTORS_MOT_1 ] > out_max ) {
2013-09-12 14:39:40 -03:00
motor_out [ AP_MOTORS_MOT_2 ] - = ( motor_out [ AP_MOTORS_MOT_1 ] - out_max ) ;
motor_out [ AP_MOTORS_MOT_4 ] - = ( motor_out [ AP_MOTORS_MOT_1 ] - out_max ) ;
2013-07-16 00:46:34 -03:00
motor_out [ AP_MOTORS_MOT_1 ] = out_max ;
}
if ( motor_out [ AP_MOTORS_MOT_2 ] > out_max ) {
2013-09-12 14:39:40 -03:00
motor_out [ AP_MOTORS_MOT_1 ] - = ( motor_out [ AP_MOTORS_MOT_2 ] - out_max ) ;
motor_out [ AP_MOTORS_MOT_4 ] - = ( motor_out [ AP_MOTORS_MOT_2 ] - out_max ) ;
2013-07-16 00:46:34 -03:00
motor_out [ AP_MOTORS_MOT_2 ] = out_max ;
}
if ( motor_out [ AP_MOTORS_MOT_4 ] > out_max ) {
2013-09-12 14:39:40 -03:00
motor_out [ AP_MOTORS_MOT_1 ] - = ( motor_out [ AP_MOTORS_MOT_4 ] - out_max ) ;
motor_out [ AP_MOTORS_MOT_2 ] - = ( motor_out [ AP_MOTORS_MOT_4 ] - out_max ) ;
2013-07-16 00:46:34 -03:00
motor_out [ AP_MOTORS_MOT_4 ] = out_max ;
}
2015-02-21 04:33:37 -04:00
// adjust for thrust curve and voltage scaling
motor_out [ AP_MOTORS_MOT_1 ] = apply_thrust_curve_and_volt_scaling ( motor_out [ AP_MOTORS_MOT_1 ] , out_min , out_max ) ;
motor_out [ AP_MOTORS_MOT_2 ] = apply_thrust_curve_and_volt_scaling ( motor_out [ AP_MOTORS_MOT_2 ] , out_min , out_max ) ;
motor_out [ AP_MOTORS_MOT_4 ] = apply_thrust_curve_and_volt_scaling ( motor_out [ AP_MOTORS_MOT_4 ] , out_min , out_max ) ;
2013-07-16 00:46:34 -03:00
// ensure motors don't drop below a minimum value and stop
motor_out [ AP_MOTORS_MOT_1 ] = max ( motor_out [ AP_MOTORS_MOT_1 ] , out_min ) ;
motor_out [ AP_MOTORS_MOT_2 ] = max ( motor_out [ AP_MOTORS_MOT_2 ] , out_min ) ;
motor_out [ AP_MOTORS_MOT_4 ] = max ( motor_out [ AP_MOTORS_MOT_4 ] , out_min ) ;
2012-08-17 03:20:26 -03:00
}
// send output to each motor
2014-02-10 02:59:02 -04:00
hal . rcout - > write ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_1 ] ) , motor_out [ AP_MOTORS_MOT_1 ] ) ;
hal . rcout - > write ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_2 ] ) , motor_out [ AP_MOTORS_MOT_2 ] ) ;
hal . rcout - > write ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_4 ] ) , motor_out [ AP_MOTORS_MOT_4 ] ) ;
2012-08-17 03:20:26 -03:00
// also send out to tail command (we rely on any auto pilot to have updated the rc_yaw->radio_out to the correct value)
// 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
2014-02-10 00:23:09 -04:00
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 ) ) ;
2012-08-17 03:20:26 -03:00
} else {
2014-02-10 00:23:09 -04:00
hal . rcout - > write ( AP_MOTORS_CH_TRI_YAW , _rc_yaw . radio_out ) ;
2012-08-17 03:20:26 -03:00
}
2012-04-02 05:26:37 -03:00
}
// output_disarmed - sends commands to the motors
void AP_MotorsTri : : output_disarmed ( )
{
2012-08-17 03:20:26 -03:00
// Send minimum values to all motors
output_min ( ) ;
2012-04-02 05:26:37 -03:00
}
2014-04-28 04:30:26 -03:00
// 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
void AP_MotorsTri : : output_test ( uint8_t motor_seq , int16_t pwm )
2012-04-02 05:26:37 -03:00
{
2014-04-28 04:30:26 -03:00
// exit immediately if not armed
2015-04-02 17:54:15 -03:00
if ( ! armed ( ) ) {
2014-04-28 04:30:26 -03:00
return ;
}
2012-10-26 20:59:07 -03:00
2014-04-28 04:30:26 -03:00
// output to motors and servos
switch ( motor_seq ) {
case 1 :
// front right motor
hal . rcout - > write ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_1 ] ) , pwm ) ;
break ;
case 2 :
// back motor
hal . rcout - > write ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_4 ] ) , pwm ) ;
break ;
case 3 :
// back servo
2015-04-05 20:25:27 -03:00
hal . rcout - > write ( AP_MOTORS_CH_TRI_YAW , pwm ) ;
2014-04-28 04:30:26 -03:00
break ;
case 4 :
// front left motor
hal . rcout - > write ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_2 ] ) , pwm ) ;
break ;
default :
// do nothing
break ;
}
2012-10-26 20:59:07 -03:00
}