2013-05-29 20:48:45 -03:00
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2011-09-11 14:13:01 -03:00
# include "RC_Channel_aux.h"
2012-10-26 20:59:16 -03:00
# include <AP_Math.h>
# include <AP_HAL.h>
extern const AP_HAL : : HAL & hal ;
2012-02-11 07:54:21 -04:00
const AP_Param : : GroupInfo RC_Channel_aux : : var_info [ ] PROGMEM = {
2012-08-17 03:22:48 -03:00
AP_NESTEDGROUPINFO ( RC_Channel , 0 ) ,
2012-06-20 19:36:10 -03:00
2012-08-17 03:22:48 -03:00
// @Param: FUNCTION
// @DisplayName: Servo out function
2013-12-15 03:55:48 -04:00
// @Description: Setting this to Disabled(0) will setup this output for control by auto missions or MAVLink servo set commands. any other value will enable the corresponding function
2014-04-01 08:57:49 -03:00
// @Values: 0:Disabled,1:RCPassThru,2:Flap,3:Flap_auto,4:Aileron,6:mount_pan,7:mount_tilt,8:mount_roll,9:mount_open,10:camera_trigger,11:release,12:mount2_pan,13:mount2_tilt,14:mount2_roll,15:mount2_open,16:DifferentialSpoiler1,17:DifferentialSpoiler2,18:AileronWithInput,19:Elevator,20:ElevatorWithInput,21:Rudder,24:Flaperon1,25:Flaperon2,26:GroundSteering,27:Parachute
2012-08-17 03:22:48 -03:00
// @User: Standard
AP_GROUPINFO ( " FUNCTION " , 1 , RC_Channel_aux , function , 0 ) ,
2012-06-20 19:36:10 -03:00
2012-08-17 03:22:48 -03:00
AP_GROUPEND
2012-02-11 07:54:21 -04:00
} ;
2014-03-25 01:42:48 -03:00
RC_Channel_aux * RC_Channel_aux : : _aux_channels [ RC_AUX_MAX_CHANNELS ] ;
2014-02-05 19:04:05 -04:00
uint32_t RC_Channel_aux : : _function_mask ;
2011-09-11 18:07:30 -03:00
2012-06-17 17:53:54 -03:00
/// map a function to a servo channel and output it
2011-09-11 14:13:01 -03:00
void
2014-04-02 22:18:56 -03:00
RC_Channel_aux : : output_ch ( void )
2011-09-11 14:13:01 -03:00
{
2012-09-16 02:50:13 -03:00
// take care of two corner cases
2012-08-17 03:22:48 -03:00
switch ( function )
{
case k_none : // disabled
return ;
case k_manual : // manual
radio_out = radio_in ;
break ;
}
2014-04-02 22:18:56 -03:00
hal . rcout - > write ( _ch_out , radio_out ) ;
}
/*
call output_ch ( ) on all auxillary channels
*/
void
RC_Channel_aux : : output_ch_all ( void )
{
for ( uint8_t i = 0 ; i < RC_AUX_MAX_CHANNELS ; i + + ) {
if ( _aux_channels [ i ] ) {
_aux_channels [ i ] - > output_ch ( ) ;
}
}
2011-09-11 14:13:01 -03:00
}
2011-09-11 18:07:30 -03:00
2014-02-06 06:30:55 -04:00
/*
prevent a channel from being used for auxillary functions
This is used by the copter code to ensure channels used for motors
can ' t be used for auxillary functions
*/
void RC_Channel_aux : : disable_aux_channel ( uint8_t channel )
{
for ( uint8_t i = 0 ; i < RC_AUX_MAX_CHANNELS ; i + + ) {
if ( _aux_channels [ i ] & & _aux_channels [ i ] - > _ch_out = = channel ) {
_aux_channels [ i ] = NULL ;
}
}
}
2014-11-06 02:28:38 -04:00
/*
return the current function for a channel
*/
RC_Channel_aux : : Aux_servo_function_t RC_Channel_aux : : channel_function ( uint8_t channel )
{
for ( uint8_t i = 0 ; i < RC_AUX_MAX_CHANNELS ; i + + ) {
if ( _aux_channels [ i ] & & _aux_channels [ i ] - > _ch_out = = channel ) {
return ( RC_Channel_aux : : Aux_servo_function_t ) _aux_channels [ i ] - > function . get ( ) ;
}
}
return RC_Channel_aux : : k_none ;
}
2012-09-08 02:12:28 -03:00
/// Update the _aux_channels array of pointers to rc_x channels
2012-06-17 17:53:54 -03:00
/// This is to be done before rc_init so that the channels get correctly initialized.
/// It also should be called periodically because the user might change the configuration and
/// expects the changes to take effect instantly
2013-04-25 07:00:55 -03:00
/// Supports up to eight aux servo outputs (typically CH5 ... CH11)
2012-07-18 16:46:14 -03:00
/// All servos must be configured with a single call to this function
2012-08-05 18:48:57 -03:00
/// (do not call this twice with different parameters, the second call will reset the effect of the first call)
2014-02-05 19:04:05 -04:00
void RC_Channel_aux : : update_aux_servo_function ( void )
2011-09-11 18:07:30 -03:00
{
2012-09-08 02:12:28 -03:00
// set auxiliary ranges
2014-02-05 19:04:05 -04:00
for ( uint8_t i = 0 ; i < RC_AUX_MAX_CHANNELS ; i + + ) {
2012-09-08 02:12:28 -03:00
if ( _aux_channels [ i ] = = NULL ) continue ;
RC_Channel_aux : : Aux_servo_function_t function = ( RC_Channel_aux : : Aux_servo_function_t ) _aux_channels [ i ] - > function . get ( ) ;
switch ( function ) {
case RC_Channel_aux : : k_flap :
case RC_Channel_aux : : k_flap_auto :
2014-02-05 21:35:32 -04:00
case RC_Channel_aux : : k_flaperon1 :
case RC_Channel_aux : : k_flaperon2 :
2012-09-08 02:12:28 -03:00
case RC_Channel_aux : : k_egg_drop :
_aux_channels [ i ] - > set_range ( 0 , 100 ) ;
break ;
case RC_Channel_aux : : k_aileron :
2012-11-20 20:47:36 -04:00
case RC_Channel_aux : : k_aileron_with_input :
2013-02-04 17:57:28 -04:00
case RC_Channel_aux : : k_elevator :
case RC_Channel_aux : : k_elevator_with_input :
2012-10-02 23:40:45 -03:00
case RC_Channel_aux : : k_dspoiler1 :
case RC_Channel_aux : : k_dspoiler2 :
2013-06-28 21:14:43 -03:00
case RC_Channel_aux : : k_rudder :
2014-03-04 21:09:02 -04:00
case RC_Channel_aux : : k_steering :
2012-10-02 23:40:45 -03:00
_aux_channels [ i ] - > set_angle ( 4500 ) ;
break ;
2012-09-08 02:12:28 -03:00
default :
break ;
}
}
2014-02-05 19:04:05 -04:00
// create a function mask to make updates master
_function_mask = 0 ;
for ( uint8_t i = 0 ; i < RC_AUX_MAX_CHANNELS ; i + + ) {
if ( _aux_channels [ i ] ) {
RC_Channel_aux : : Aux_servo_function_t function = ( RC_Channel_aux : : Aux_servo_function_t ) _aux_channels [ i ] - > function . get ( ) ;
if ( function < k_nr_aux_servo_functions ) {
_function_mask | = ( 1UL < < ( uint8_t ) function ) ;
}
}
}
2012-09-08 02:12:28 -03:00
}
/// Should be called after the the servo functions have been initialized
2014-02-05 19:04:05 -04:00
void RC_Channel_aux : : enable_aux_servos ( )
2012-09-08 02:12:28 -03:00
{
2014-02-05 19:04:05 -04:00
update_aux_servo_function ( ) ;
2014-02-17 18:22:25 -04:00
// enable all channels that are not set to a valid function. This
// includes k_none servos, which allows those to get their initial
// trim value on startup
2014-02-05 19:04:05 -04:00
for ( uint8_t i = 0 ; i < RC_AUX_MAX_CHANNELS ; i + + ) {
2012-09-08 02:12:28 -03:00
if ( _aux_channels [ i ] ) {
RC_Channel_aux : : Aux_servo_function_t function = ( RC_Channel_aux : : Aux_servo_function_t ) _aux_channels [ i ] - > function . get ( ) ;
// see if it is a valid function
2012-09-16 02:50:13 -03:00
if ( function < RC_Channel_aux : : k_nr_aux_servo_functions ) {
2012-09-08 02:12:28 -03:00
_aux_channels [ i ] - > enable_out ( ) ;
}
}
}
}
2012-10-30 22:38:26 -03:00
/*
set radio_out for all channels matching the given function type
*/
void
RC_Channel_aux : : set_radio ( RC_Channel_aux : : Aux_servo_function_t function , int16_t value )
{
2014-02-05 19:04:05 -04:00
if ( ! function_assigned ( function ) ) {
return ;
}
for ( uint8_t i = 0 ; i < RC_AUX_MAX_CHANNELS ; i + + ) {
2012-10-30 22:38:26 -03:00
if ( _aux_channels [ i ] & & _aux_channels [ i ] - > function . get ( ) = = function ) {
2012-12-18 22:36:35 -04:00
_aux_channels [ i ] - > radio_out = constrain_int16 ( value , _aux_channels [ i ] - > radio_min , _aux_channels [ i ] - > radio_max ) ;
2012-12-06 04:41:42 -04:00
_aux_channels [ i ] - > output ( ) ;
2012-10-30 22:38:26 -03:00
}
}
}
2012-09-08 02:12:28 -03:00
/*
set and save the trim value to radio_in for all channels matching
the given function type
*/
void
RC_Channel_aux : : set_radio_trim ( RC_Channel_aux : : Aux_servo_function_t function )
{
2014-02-05 19:04:05 -04:00
if ( ! function_assigned ( function ) ) {
return ;
}
for ( uint8_t i = 0 ; i < RC_AUX_MAX_CHANNELS ; i + + ) {
2012-09-08 02:12:28 -03:00
if ( _aux_channels [ i ] & & _aux_channels [ i ] - > function . get ( ) = = function ) {
2013-01-24 23:27:22 -04:00
if ( _aux_channels [ i ] - > radio_in ! = 0 ) {
_aux_channels [ i ] - > radio_trim = _aux_channels [ i ] - > radio_in ;
_aux_channels [ i ] - > radio_trim . save ( ) ;
}
2012-09-08 02:12:28 -03:00
}
2012-08-17 03:22:48 -03:00
}
2012-09-08 02:12:28 -03:00
}
/*
set the radio_out value for any channel with the given function to radio_min
*/
void
RC_Channel_aux : : set_radio_to_min ( RC_Channel_aux : : Aux_servo_function_t function )
{
2014-02-05 19:04:05 -04:00
if ( ! function_assigned ( function ) ) {
return ;
}
for ( uint8_t i = 0 ; i < RC_AUX_MAX_CHANNELS ; i + + ) {
2012-09-08 02:12:28 -03:00
if ( _aux_channels [ i ] & & _aux_channels [ i ] - > function . get ( ) = = function ) {
2012-12-06 04:41:42 -04:00
_aux_channels [ i ] - > radio_out = _aux_channels [ i ] - > radio_min ;
_aux_channels [ i ] - > output ( ) ;
2012-09-08 02:12:28 -03:00
}
}
}
/*
set the radio_out value for any channel with the given function to radio_max
*/
void
RC_Channel_aux : : set_radio_to_max ( RC_Channel_aux : : Aux_servo_function_t function )
{
2014-02-05 19:04:05 -04:00
if ( ! function_assigned ( function ) ) {
return ;
}
for ( uint8_t i = 0 ; i < RC_AUX_MAX_CHANNELS ; i + + ) {
2012-09-08 02:12:28 -03:00
if ( _aux_channels [ i ] & & _aux_channels [ i ] - > function . get ( ) = = function ) {
2012-12-06 04:41:42 -04:00
_aux_channels [ i ] - > radio_out = _aux_channels [ i ] - > radio_max ;
_aux_channels [ i ] - > output ( ) ;
2012-09-08 02:12:28 -03:00
}
2012-08-17 03:22:48 -03:00
}
2012-09-08 02:12:28 -03:00
}
2011-09-11 18:07:30 -03:00
2012-10-30 22:38:26 -03:00
/*
set the radio_out value for any channel with the given function to radio_trim
*/
void
RC_Channel_aux : : set_radio_to_trim ( RC_Channel_aux : : Aux_servo_function_t function )
{
2014-02-05 19:04:05 -04:00
if ( ! function_assigned ( function ) ) {
return ;
}
for ( uint8_t i = 0 ; i < RC_AUX_MAX_CHANNELS ; i + + ) {
2012-10-30 22:38:26 -03:00
if ( _aux_channels [ i ] & & _aux_channels [ i ] - > function . get ( ) = = function ) {
_aux_channels [ i ] - > radio_out = _aux_channels [ i ] - > radio_trim ;
2012-12-06 04:41:42 -04:00
_aux_channels [ i ] - > output ( ) ;
2012-10-30 22:38:26 -03:00
}
}
}
2012-08-05 18:48:57 -03:00
/*
2012-09-08 02:12:28 -03:00
copy radio_in to radio_out for a given function
2012-08-17 03:22:48 -03:00
*/
2012-09-08 02:12:28 -03:00
void
2012-11-26 02:16:25 -04:00
RC_Channel_aux : : copy_radio_in_out ( RC_Channel_aux : : Aux_servo_function_t function , bool do_input_output )
2012-09-08 02:12:28 -03:00
{
2014-02-05 19:04:05 -04:00
if ( ! function_assigned ( function ) ) {
return ;
}
for ( uint8_t i = 0 ; i < RC_AUX_MAX_CHANNELS ; i + + ) {
2012-09-08 02:12:28 -03:00
if ( _aux_channels [ i ] & & _aux_channels [ i ] - > function . get ( ) = = function ) {
2012-11-26 02:16:25 -04:00
if ( do_input_output ) {
_aux_channels [ i ] - > input ( ) ;
}
2012-09-08 02:12:28 -03:00
_aux_channels [ i ] - > radio_out = _aux_channels [ i ] - > radio_in ;
2012-11-26 02:16:25 -04:00
if ( do_input_output ) {
_aux_channels [ i ] - > output ( ) ;
}
2012-09-08 02:12:28 -03:00
}
}
2011-09-11 18:07:30 -03:00
}
2012-08-05 18:08:31 -03:00
2012-09-08 02:12:28 -03:00
/*
set servo_out and call calc_pwm ( ) for a given function
*/
2012-08-05 18:08:31 -03:00
void
2012-09-08 02:12:28 -03:00
RC_Channel_aux : : set_servo_out ( RC_Channel_aux : : Aux_servo_function_t function , int16_t value )
2012-08-05 18:08:31 -03:00
{
2014-02-05 19:04:05 -04:00
if ( ! function_assigned ( function ) ) {
return ;
}
for ( uint8_t i = 0 ; i < RC_AUX_MAX_CHANNELS ; i + + ) {
2012-09-08 02:12:28 -03:00
if ( _aux_channels [ i ] & & _aux_channels [ i ] - > function . get ( ) = = function ) {
_aux_channels [ i ] - > servo_out = value ;
_aux_channels [ i ] - > calc_pwm ( ) ;
2012-12-06 04:41:42 -04:00
_aux_channels [ i ] - > output ( ) ;
2012-09-08 02:12:28 -03:00
}
2012-08-17 03:22:48 -03:00
}
2012-08-05 18:08:31 -03:00
}
2014-04-20 21:34:10 -03:00
/*
setup failsafe value for an auxiliary function type to a LimitValue
*/
void
RC_Channel_aux : : set_servo_failsafe ( RC_Channel_aux : : Aux_servo_function_t function , RC_Channel : : LimitValue limit )
{
if ( ! function_assigned ( function ) ) {
return ;
}
for ( uint8_t i = 0 ; i < RC_AUX_MAX_CHANNELS ; i + + ) {
const RC_Channel_aux * ch = _aux_channels [ i ] ;
if ( ch & & ch - > function . get ( ) = = function ) {
uint16_t pwm = ch - > get_limit_pwm ( limit ) ;
hal . rcout - > set_failsafe_pwm ( 1U < < ch - > get_ch_out ( ) , pwm ) ;
}
}
}
/*
set radio output value for an auxiliary function type to a LimitValue
*/
void
RC_Channel_aux : : set_servo_limit ( RC_Channel_aux : : Aux_servo_function_t function , RC_Channel : : LimitValue limit )
{
if ( ! function_assigned ( function ) ) {
return ;
}
for ( uint8_t i = 0 ; i < RC_AUX_MAX_CHANNELS ; i + + ) {
RC_Channel_aux * ch = _aux_channels [ i ] ;
if ( ch & & ch - > function . get ( ) = = function ) {
uint16_t pwm = ch - > get_limit_pwm ( limit ) ;
ch - > radio_out = pwm ;
2014-08-09 03:53:14 -03:00
if ( ch - > function . get ( ) = = k_manual ) {
// in order for output_ch() to work for k_manual we
// also have to override radio_in
ch - > radio_in = pwm ;
}
2014-04-20 21:34:10 -03:00
}
}
}
2012-09-08 02:12:28 -03:00
/*
return true if a particular function is assigned to at least one RC channel
*/
bool
RC_Channel_aux : : function_assigned ( RC_Channel_aux : : Aux_servo_function_t function )
{
2014-02-05 19:04:05 -04:00
if ( function < k_nr_aux_servo_functions ) {
return ( _function_mask & ( 1UL < < function ) ) ! = 0 ;
}
2012-09-08 02:12:28 -03:00
return false ;
}
/*
set servo_out and angle_min / max , then calc_pwm and output a
value . This is used to move a AP_Mount servo
*/
void
RC_Channel_aux : : move_servo ( RC_Channel_aux : : Aux_servo_function_t function ,
int16_t value , int16_t angle_min , int16_t angle_max )
{
2014-02-05 19:04:05 -04:00
if ( ! function_assigned ( function ) ) {
return ;
}
for ( uint8_t i = 0 ; i < RC_AUX_MAX_CHANNELS ; i + + ) {
2012-09-08 02:12:28 -03:00
if ( _aux_channels [ i ] & & _aux_channels [ i ] - > function . get ( ) = = function ) {
_aux_channels [ i ] - > servo_out = value ;
_aux_channels [ i ] - > set_range ( angle_min , angle_max ) ;
_aux_channels [ i ] - > calc_pwm ( ) ;
_aux_channels [ i ] - > output ( ) ;
}
}
}