@ -711,181 +711,16 @@ void SRV_Channels::constrain_pwm(SRV_Channel::Aux_servo_function_t function)
@@ -711,181 +711,16 @@ void SRV_Channels::constrain_pwm(SRV_Channel::Aux_servo_function_t function)
}
/*
upgrade RC * parameters into SERVO * parameters . This does the following :
upgrade SERVO * parameters . This does the following :
- copies MIN / MAX / TRIM values from old RC parameters into new RC * parameters and SERVO * parameters .
- copies RCn_FUNCTION to SERVOn_FUNCTION
- maps old RCn_REV to SERVOn_REVERSE and RCn_REVERSE
aux_channel_mask is a bitmask of which channels were RC_Channel_aux channels
Note that this code is highly dependent on the parameter indexing of
the old RC_Channel and RC_Channel_aux objects .
If rcmap is passed in then the vehicle code also wants functions for
the first 4 output channels to be remapped
We return true if an upgrade has been done . This allows the caller
to make any vehicle specific upgrades that may be needed
- update to 16 bit FUNCTION from AP_Int8
*/
bool SRV_Channels : : upgrade_parameters ( const uint8_t rc_keys [ 14 ] , uint16_t aux_channel_mask , RCMapper * rcmap )
void SRV_Channels : : upgrade_parameters ( void )
{
// use SERVO16_FUNCTION as a marker to say that we have run the upgrade already
if ( channels [ 15 ] . function . configured_in_storage ( ) ) {
// upgrade already done
return false ;
}
// old system had 14 RC channels
for ( uint8_t i = 0 ; i < 14 ; i + + ) {
uint8_t k = rc_keys [ i ] ;
if ( k = = 0 ) {
// missing parameter. Some vehicle types didn't have all parameters
continue ;
}
SRV_Channel & srv_chan = channels [ i ] ;
RC_Channel * rc_chan = rc ( ) . channel ( i ) ;
enum {
FLAG_NONE = 0 ,
FLAG_IS_REVERSE = 1 ,
FLAG_AUX_ONLY = 2
} ;
const struct mapping {
uint8_t old_index ;
AP_Param * new_srv_param ;
AP_Param * new_rc_param ;
enum ap_var_type type ;
uint8_t flags ;
} mapping [ ] = {
{ 0 , & srv_chan . servo_min , & rc_chan - > radio_min , AP_PARAM_INT16 , FLAG_NONE } ,
{ 1 , & srv_chan . servo_trim , & rc_chan - > radio_trim , AP_PARAM_INT16 , FLAG_NONE } ,
{ 2 , & srv_chan . servo_max , & rc_chan - > radio_max , AP_PARAM_INT16 , FLAG_NONE } ,
{ 3 , & srv_chan . reversed , & rc_chan - > reversed , AP_PARAM_INT8 , FLAG_IS_REVERSE } ,
{ 1 , & srv_chan . function , nullptr , AP_PARAM_INT8 , FLAG_AUX_ONLY } ,
} ;
bool is_aux = aux_channel_mask & ( 1U < < i ) ;
for ( uint8_t j = 0 ; j < ARRAY_SIZE ( mapping ) ; j + + ) {
const struct mapping & m = mapping [ j ] ;
AP_Param : : ConversionInfo info ;
AP_Int8 v8 ;
AP_Int16 v16 ;
AP_Param * v = m . type = = AP_PARAM_INT16 ? ( AP_Param * ) & v16 : ( AP_Param * ) & v8 ;
bool aux_only = ( m . flags & FLAG_AUX_ONLY ) ! = 0 ;
if ( ! is_aux & & aux_only ) {
continue ;
}
info . old_key = k ;
info . type = m . type ;
info . new_name = nullptr ;
// if this was an aux channel we need to shift by 6 bits, but not for RCn_FUNCTION
info . old_group_element = ( is_aux & & ! aux_only ) ? ( m . old_index < < 6 ) : m . old_index ;
if ( ! AP_Param : : find_old_parameter ( & info , v ) ) {
// the parameter wasn't set in the old eeprom
continue ;
}
if ( m . flags & FLAG_IS_REVERSE ) {
// special mapping from RCn_REV to RCn_REVERSED
v8 . set ( v8 . get ( ) = = - 1 ? 1 : 0 ) ;
}
if ( ! m . new_srv_param - > configured_in_storage ( ) ) {
// not configured yet in new eeprom
if ( m . type = = AP_PARAM_INT16 ) {
( ( AP_Int16 * ) m . new_srv_param ) - > set_and_save_ifchanged ( v16 . get ( ) ) ;
} else {
( ( AP_Int8 * ) m . new_srv_param ) - > set_and_save_ifchanged ( v8 . get ( ) ) ;
}
}
if ( m . new_rc_param & & ! m . new_rc_param - > configured_in_storage ( ) ) {
// not configured yet in new eeprom
if ( m . type = = AP_PARAM_INT16 ) {
( ( AP_Int16 * ) m . new_rc_param ) - > set_and_save_ifchanged ( v16 . get ( ) ) ;
} else {
( ( AP_Int8 * ) m . new_rc_param ) - > set_and_save_ifchanged ( v8 . get ( ) ) ;
}
}
}
}
if ( rcmap ! = nullptr ) {
// we need to make the output functions from the rcmapped inputs
const int8_t func_map [ 4 ] = { channels [ 0 ] . function . get ( ) ,
channels [ 1 ] . function . get ( ) ,
channels [ 2 ] . function . get ( ) ,
channels [ 3 ] . function . get ( ) } ;
const uint8_t map [ 4 ] = { rcmap - > roll ( ) , rcmap - > pitch ( ) , rcmap - > throttle ( ) , rcmap - > yaw ( ) } ;
for ( uint8_t i = 0 ; i < 4 ; i + + ) {
uint8_t m = uint8_t ( map [ i ] - 1 ) ;
if ( m ! = i & & m < 4 ) {
channels [ m ] . function . set_and_save_ifchanged ( func_map [ i ] ) ;
}
}
}
// mark the upgrade as having been done
channels [ 15 ] . function . set_and_save ( channels [ 15 ] . function . get ( ) ) ;
return true ;
}
/*
Upgrade servo MIN / MAX / TRIM / REVERSE parameters for a single AP_Motors
RC_Channel servo from previous firmwares , setting the equivalent
parameter in the new SRV_Channels object
*/
void SRV_Channels : : upgrade_motors_servo ( uint8_t ap_motors_key , uint8_t ap_motors_idx , uint8_t new_channel )
{
SRV_Channel & srv_chan = channels [ new_channel ] ;
enum {
FLAG_NONE = 0 ,
FLAG_IS_REVERSE = 1
} ;
const struct mapping {
uint8_t old_index ;
AP_Param * new_srv_param ;
enum ap_var_type type ;
uint8_t flags ;
} mapping [ ] = {
{ 0 , & srv_chan . servo_min , AP_PARAM_INT16 , FLAG_NONE } ,
{ 1 , & srv_chan . servo_trim , AP_PARAM_INT16 , FLAG_NONE } ,
{ 2 , & srv_chan . servo_max , AP_PARAM_INT16 , FLAG_NONE } ,
{ 3 , & srv_chan . reversed , AP_PARAM_INT8 , FLAG_IS_REVERSE } ,
} ;
for ( uint8_t j = 0 ; j < ARRAY_SIZE ( mapping ) ; j + + ) {
const struct mapping & m = mapping [ j ] ;
AP_Param : : ConversionInfo info ;
AP_Int8 v8 ;
AP_Int16 v16 ;
AP_Param * v = m . type = = AP_PARAM_INT16 ? ( AP_Param * ) & v16 : ( AP_Param * ) & v8 ;
info . old_key = ap_motors_key ;
info . type = m . type ;
info . new_name = nullptr ;
info . old_group_element = ap_motors_idx | ( m . old_index < < 6 ) ;
if ( ! AP_Param : : find_old_parameter ( & info , v ) ) {
// the parameter wasn't set in the old eeprom
continue ;
}
if ( m . flags & FLAG_IS_REVERSE ) {
// special mapping from RCn_REV to RCn_REVERSED
v8 . set ( v8 . get ( ) = = - 1 ? 1 : 0 ) ;
}
// we save even if there is already a value in the new eeprom,
// as that may come from the equivalent RC channel, not the
// old motor servo channel
if ( m . type = = AP_PARAM_INT16 ) {
( ( AP_Int16 * ) m . new_srv_param ) - > set_and_save_ifchanged ( v16 . get ( ) ) ;
} else {
( ( AP_Int8 * ) m . new_srv_param ) - > set_and_save_ifchanged ( v8 . get ( ) ) ;
}
for ( uint8_t i = 0 ; i < NUM_SERVO_CHANNELS ; i + + ) {
SRV_Channel & c = channels [ i ] ;
// convert from AP_Int8 to AP_Int16
c . function . convert_parameter_width ( AP_PARAM_INT8 ) ;
}
}