ardupilot/ArduCopter/system.cpp

673 lines
21 KiB
C++
Raw Normal View History

#include "Copter.h"
/*****************************************************************************
2012-08-21 23:19:50 -03:00
* The init_ardupilot function processes everything we need for an in - air restart
* We will determine later if we are actually on the ground and process a
* ground start in that case.
*
*****************************************************************************/
static void mavlink_delay_cb_static()
{
copter.mavlink_delay_cb();
}
static void failsafe_check_static()
{
copter.failsafe_check();
}
void Copter::init_ardupilot()
{
// initialise serial port
serial_manager.init_console();
2014-02-25 18:40:29 -04:00
// init vehicle capabilties
init_capabilities();
hal.console->printf("\n\nInit %s"
2017-08-11 01:08:41 -03:00
"\n\nFree RAM: %u\n",
fwver.fw_string,
2017-08-11 01:08:41 -03:00
(unsigned)hal.util->available_memory());
2012-08-21 23:19:50 -03:00
//
// Report firmware version code expect on console (check of actual EEPROM format version is done in load_parameters function)
2012-08-21 23:19:50 -03:00
//
report_version();
2012-02-12 07:27:51 -04:00
// load parameters from EEPROM
load_parameters();
2018-02-13 01:46:47 -04:00
// time per loop - this gets updated in the main loop() based on
// actual loop rate
G_Dt = 1.0 / scheduler.get_loop_rate_hz();
2018-02-28 08:20:57 -04:00
#if STATS_ENABLED == ENABLED
// initialise stats module
g2.stats.init();
2018-02-28 08:20:57 -04:00
#endif
2016-05-30 07:05:06 -03:00
gcs().set_dataflash(&DataFlash);
2014-01-19 21:58:12 -04:00
// identify ourselves correctly with the ground station
mavlink_system.sysid = g.sysid_this_mav;
// initialise serial ports
serial_manager.init();
// setup first port early to allow BoardConfig to report errors
gcs().chan(0).setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 0);
// Register mavlink_delay_cb, which will run anytime you have
// more than 5ms remaining in your call to hal.scheduler->delay
hal.scheduler->register_delay_callback(mavlink_delay_cb_static, 5);
BoardConfig.init();
#if HAL_WITH_UAVCAN
BoardConfig_CAN.init();
#endif
2016-10-28 19:08:22 -03:00
// init cargo gripper
#if GRIPPER_ENABLED == ENABLED
g2.gripper.init();
#endif
// init winch and wheel encoder
winch_init();
// initialise notify system
2014-09-15 03:52:21 -03:00
notify.init(true);
notify_flight_mode();
// initialise battery monitor
battery.init();
// Init RSSI
rssi.init();
2013-05-25 00:21:29 -03:00
barometer.init();
2013-09-20 20:21:17 -03:00
// we start by assuming USB connected, as we initialed the serial
2013-10-29 01:28:27 -03:00
// port with SERIAL0_BAUD. check_usb_mux() fixes this if need be.
ap.usb_connected = true;
2013-09-20 20:21:17 -03:00
check_usb_mux();
2016-05-16 00:33:43 -03:00
// setup telem slots with serial ports
gcs().setup_uarts(serial_manager);
#if FRSKY_TELEM_ENABLED == ENABLED
// setup frsky, and pass a number of parameters to the library
char firmware_buf[50];
snprintf(firmware_buf, sizeof(firmware_buf), "%s %s", fwver.fw_string, get_frame_string());
2016-12-12 06:22:56 -04:00
frsky_telemetry.init(serial_manager, firmware_buf,
get_frame_mav_type(),
2018-02-28 19:32:16 -04:00
&ap.value);
#endif
2011-12-28 00:53:05 -04:00
#if LOGGING_ENABLED == ENABLED
log_init();
2011-12-28 00:53:05 -04:00
#endif
// update motor interlock state
update_using_interlock();
#if FRAME_CONFIG == HELI_FRAME
// trad heli specific initialisation
heli_init();
#endif
#if FRAME_CONFIG == HELI_FRAME
input_manager.set_loop_rate(scheduler.get_loop_rate_hz());
#endif
2012-08-21 23:19:50 -03:00
init_rc_in(); // sets up rc channels from radio
// default frame class to match firmware if possible
set_default_frame_class();
// allocate the motors class
allocate_motors();
// sets up motors and output to escs
init_rc_out();
// motors initialised so parameters can be sent
ap.initialised_params = true;
// initialise which outputs Servo and Relay events can use
ServoRelayEvents.set_channel_mask(~motors->get_motor_mask());
relay.init();
/*
* setup the 'main loop is dead' check. Note that this relies on
* the RC library being initialised.
*/
hal.scheduler->register_timer_failsafe(failsafe_check_static, 1000);
#if BEACON_ENABLED == ENABLED
2017-04-26 14:25:16 -03:00
// give AHRS the range beacon sensor
ahrs.set_beacon(&g2.beacon);
#endif
2012-08-21 23:19:50 -03:00
// Do GPS init
gps.set_log_gps_bit(MASK_LOG_GPS);
gps.init(serial_manager);
2014-02-25 18:40:29 -04:00
init_compass();
#if OPTFLOW == ENABLED
2015-01-02 20:15:46 -04:00
// make optflow available to AHRS
ahrs.set_optflow(&optflow);
#endif
2015-01-02 20:15:46 -04:00
2015-08-13 22:12:10 -03:00
// init Location class
Location_Class::set_ahrs(&ahrs);
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
2015-08-13 22:12:10 -03:00
Location_Class::set_terrain(&terrain);
wp_nav->set_terrain(&terrain);
2015-08-13 22:12:10 -03:00
#endif
#if AC_AVOID_ENABLED == ENABLED
wp_nav->set_avoidance(&avoid);
loiter_nav->set_avoidance(&avoid);
#endif
2015-08-13 22:12:10 -03:00
attitude_control->parameter_sanity_check();
pos_control->set_dt(scheduler.get_loop_period_s());
2012-08-21 23:19:50 -03:00
// init the optical flow sensor
init_optflow();
#if MOUNT == ENABLED
// initialise camera mount
camera_mount.init(serial_manager);
#endif
#if PRECISION_LANDING == ENABLED
// initialise precision landing
init_precland();
#endif
2017-08-04 03:29:06 -03:00
// initialise landing gear position
landinggear.init();
2011-10-18 03:51:47 -03:00
#ifdef USERHOOK_INIT
2012-08-21 23:19:50 -03:00
USERHOOK_INIT
2011-10-18 03:51:47 -03:00
#endif
#if HIL_MODE != HIL_MODE_DISABLED
2014-08-13 10:54:41 -03:00
while (barometer.get_last_update() == 0) {
// the barometer begins updating when we get the first
// HIL_STATE message
gcs().send_text(MAV_SEVERITY_WARNING, "Waiting for first HIL_STATE message");
delay(1000);
}
// set INS to HIL mode
ins.set_hil_mode();
#endif
2012-08-21 23:19:50 -03:00
// read Baro pressure at ground
//-----------------------------
barometer.calibrate();
2012-08-21 23:19:50 -03:00
2016-04-27 08:37:04 -03:00
// initialise rangefinder
init_rangefinder();
2012-08-21 23:19:50 -03:00
// init proximity sensor
init_proximity();
#if BEACON_ENABLED == ENABLED
2016-10-24 02:46:33 -03:00
// init beacons used for non-gps position estimation
g2.beacon.init();
#endif
2016-10-24 02:46:33 -03:00
2017-03-01 07:18:11 -04:00
// init visual odometry
init_visual_odom();
#if RPM_ENABLED == ENABLED
// initialise AP_RPM library
rpm_sensor.init();
#endif
#if MODE_AUTO_ENABLED == ENABLED
// initialise mission library
mission.init();
#endif
#if MODE_SMARTRTL_ENABLED == ENABLED
// initialize SmartRTL
2017-09-08 23:45:31 -03:00
g2.smart_rtl.init();
#endif
2017-07-26 14:14:40 -03:00
// initialise DataFlash library
#if MODE_AUTO_ENABLED == ENABLED
DataFlash.set_mission(&mission);
#endif
DataFlash.setVehicle_Startup_Log_Writer(FUNCTOR_BIND(&copter, &Copter::Log_Write_Vehicle_Startup_Messages, void));
// initialise the flight mode and aux switch
2012-08-21 23:19:50 -03:00
// ---------------------------
reset_control_switch();
init_aux_switches();
2012-08-21 23:19:50 -03:00
startup_INS_ground();
// set landed flags
set_land_complete(true);
set_land_complete_maybe(true);
// we don't want writes to the serial port to cause us to pause
// mid-flight, so set the serial ports non-blocking once we are
// ready to fly
serial_manager.set_blocking_writes_all(false);
// enable CPU failsafe
failsafe_enable();
ins.set_log_raw_bit(MASK_LOG_IMU_RAW);
// enable output to motors
if (arming.rc_calibration_checks(true)) {
enable_motor_output();
}
// disable safety if requested
BoardConfig.init_safety();
2018-02-15 00:37:00 -04:00
// default enable RC override
copter.ap.rc_override_enable = true;
2017-08-11 01:08:41 -03:00
hal.console->printf("\nReady to FLY ");
// flag that initialisation has completed
ap.initialised = true;
2012-12-13 15:48:01 -04:00
}
2012-12-13 15:48:01 -04:00
//******************************************************************************
//This function does all the calibrations, etc. that we need during a ground start
2012-12-13 15:48:01 -04:00
//******************************************************************************
void Copter::startup_INS_ground()
{
2013-01-13 01:04:04 -04:00
// initialise ahrs (may push imu calibration into the mpu6000 if using that device).
ahrs.init();
2014-04-21 05:11:53 -03:00
ahrs.set_vehicle_class(AHRS_VEHICLE_COPTER);
2013-01-13 01:04:04 -04:00
// Warm up and calibrate gyro offsets
2015-12-26 00:00:03 -04:00
ins.init(scheduler.get_loop_rate_hz());
// reset ahrs including gyro bias
ahrs.reset();
}
// position_ok - returns true if the horizontal absolute position is ok and home position is set
bool Copter::position_ok()
{
// return false if ekf failsafe has triggered
if (failsafe.ekf) {
return false;
}
// check ekf position estimate
return (ekf_position_ok() || optflow_position_ok());
}
// ekf_position_ok - returns true if the ekf claims it's horizontal absolute position estimate is ok and home position is set
bool Copter::ekf_position_ok()
{
if (!ahrs.have_inertial_nav()) {
// do not allow navigation with dcm position
return false;
}
// with EKF use filter status and ekf check
nav_filter_status filt_status = inertial_nav.get_filter_status();
// if disarmed we accept a predicted horizontal position
if (!motors->armed()) {
return ((filt_status.flags.horiz_pos_abs || filt_status.flags.pred_horiz_pos_abs));
} else {
// once armed we require a good absolute position and EKF must not be in const_pos_mode
return (filt_status.flags.horiz_pos_abs && !filt_status.flags.const_pos_mode);
}
}
// optflow_position_ok - returns true if optical flow based position estimate is ok
bool Copter::optflow_position_ok()
{
2017-03-01 07:18:11 -04:00
#if OPTFLOW != ENABLED && VISUAL_ODOMETRY_ENABLED != ENABLED
return false;
#else
2017-03-01 07:18:11 -04:00
// return immediately if EKF not used
if (!ahrs.have_inertial_nav()) {
return false;
}
// return immediately if neither optflow nor visual odometry is enabled
bool enabled = false;
#if OPTFLOW == ENABLED
if (optflow.enabled()) {
enabled = true;
}
#endif
#if VISUAL_ODOMETRY_ENABLED == ENABLED
if (g2.visual_odom.enabled()) {
enabled = true;
}
#endif
if (!enabled) {
return false;
}
// get filter status from EKF
nav_filter_status filt_status = inertial_nav.get_filter_status();
// if disarmed we accept a predicted horizontal relative position
if (!motors->armed()) {
return (filt_status.flags.pred_horiz_pos_rel);
} else {
return (filt_status.flags.horiz_pos_rel && !filt_status.flags.const_pos_mode);
}
#endif
}
// update_auto_armed - update status of auto_armed flag
void Copter::update_auto_armed()
{
// disarm checks
if(ap.auto_armed){
// if motors are disarmed, auto_armed should also be false
if(!motors->armed()) {
set_auto_armed(false);
return;
}
// if in stabilize or acro flight mode and throttle is zero, auto-armed should become false
if(flightmode->has_manual_throttle() && ap.throttle_zero && !failsafe.radio) {
set_auto_armed(false);
}
#if FRAME_CONFIG == HELI_FRAME
// if helicopters are on the ground, and the motor is switched off, auto-armed should be false
// so that rotor runup is checked again before attempting to take-off
if(ap.land_complete && !motors->rotor_runup_complete()) {
set_auto_armed(false);
}
#endif // HELI_FRAME
}else{
// arm checks
#if FRAME_CONFIG == HELI_FRAME
// for tradheli if motors are armed and throttle is above zero and the motor is started, auto_armed should be true
if(motors->armed() && !ap.throttle_zero && motors->rotor_runup_complete()) {
2013-11-04 07:54:47 -04:00
set_auto_armed(true);
}
#else
// if motors are armed and throttle is above zero auto_armed should be true
// if motors are armed and we are in throw mode, then auto_armed should be true
if(motors->armed() && (!ap.throttle_zero || control_mode == THROW)) {
set_auto_armed(true);
}
2013-11-04 07:54:47 -04:00
#endif // HELI_FRAME
}
}
void Copter::check_usb_mux(void)
{
bool usb_check = hal.gpio->usb_connected();
if (usb_check == ap.usb_connected) {
return;
}
// the user has switched to/from the telemetry port
ap.usb_connected = usb_check;
}
2014-10-16 21:37:49 -03:00
/*
should we log a message type now?
*/
bool Copter::should_log(uint32_t mask)
2014-10-16 21:37:49 -03:00
{
#if LOGGING_ENABLED == ENABLED
ap.logging_started = DataFlash.logging_started();
return DataFlash.should_log(mask);
#else
return false;
#endif
}
2016-12-12 06:22:56 -04:00
2016-12-13 22:30:13 -04:00
// default frame_class to match firmware if possible
void Copter::set_default_frame_class()
{
if (FRAME_CONFIG == HELI_FRAME &&
2017-08-27 02:38:00 -03:00
g2.frame_class.get() != AP_Motors::MOTOR_FRAME_HELI_DUAL &&
g2.frame_class.get() != AP_Motors::MOTOR_FRAME_HELI_QUAD) {
g2.frame_class.set(AP_Motors::MOTOR_FRAME_HELI);
2016-12-13 22:30:13 -04:00
}
}
2016-12-12 06:22:56 -04:00
// return MAV_TYPE corresponding to frame class
MAV_TYPE Copter::get_frame_mav_type()
2016-12-12 06:22:56 -04:00
{
switch ((AP_Motors::motor_frame_class)g2.frame_class.get()) {
case AP_Motors::MOTOR_FRAME_QUAD:
case AP_Motors::MOTOR_FRAME_UNDEFINED:
2016-12-12 06:22:56 -04:00
return MAV_TYPE_QUADROTOR;
case AP_Motors::MOTOR_FRAME_HEXA:
case AP_Motors::MOTOR_FRAME_Y6:
return MAV_TYPE_HEXAROTOR;
case AP_Motors::MOTOR_FRAME_OCTA:
case AP_Motors::MOTOR_FRAME_OCTAQUAD:
return MAV_TYPE_OCTOROTOR;
case AP_Motors::MOTOR_FRAME_HELI:
case AP_Motors::MOTOR_FRAME_HELI_DUAL:
2017-08-27 02:38:00 -03:00
case AP_Motors::MOTOR_FRAME_HELI_QUAD:
2016-12-12 06:22:56 -04:00
return MAV_TYPE_HELICOPTER;
case AP_Motors::MOTOR_FRAME_TRI:
return MAV_TYPE_TRICOPTER;
case AP_Motors::MOTOR_FRAME_SINGLE:
case AP_Motors::MOTOR_FRAME_COAX:
2017-02-11 01:50:34 -04:00
case AP_Motors::MOTOR_FRAME_TAILSITTER:
2016-12-12 06:22:56 -04:00
return MAV_TYPE_COAXIAL;
2017-05-13 22:15:02 -03:00
case AP_Motors::MOTOR_FRAME_DODECAHEXA:
return MAV_TYPE_HEXAROTOR;
2016-12-12 06:22:56 -04:00
}
// unknown frame so return generic
2016-12-12 06:22:56 -04:00
return MAV_TYPE_GENERIC;
}
// return string corresponding to frame_class
const char* Copter::get_frame_string()
{
switch ((AP_Motors::motor_frame_class)g2.frame_class.get()) {
case AP_Motors::MOTOR_FRAME_QUAD:
return "QUAD";
case AP_Motors::MOTOR_FRAME_HEXA:
return "HEXA";
case AP_Motors::MOTOR_FRAME_Y6:
return "Y6";
case AP_Motors::MOTOR_FRAME_OCTA:
return "OCTA";
case AP_Motors::MOTOR_FRAME_OCTAQUAD:
return "OCTA_QUAD";
case AP_Motors::MOTOR_FRAME_HELI:
return "HELI";
case AP_Motors::MOTOR_FRAME_HELI_DUAL:
return "HELI_DUAL";
2017-08-27 02:38:00 -03:00
case AP_Motors::MOTOR_FRAME_HELI_QUAD:
return "HELI_QUAD";
2016-12-12 06:22:56 -04:00
case AP_Motors::MOTOR_FRAME_TRI:
return "TRI";
case AP_Motors::MOTOR_FRAME_SINGLE:
return "SINGLE";
case AP_Motors::MOTOR_FRAME_COAX:
return "COAX";
2017-02-11 07:29:04 -04:00
case AP_Motors::MOTOR_FRAME_TAILSITTER:
return "TAILSITTER";
2017-05-13 22:15:02 -03:00
case AP_Motors::MOTOR_FRAME_DODECAHEXA:
return "DODECA_HEXA";
2016-12-12 06:22:56 -04:00
case AP_Motors::MOTOR_FRAME_UNDEFINED:
default:
return "UNKNOWN";
}
}
/*
allocate the motors class
*/
void Copter::allocate_motors(void)
{
switch ((AP_Motors::motor_frame_class)g2.frame_class.get()) {
#if FRAME_CONFIG != HELI_FRAME
case AP_Motors::MOTOR_FRAME_QUAD:
case AP_Motors::MOTOR_FRAME_HEXA:
case AP_Motors::MOTOR_FRAME_Y6:
case AP_Motors::MOTOR_FRAME_OCTA:
case AP_Motors::MOTOR_FRAME_OCTAQUAD:
2017-05-13 22:15:02 -03:00
case AP_Motors::MOTOR_FRAME_DODECAHEXA:
default:
motors = new AP_MotorsMatrix(copter.scheduler.get_loop_rate_hz());
motors_var_info = AP_MotorsMatrix::var_info;
break;
case AP_Motors::MOTOR_FRAME_TRI:
motors = new AP_MotorsTri(copter.scheduler.get_loop_rate_hz());
motors_var_info = AP_MotorsTri::var_info;
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_TRICOPTER);
break;
case AP_Motors::MOTOR_FRAME_SINGLE:
motors = new AP_MotorsSingle(copter.scheduler.get_loop_rate_hz());
motors_var_info = AP_MotorsSingle::var_info;
break;
case AP_Motors::MOTOR_FRAME_COAX:
motors = new AP_MotorsCoax(copter.scheduler.get_loop_rate_hz());
motors_var_info = AP_MotorsCoax::var_info;
break;
2017-02-11 01:50:34 -04:00
case AP_Motors::MOTOR_FRAME_TAILSITTER:
motors = new AP_MotorsTailsitter(copter.scheduler.get_loop_rate_hz());
motors_var_info = AP_MotorsTailsitter::var_info;
2017-02-11 01:50:34 -04:00
break;
#else // FRAME_CONFIG == HELI_FRAME
case AP_Motors::MOTOR_FRAME_HELI_DUAL:
motors = new AP_MotorsHeli_Dual(copter.scheduler.get_loop_rate_hz());
motors_var_info = AP_MotorsHeli_Dual::var_info;
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_HELI);
break;
2017-08-27 02:38:00 -03:00
case AP_Motors::MOTOR_FRAME_HELI_QUAD:
motors = new AP_MotorsHeli_Quad(copter.scheduler.get_loop_rate_hz());
motors_var_info = AP_MotorsHeli_Quad::var_info;
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_HELI);
break;
case AP_Motors::MOTOR_FRAME_HELI:
default:
motors = new AP_MotorsHeli_Single(copter.scheduler.get_loop_rate_hz());
motors_var_info = AP_MotorsHeli_Single::var_info;
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_HELI);
break;
#endif
}
if (motors == nullptr) {
AP_HAL::panic("Unable to allocate FRAME_CLASS=%u", (unsigned)g2.frame_class.get());
}
AP_Param::load_object_from_eeprom(motors, motors_var_info);
AP_AHRS_View *ahrs_view = ahrs.create_view(ROTATION_NONE);
if (ahrs_view == nullptr) {
AP_HAL::panic("Unable to allocate AP_AHRS_View");
}
const struct AP_Param::GroupInfo *ac_var_info;
#if FRAME_CONFIG != HELI_FRAME
attitude_control = new AC_AttitudeControl_Multi(*ahrs_view, aparm, *motors, scheduler.get_loop_period_s());
ac_var_info = AC_AttitudeControl_Multi::var_info;
#else
attitude_control = new AC_AttitudeControl_Heli(*ahrs_view, aparm, *motors, scheduler.get_loop_period_s());
ac_var_info = AC_AttitudeControl_Heli::var_info;
#endif
if (attitude_control == nullptr) {
AP_HAL::panic("Unable to allocate AttitudeControl");
}
AP_Param::load_object_from_eeprom(attitude_control, ac_var_info);
pos_control = new AC_PosControl(*ahrs_view, inertial_nav, *motors, *attitude_control);
if (pos_control == nullptr) {
AP_HAL::panic("Unable to allocate PosControl");
}
AP_Param::load_object_from_eeprom(pos_control, pos_control->var_info);
2017-02-11 18:34:00 -04:00
wp_nav = new AC_WPNav(inertial_nav, *ahrs_view, *pos_control, *attitude_control);
if (wp_nav == nullptr) {
AP_HAL::panic("Unable to allocate WPNav");
}
AP_Param::load_object_from_eeprom(wp_nav, wp_nav->var_info);
loiter_nav = new AC_Loiter(inertial_nav, *ahrs_view, *pos_control, *attitude_control);
if (loiter_nav == nullptr) {
AP_HAL::panic("Unable to allocate LoiterNav");
}
AP_Param::load_object_from_eeprom(loiter_nav, loiter_nav->var_info);
#if MODE_CIRCLE_ENABLED == ENABLED
2017-02-11 18:34:00 -04:00
circle_nav = new AC_Circle(inertial_nav, *ahrs_view, *pos_control);
if (circle_nav == nullptr) {
AP_HAL::panic("Unable to allocate CircleNav");
}
AP_Param::load_object_from_eeprom(circle_nav, circle_nav->var_info);
#endif
// reload lines from the defaults file that may now be accessible
AP_Param::reload_defaults_file();
// now setup some frame-class specific defaults
switch ((AP_Motors::motor_frame_class)g2.frame_class.get()) {
case AP_Motors::MOTOR_FRAME_Y6:
attitude_control->get_rate_roll_pid().kP().set_default(0.1);
attitude_control->get_rate_roll_pid().kD().set_default(0.006);
attitude_control->get_rate_pitch_pid().kP().set_default(0.1);
attitude_control->get_rate_pitch_pid().kD().set_default(0.006);
attitude_control->get_rate_yaw_pid().kP().set_default(0.15);
attitude_control->get_rate_yaw_pid().kI().set_default(0.015);
break;
case AP_Motors::MOTOR_FRAME_TRI:
attitude_control->get_rate_yaw_pid().filt_hz().set_default(100);
break;
default:
break;
}
// brushed 16kHz defaults to 16kHz pulses
if (motors->get_pwm_type() >= AP_Motors::PWM_TYPE_BRUSHED) {
g.rc_speed.set_default(16000);
}
if (upgrading_frame_params) {
// do frame specific upgrade. This is only done the first time we run the new firmware
#if FRAME_CONFIG == HELI_FRAME
SRV_Channels::upgrade_motors_servo(Parameters::k_param_motors, 12, CH_1);
SRV_Channels::upgrade_motors_servo(Parameters::k_param_motors, 13, CH_2);
SRV_Channels::upgrade_motors_servo(Parameters::k_param_motors, 14, CH_3);
SRV_Channels::upgrade_motors_servo(Parameters::k_param_motors, 15, CH_4);
#else
if (g2.frame_class == AP_Motors::MOTOR_FRAME_TRI) {
const AP_Param::ConversionInfo tri_conversion_info[] = {
{ Parameters::k_param_motors, 32, AP_PARAM_INT16, "SERVO7_TRIM" },
{ Parameters::k_param_motors, 33, AP_PARAM_INT16, "SERVO7_MIN" },
{ Parameters::k_param_motors, 34, AP_PARAM_INT16, "SERVO7_MAX" },
{ Parameters::k_param_motors, 35, AP_PARAM_FLOAT, "MOT_YAW_SV_ANGLE" },
};
// we need to use CONVERT_FLAG_FORCE as the SERVO7_* parameters will already be set from RC7_*
AP_Param::convert_old_parameters(tri_conversion_info, ARRAY_SIZE(tri_conversion_info), AP_Param::CONVERT_FLAG_FORCE);
const AP_Param::ConversionInfo tri_conversion_info_rev { Parameters::k_param_motors, 31, AP_PARAM_INT8, "SERVO7_REVERSED" };
AP_Param::convert_old_parameter(&tri_conversion_info_rev, 1, AP_Param::CONVERT_FLAG_REVERSE | AP_Param::CONVERT_FLAG_FORCE);
// AP_MotorsTri was converted from having nested var_info to one level
AP_Param::convert_parent_class(Parameters::k_param_motors, motors, motors->var_info);
}
#endif
}
// upgrade parameters. This must be done after allocating the objects
convert_pid_parameters();
}