2014-02-06 08:28:55 -04:00
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
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/>.
*/
/*
* AP_MotorsSingle . cpp - ArduCopter motors library
* Code by RandyMackay . DIYDrones . com
*
*/
# include <AP_HAL.h>
# include <AP_Math.h>
# include "AP_MotorsCoax.h"
extern const AP_HAL : : HAL & hal ;
const AP_Param : : GroupInfo AP_MotorsCoax : : var_info [ ] PROGMEM = {
// 0 was used by TB_RATIO
// @Param: TCRV_ENABLE
// @DisplayName: Thrust Curve Enable
// @Description: Controls whether a curve is used to linearize the thrust produced by the motors
// @User: Advanced
// @Values: 0:Disabled,1:Enable
AP_GROUPINFO ( " TCRV_ENABLE " , 1 , AP_MotorsCoax , _throttle_curve_enabled , THROTTLE_CURVE_ENABLED ) ,
// @Param: TCRV_MIDPCT
// @DisplayName: Thrust Curve mid-point percentage
// @Description: Set the pwm position that produces half the maximum thrust of the motors
// @User: Advanced
// @Range: 20 80
// @Increment: 1
AP_GROUPINFO ( " TCRV_MIDPCT " , 2 , AP_MotorsCoax , _throttle_curve_mid , THROTTLE_CURVE_MID_THRUST ) ,
// @Param: TCRV_MAXPCT
// @DisplayName: Thrust Curve max thrust percentage
// @Description: Set to the lowest pwm position that produces the maximum thrust of the motors. Most motors produce maximum thrust below the maximum pwm value that they accept.
// @User: Advanced
// @Range: 20 80
// @Increment: 1
AP_GROUPINFO ( " TCRV_MAXPCT " , 3 , AP_MotorsCoax , _throttle_curve_max , THROTTLE_CURVE_MAX_THRUST ) ,
// @Param: SPIN_ARMED
// @DisplayName: Motors always spin when armed
// @Description: Controls whether motors always spin when armed (must be below THR_MIN)
// @Values: 0:Do Not Spin,70:VerySlow,100:Slow,130:Medium,150:Fast
// @User: Standard
AP_GROUPINFO ( " SPIN_ARMED " , 5 , AP_MotorsCoax , _spin_when_armed , AP_MOTORS_SPIN_WHEN_ARMED ) ,
// @Param: REV_ROLL
// @DisplayName: Reverse roll feedback
// @Description: Ensure the feedback is negative
// @Values: -1:Opposite direction,1:Same direction
AP_GROUPINFO ( " REV_ROLL " , 6 , AP_MotorsCoax , _rev_roll , AP_MOTORS_COAX_POSITIVE ) ,
// @Param: REV_PITCH
// @DisplayName: Reverse roll feedback
// @Description: Ensure the feedback is negative
// @Values: -1:Opposite direction,1:Same direction
AP_GROUPINFO ( " REV_PITCH " , 7 , AP_MotorsCoax , _rev_pitch , AP_MOTORS_COAX_POSITIVE ) ,
// @Param: REV_ROLL
// @DisplayName: Reverse roll feedback
// @Description: Ensure the feedback is negative
// @Values: -1:Opposite direction,1:Same direction
AP_GROUPINFO ( " REV_YAW " , 8 , AP_MotorsCoax , _rev_yaw , AP_MOTORS_COAX_POSITIVE ) ,
// @Param: SV_SPEED
// @DisplayName: Servo speed
// @Description: Servo update speed
// @Values: -1:Opposite direction,1:Same direction
AP_GROUPINFO ( " SV_SPEED " , 9 , AP_MotorsCoax , _servo_speed , AP_MOTORS_SINGLE_SPEED_DIGITAL_SERVOS ) ,
AP_GROUPEND
} ;
// init
void AP_MotorsCoax : : Init ( )
{
// call parent Init function to set-up throttle curve
AP_Motors : : Init ( ) ;
2014-02-06 22:57:11 -04:00
// set update rate for the 2 motors (but not the servo on channel 1&2)
2014-02-06 08:28:55 -04:00
set_update_rate ( _speed_hz ) ;
// set the motor_enabled flag so that the ESCs can be calibrated like other frame types
2014-02-06 22:57:11 -04:00
motor_enabled [ AP_MOTORS_MOT_3 ] = true ;
motor_enabled [ AP_MOTORS_MOT_4 ] = true ;
2014-02-06 10:39:30 -04:00
// set ranges for fin servos
2014-02-12 22:52:44 -04:00
_servo1 . set_type ( RC_CHANNEL_TYPE_ANGLE ) ;
_servo2 . set_type ( RC_CHANNEL_TYPE_ANGLE ) ;
_servo1 . set_angle ( AP_MOTORS_COAX_SERVO_INPUT_RANGE ) ;
_servo2 . set_angle ( AP_MOTORS_COAX_SERVO_INPUT_RANGE ) ;
2014-02-06 08:28:55 -04:00
}
// set update rate to motors - a value in hertz
void AP_MotorsCoax : : set_update_rate ( uint16_t speed_hz )
{
// record requested speed
_speed_hz = speed_hz ;
2014-02-06 10:39:30 -04:00
// set update rate for the two motors
uint32_t mask2 =
2014-02-12 22:52:44 -04:00
1U < < pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_3 ] ) |
1U < < pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_4 ] ) ;
2014-02-06 10:39:30 -04:00
hal . rcout - > set_freq ( mask2 , _speed_hz ) ;
// set update rate for the two servos
uint32_t mask =
2014-02-12 22:52:44 -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 ] ) ;
2014-02-06 10:39:30 -04:00
hal . rcout - > set_freq ( mask , _servo_speed ) ;
2014-02-06 08:28:55 -04:00
}
// enable - starts allowing signals to be sent to motors
void AP_MotorsCoax : : enable ( )
{
2014-02-06 10:39:30 -04:00
// enable output channels
2014-02-12 22:52:44 -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_3 ] ) ) ;
hal . rcout - > enable_ch ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_4 ] ) ) ;
2014-02-06 08:28:55 -04:00
}
// output_min - sends minimum values out to the motor and trim values to the servos
void AP_MotorsCoax : : output_min ( )
{
// send minimum value to each motor
2014-02-12 22:52:44 -04:00
hal . rcout - > write ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_1 ] ) , _servo1 . radio_trim ) ;
hal . rcout - > write ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_2 ] ) , _servo2 . radio_trim ) ;
hal . rcout - > write ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_3 ] ) , _rc_throttle . radio_min ) ;
hal . rcout - > write ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_4 ] ) , _rc_throttle . radio_min ) ;
2014-02-06 08:28:55 -04:00
}
// output_armed - sends commands to the motors
void AP_MotorsCoax : : output_armed ( )
{
2014-02-12 22:52:44 -04:00
int16_t out_min = _rc_throttle . radio_min + _min_throttle ;
int16_t motor_out [ 4 ] ;
2014-02-06 08:28:55 -04:00
// Throttle is 0 to 1000 only
2014-02-12 22:52:44 -04:00
_rc_throttle . servo_out = constrain_int16 ( _rc_throttle . servo_out , 0 , _max_throttle ) ;
2014-02-06 08:28:55 -04:00
2014-02-08 17:23:08 -04:00
// capture desired throttle and yaw from receiver
2014-02-12 22:52:44 -04:00
_rc_throttle . calc_pwm ( ) ;
_rc_yaw . calc_pwm ( ) ;
2014-02-06 08:28:55 -04:00
// if we are not sending a throttle output, we cut the motors
2014-02-12 22:52:44 -04:00
if ( _rc_throttle . servo_out = = 0 ) {
2014-02-06 08:28:55 -04:00
// range check spin_when_armed
if ( _spin_when_armed < 0 ) {
_spin_when_armed = 0 ;
}
if ( _spin_when_armed > _min_throttle ) {
_spin_when_armed = _min_throttle ;
}
2014-02-12 22:52:44 -04:00
motor_out [ AP_MOTORS_MOT_3 ] = _rc_throttle . radio_min + _spin_when_armed ;
motor_out [ AP_MOTORS_MOT_4 ] = _rc_throttle . radio_min + _spin_when_armed ;
2014-02-06 08:28:55 -04:00
} else {
2014-02-06 10:39:30 -04:00
// motors
2014-02-12 22:52:44 -04:00
motor_out [ AP_MOTORS_MOT_3 ] = _rev_yaw * _rc_yaw . pwm_out + _rc_throttle . radio_out ;
motor_out [ AP_MOTORS_MOT_4 ] = - _rev_yaw * _rc_yaw . pwm_out + _rc_throttle . radio_out ;
2014-02-06 10:39:30 -04:00
// front
2014-02-12 22:52:44 -04:00
_servo1 . servo_out = _rev_roll * _rc_roll . servo_out ;
2014-02-06 10:39:30 -04:00
// right
2014-02-12 22:52:44 -04:00
_servo2 . servo_out = _rev_pitch * _rc_pitch . servo_out ;
_servo1 . calc_pwm ( ) ;
_servo2 . calc_pwm ( ) ;
2014-02-06 08:28:55 -04:00
// adjust for throttle curve
if ( _throttle_curve_enabled ) {
2014-02-06 22:57:11 -04:00
motor_out [ AP_MOTORS_MOT_3 ] = _throttle_curve . get_y ( motor_out [ AP_MOTORS_MOT_3 ] ) ;
motor_out [ AP_MOTORS_MOT_4 ] = _throttle_curve . get_y ( motor_out [ AP_MOTORS_MOT_4 ] ) ;
2014-02-06 08:28:55 -04:00
}
// ensure motors don't drop below a minimum value and stop
2014-02-06 22:57:11 -04:00
motor_out [ AP_MOTORS_MOT_3 ] = max ( motor_out [ AP_MOTORS_MOT_3 ] , out_min ) ;
motor_out [ AP_MOTORS_MOT_4 ] = max ( motor_out [ AP_MOTORS_MOT_4 ] , out_min ) ;
2014-02-06 08:28:55 -04:00
}
// send output to each motor
2014-02-12 22:52:44 -04:00
hal . rcout - > write ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_1 ] ) , _servo1 . radio_out ) ;
hal . rcout - > write ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_2 ] ) , _servo2 . radio_out ) ;
hal . rcout - > write ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_3 ] ) , motor_out [ AP_MOTORS_MOT_3 ] ) ;
hal . rcout - > write ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_4 ] ) , motor_out [ AP_MOTORS_MOT_4 ] ) ;
2014-02-06 08:28:55 -04:00
}
// output_disarmed - sends commands to the motors
void AP_MotorsCoax : : output_disarmed ( )
{
// Send minimum values to all motors
output_min ( ) ;
}
2014-04-28 04:29:30 -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_MotorsCoax : : output_test ( uint8_t motor_seq , int16_t pwm )
2014-02-06 08:28:55 -04:00
{
2014-04-28 04:29:30 -03:00
// exit immediately if not armed
if ( ! _flags . armed ) {
return ;
}
2014-02-06 08:28:55 -04:00
2014-04-28 04:29:30 -03:00
// output to motors and servos
switch ( motor_seq ) {
case 1 :
// flap servo 1
hal . rcout - > write ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_1 ] ) , pwm ) ;
break ;
case 2 :
// flap servo 2
hal . rcout - > write ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_2 ] ) , pwm ) ;
break ;
case 3 :
// motor 1
hal . rcout - > write ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_3 ] ) , pwm ) ;
break ;
case 4 :
// motor 2
hal . rcout - > write ( pgm_read_byte ( & _motor_to_channel_map [ AP_MOTORS_MOT_4 ] ) , pwm ) ;
break ;
default :
// do nothing
break ;
}
2014-02-06 08:28:55 -04:00
}