From 2c6e35750f97d30f4c5679d81f0fa688b759cae1 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 12 Feb 2024 12:24:41 +1100 Subject: [PATCH] kill RCMapper --- AntennaTracker/wscript | 1 - ArduCopter/Copter.h | 3 - ArduCopter/Parameters.cpp | 9 ++- ArduCopter/Parameters.h | 2 +- ArduCopter/radio.cpp | 10 ++- ArduCopter/wscript | 1 - ArduPlane/ArduPlane.cpp | 2 +- ArduPlane/Parameters.cpp | 11 +-- ArduPlane/Parameters.h | 2 +- ArduPlane/Plane.h | 4 - ArduPlane/radio.cpp | 12 +-- ArduPlane/wscript | 1 - ArduSub/Parameters.cpp | 11 ++- ArduSub/Parameters.h | 2 +- ArduSub/Sub.h | 9 --- ArduSub/config.h | 8 -- ArduSub/wscript | 1 - Blimp/Blimp.h | 3 - Blimp/Parameters.cpp | 8 +- Blimp/Parameters.h | 2 +- Blimp/radio.cpp | 10 ++- Blimp/wscript | 1 - Rover/Parameters.cpp | 8 +- Rover/Parameters.h | 2 +- Rover/Rover.h | 4 - Rover/radio.cpp | 6 +- Rover/wscript | 1 - Tools/Replay/wscript | 2 +- Tools/autotest/rover.py | 4 +- libraries/AP_Arming/AP_Arming.cpp | 29 ++++--- libraries/AP_Camera/AP_RunCam.cpp | 8 +- libraries/AP_Camera/AP_RunCam.h | 1 - .../examples/DroneCAN_sniffer/wscript | 1 - libraries/AP_IOMCU/AP_IOMCU.cpp | 20 +++-- libraries/AP_IOMCU/AP_IOMCU.h | 3 +- libraries/AP_MSP/AP_MSP_Telem_Backend.cpp | 40 ++++------ libraries/AP_OSD/AP_OSD.h | 2 +- libraries/AP_OSD/AP_OSD_ParamScreen.cpp | 13 ++-- libraries/AP_Param/AP_Param.h | 6 +- .../AP_Scripting/applets/VTOL-quicktune.lua | 10 +-- libraries/AP_Vehicle/AP_Vehicle.cpp | 5 ++ libraries/RC_Channel/RC_Channel.cpp | 76 ++++++++++++++++++- libraries/RC_Channel/RC_Channel.h | 17 ++++- libraries/RC_Channel/RC_Channels.cpp | 13 +++- libraries/RC_Channel/RC_Channels_VarInfo.h | 9 +++ 45 files changed, 230 insertions(+), 163 deletions(-) diff --git a/AntennaTracker/wscript b/AntennaTracker/wscript index c9fb73b7721415..95c57ee2a6df0e 100644 --- a/AntennaTracker/wscript +++ b/AntennaTracker/wscript @@ -9,7 +9,6 @@ def build(bld): ap_libraries=bld.ap_common_vehicle_libraries() + [ 'AP_Beacon', 'AP_Arming', - 'AP_RCMapper', 'AP_OSD', ], ) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 3c922cb14073fd..13398bdfba9b4b 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -54,7 +54,6 @@ #include // ArduCopter Loiter Mode Library #include // circle navigation library #include // ArduPilot Mega Declination Helper Library -#include // RC input mapping library #include // Battery monitor library #include // Landing Gear library #include // Pilot input handling library @@ -403,8 +402,6 @@ class Copter : public AP_Vehicle { Mode *flightmode; Mode::Number prev_control_mode; - RCMapper rcmap; - // inertial nav alt when we armed float arming_altitude_m; diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 162492ffd86c71..8b8961440d92d2 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -615,10 +615,6 @@ const AP_Param::Info Copter::var_info[] = { GOBJECTVARPTR(motors, "MOT_", &copter.motors_var_info), #endif - // @Group: RCMAP_ - // @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp - GOBJECT(rcmap, "RCMAP_", RCMapper), - #if HAL_NAVEKF2_AVAILABLE // @Group: EK2_ // @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -1392,6 +1388,11 @@ void Copter::load_parameters(void) AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true); #endif + // PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.6 +#if AP_RC_CHANNEL_ENABLED + rc().convert_rcmap_parameters(Parameters::k_param_rcmap_old); +#endif + // setup AP_Param frame type flags AP_Param::set_frame_type_flags(AP_PARAM_FRAME_COPTER); } diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index a7374f37744d5f..d66b0dc21607f5 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -313,7 +313,7 @@ class Parameters { k_param_rc_9_old, k_param_rc_12_old, k_param_failsafe_gcs, - k_param_rcmap, // 199 + k_param_rcmap_old, // 199 // // 200: flight modes diff --git a/ArduCopter/radio.cpp b/ArduCopter/radio.cpp index d39d876c53761b..97428c7ce0773f 100644 --- a/ArduCopter/radio.cpp +++ b/ArduCopter/radio.cpp @@ -20,10 +20,12 @@ void Copter::default_dead_zones() void Copter::init_rc_in() { - channel_roll = rc().channel(rcmap.roll()-1); - channel_pitch = rc().channel(rcmap.pitch()-1); - channel_throttle = rc().channel(rcmap.throttle()-1); - channel_yaw = rc().channel(rcmap.yaw()-1); + auto &_rc = rc(); + + channel_roll = _rc.find_channel_for_option(RC_Channel::AUX_FUNC::ROLL); + channel_pitch = _rc.find_channel_for_option(RC_Channel::AUX_FUNC::PITCH); + channel_throttle = _rc.find_channel_for_option(RC_Channel::AUX_FUNC::THROTTLE); + channel_yaw = _rc.find_channel_for_option(RC_Channel::AUX_FUNC::YAW); // set rc channel ranges channel_roll->set_angle(ROLL_PITCH_YAW_INPUT_MAX); diff --git a/ArduCopter/wscript b/ArduCopter/wscript index 863834ad4ed7de..a196f6ff8ed15a 100644 --- a/ArduCopter/wscript +++ b/ArduCopter/wscript @@ -17,7 +17,6 @@ def build(bld): 'AP_IRLock', 'AP_InertialNav', 'AP_Motors', - 'AP_RCMapper', 'AP_Avoidance', 'AP_AdvancedFailsafe', 'AP_SmartRTL', diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index bab97f46e259c6..23bd5d631fddff 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -315,7 +315,7 @@ void Plane::one_second_loop() set_control_channels(); #if HAL_WITH_IO_MCU - iomcu.setup_mixing(&rcmap, g.override_channel.get(), g.mixing_gain, g2.manual_rc_mask); + iomcu.setup_mixing(g.override_channel.get(), g.mixing_gain, g2.manual_rc_mask); #endif #if HAL_ADSB_ENABLED diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 6d3c1d945652fd..06994dc2c7d4b1 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -600,7 +600,7 @@ const AP_Param::Info Plane::var_info[] = { // @Param: RUDDER_ONLY // @DisplayName: Rudder only aircraft - // @Description: Enable rudder only mode. The rudder will control attitude in attitude controlled modes (such as FBWA). You should setup your transmitter to send roll stick inputs to the RCMAP_YAW channel (normally channel 4). The rudder servo should be attached to the RCMAP_YAW channel as well. Note that automatic ground steering will be disabled for rudder only aircraft. You should also set KFF_RDDRMIX to 1.0. You will also need to setup the YAW2SRV_DAMP yaw damping appropriately for your aircraft. A value of 0.5 for YAW2SRV_DAMP is a good starting point. + // @Description: Enable rudder only mode. The rudder will control attitude in attitude controlled modes (such as FBWA). You should setup your transmitter to send roll stick inputs to the RC yaw input channel (normally channel 4). Note that automatic ground steering will be disabled for rudder only aircraft. You should also set KFF_RDDRMIX to 1.0. You will also need to setup the YAW2SRV_DAMP yaw damping appropriately for your aircraft. A value of 0.5 for YAW2SRV_DAMP is a good starting point. // @Values: 0:Disabled,1:Enabled // @User: Standard GSCALAR(rudder_only, "RUDDER_ONLY", 0), @@ -840,10 +840,6 @@ const AP_Param::Info Plane::var_info[] = { // @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp GOBJECT(scheduler, "SCHED_", AP_Scheduler), - // @Group: RCMAP_ - // @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp - GOBJECT(rcmap, "RCMAP_", RCMapper), - // @Group: SR0_ // @Path: GCS_Mavlink.cpp GOBJECTN(_gcs.chan_parameters[0], gcs0, "SR0_", GCS_MAVLINK_Parameters), @@ -1562,4 +1558,9 @@ void Plane::load_parameters(void) #if HAL_LOGGING_ENABLED AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true); #endif + + // PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.6 +#if AP_RC_CHANNEL_ENABLED + rc().convert_rcmap_parameters(Parameters::k_param_rcmap_old); +#endif } diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index ad78f76de7e216..dea93b03b8dfea 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -326,7 +326,7 @@ class Parameters { k_param_pitchController, k_param_yawController, k_param_L1_controller, - k_param_rcmap, + k_param_rcmap_old, k_param_TECS_controller, k_param_rally_total_old, //unused k_param_steerController, diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 3d08a2bca9add5..d680485a36ec2c 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -58,7 +58,6 @@ #include #include -#include // RC input mapping library #include #include @@ -181,9 +180,6 @@ class Plane : public AP_Vehicle { Parameters g; ParametersG2 g2; - // mapping between input channels - RCMapper rcmap; - // primary input channels RC_Channel *channel_roll; RC_Channel *channel_pitch; diff --git a/ArduPlane/radio.cpp b/ArduPlane/radio.cpp index 6f5ea8daeb62bb..d0810e42b2f5da 100644 --- a/ArduPlane/radio.cpp +++ b/ArduPlane/radio.cpp @@ -8,16 +8,18 @@ */ void Plane::set_control_channels(void) { + auto &_rc = rc(); + if (g.rudder_only) { // in rudder only mode the roll and rudder channels are the // same. - channel_roll = RC_Channels::rc_channel(rcmap.yaw()-1); + channel_roll = _rc.find_channel_for_option(RC_Channel::AUX_FUNC::YAW); } else { - channel_roll = RC_Channels::rc_channel(rcmap.roll()-1); + channel_roll = _rc.find_channel_for_option(RC_Channel::AUX_FUNC::ROLL); } - channel_pitch = RC_Channels::rc_channel(rcmap.pitch()-1); - channel_throttle = RC_Channels::rc_channel(rcmap.throttle()-1); - channel_rudder = RC_Channels::rc_channel(rcmap.yaw()-1); + channel_pitch = _rc.find_channel_for_option(RC_Channel::AUX_FUNC::PITCH); + channel_throttle = _rc.find_channel_for_option(RC_Channel::AUX_FUNC::THROTTLE); + channel_rudder = _rc.find_channel_for_option(RC_Channel::AUX_FUNC::YAW); // set rc channel ranges channel_roll->set_angle(SERVO_MAX); diff --git a/ArduPlane/wscript b/ArduPlane/wscript index 4dd670ccc34a52..86aaad44d6c0df 100644 --- a/ArduPlane/wscript +++ b/ArduPlane/wscript @@ -14,7 +14,6 @@ def build(bld): 'AP_Camera', 'AP_L1_Control', 'AP_Navigation', - 'AP_RCMapper', 'AP_TECS', 'AP_InertialNav', 'AC_WPNav', diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index 58e554f348ef98..a973b31a4adee8 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -619,12 +619,6 @@ const AP_Param::Info Sub::var_info[] = { // @Path: ../libraries/AP_Motors/AP_Motors6DOF.cpp,../libraries/AP_Motors/AP_MotorsMulticopter.cpp GOBJECT(motors, "MOT_", AP_Motors6DOF), -#if RCMAP_ENABLED == ENABLED - // @Group: RCMAP_ - // @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp - GOBJECT(rcmap, "RCMAP_", RCMapper), -#endif - #if HAL_NAVEKF2_AVAILABLE // @Group: EK2_ // @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -795,6 +789,11 @@ void Sub::load_parameters() #if HAL_LOGGING_ENABLED AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true); #endif + + // PARAMETER_CONVERSION - Added: Feb-2024 +#if AP_RC_CHANNEL_ENABLED + rc().convert_rcmap_parameters(Parameters::k_param_rcmap_old); +#endif } void Sub::convert_old_parameters() diff --git a/ArduSub/Parameters.h b/ArduSub/Parameters.h index f8fd851fbf5e11..b542cfc8a215f2 100644 --- a/ArduSub/Parameters.h +++ b/ArduSub/Parameters.h @@ -220,7 +220,7 @@ class Parameters { k_param_rpm_sensor = 232, // Disabled // RC_Mapper Library - k_param_rcmap, // Disabled + k_param_rcmap_old, // Disabled k_param_gcs4, k_param_gcs5, diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 2419e0fc799345..8af9c288474e0d 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -77,11 +77,6 @@ #include // Optical Flow library -// libraries which are dependent on #defines in defines.h and/or config.h -#if RCMAP_ENABLED == ENABLED -#include // RC input mapping library -#endif - #include #if AP_RPM_ENABLED @@ -206,10 +201,6 @@ class Sub : public AP_Vehicle { Mode::Number prev_control_mode; -#if RCMAP_ENABLED == ENABLED - RCMapper rcmap; -#endif - // Failsafe struct { uint32_t last_leak_warn_ms; // last time a leak warning was sent to gcs diff --git a/ArduSub/config.h b/ArduSub/config.h index d4cdc55bf93d5c..10f8c46fc6b1ef 100644 --- a/ArduSub/config.h +++ b/ArduSub/config.h @@ -34,14 +34,6 @@ # define CIRCLE_NAV_ENABLED ENABLED #endif -////////////////////////////////////////////////////////////////////////////// -// RCMAP -// - -#ifndef RCMAP_ENABLED -# define RCMAP_ENABLED DISABLED -#endif - ////////////////////////////////////////////////////////////////////////////// // Rangefinder // diff --git a/ArduSub/wscript b/ArduSub/wscript index 89da451ee21e7f..c1d3fe9a0ddede 100644 --- a/ArduSub/wscript +++ b/ArduSub/wscript @@ -14,7 +14,6 @@ def build(bld): 'AP_JSButton', 'AP_LeakDetector', 'AP_Motors', - 'AP_RCMapper', 'AP_Beacon', 'AP_TemperatureSensor', 'AP_Arming', diff --git a/Blimp/Blimp.h b/Blimp/Blimp.h index 826d92b98c49fe..08934880a9dfe1 100644 --- a/Blimp/Blimp.h +++ b/Blimp/Blimp.h @@ -42,7 +42,6 @@ #include // Filter library #include // needed for AHRS build #include // inertial navigation library -#include // RC input mapping library #include // Battery monitor library #include #include @@ -170,8 +169,6 @@ class Blimp : public AP_Vehicle ModeReason control_mode_reason = ModeReason::UNKNOWN; Mode::Number prev_control_mode; - RCMapper rcmap; - // inertial nav alt when we armed float arming_altitude_m; diff --git a/Blimp/Parameters.cpp b/Blimp/Parameters.cpp index cbc14fc4101a2f..7e89bd1d04afcc 100644 --- a/Blimp/Parameters.cpp +++ b/Blimp/Parameters.cpp @@ -372,10 +372,6 @@ const AP_Param::Info Blimp::var_info[] = { // @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp GOBJECT(scheduler, "SCHED_", AP_Scheduler), - // @Group: RCMAP_ - // @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp - GOBJECT(rcmap, "RCMAP_", RCMapper), - #if HAL_NAVEKF2_AVAILABLE // @Group: EK2_ // @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -876,6 +872,10 @@ void Blimp::load_parameters(void) AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true); #endif +#if AP_RC_CHANNEL_ENABLED + rc().convert_rcmap_parameters(Parameters::k_param_rcmap_old); +#endif + // setup AP_Param frame type flags AP_Param::set_frame_type_flags(AP_PARAM_FRAME_BLIMP); } diff --git a/Blimp/Parameters.h b/Blimp/Parameters.h index 769e9d2df7a4ad..bb9e9eb461cd9c 100644 --- a/Blimp/Parameters.h +++ b/Blimp/Parameters.h @@ -177,7 +177,7 @@ class Parameters k_param_radio_tuning, // unused k_param_rc_speed = 192, k_param_failsafe_gcs, - k_param_rcmap, // 199 + k_param_rcmap_old, // 199 // // 200: flight modes diff --git a/Blimp/radio.cpp b/Blimp/radio.cpp index fddce3e914dd21..811e529714714a 100644 --- a/Blimp/radio.cpp +++ b/Blimp/radio.cpp @@ -15,10 +15,12 @@ void Blimp::default_dead_zones() void Blimp::init_rc_in() { - channel_right = rc().channel(rcmap.roll()-1); - channel_front = rc().channel(rcmap.pitch()-1); - channel_up = rc().channel(rcmap.throttle()-1); - channel_yaw = rc().channel(rcmap.yaw()-1); + auto &_rc = rc(); + + channel_right = _rc.find_channel_for_option(RC_Channel::AUX_FUNC::ROLL); + channel_front = _rc.find_channel_for_option(RC_Channel::AUX_FUNC::PITCH); + channel_up = _rc.find_channel_for_option(RC_Channel::AUX_FUNC::THROTTLE); + channel_yaw = _rc.find_channel_for_option(RC_Channel::AUX_FUNC::YAW); // set rc channel ranges channel_right->set_angle(RC_SCALE); diff --git a/Blimp/wscript b/Blimp/wscript index 34cb8c170490e0..1966aa583bd122 100644 --- a/Blimp/wscript +++ b/Blimp/wscript @@ -9,7 +9,6 @@ def build(bld): ap_libraries=bld.ap_common_vehicle_libraries() + [ 'AC_InputManager', 'AP_InertialNav', - 'AP_RCMapper', 'AP_Avoidance', 'AP_Arming', 'AP_LTM_Telem', diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index 34f393b740a918..a011ea2a55a41b 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -228,10 +228,6 @@ const AP_Param::Info Rover::var_info[] = { GOBJECT(relay, "RELAY", AP_Relay), #endif - // @Group: RCMAP_ - // @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp - GOBJECT(rcmap, "RCMAP_", RCMapper), - // @Group: SR0_ // @Path: GCS_Mavlink.cpp GOBJECTN(_gcs.chan_parameters[0], gcs0, "SR0_", GCS_MAVLINK_Parameters), @@ -928,4 +924,8 @@ void Rover::load_parameters(void) AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true); #endif + // PARAMETER_CONVERSION - Added: Feb-2024 for Rover-4.6 +#if AP_RC_CHANNEL_ENABLED + rc().convert_rcmap_parameters(Parameters::k_param_rcmap_old); +#endif } diff --git a/Rover/Parameters.h b/Rover/Parameters.h index ef8d6194706ac3..3736b1cc1f9930 100644 --- a/Rover/Parameters.h +++ b/Rover/Parameters.h @@ -217,7 +217,7 @@ class Parameters { k_param_ahrs, k_param_ins, k_param_compass, - k_param_rcmap, + k_param_rcmap_old, k_param_L1_controller, // unused k_param_steerController_old, // unused k_param_barometer, diff --git a/Rover/Rover.h b/Rover/Rover.h index e12ed2db608b85..30d8236983d58d 100644 --- a/Rover/Rover.h +++ b/Rover/Rover.h @@ -29,7 +29,6 @@ #include // Camera/Antenna mount #include #include // Range finder library -#include // RC input mapping library #include // RPM input library #include // main loop scheduler #include // needed for AHRS build @@ -125,9 +124,6 @@ class Rover : public AP_Vehicle { Parameters g; ParametersG2 g2; - // mapping between input channels - RCMapper rcmap; - // primary control channels RC_Channel *channel_steer; RC_Channel *channel_throttle; diff --git a/Rover/radio.cpp b/Rover/radio.cpp index cf1f159689c957..3367d7e93245df 100644 --- a/Rover/radio.cpp +++ b/Rover/radio.cpp @@ -6,9 +6,9 @@ void Rover::set_control_channels(void) { // check change on RCMAP - channel_steer = rc().channel(rcmap.roll()-1); - channel_throttle = rc().channel(rcmap.throttle()-1); - channel_lateral = rc().channel(rcmap.yaw()-1); + channel_steer = rc().find_channel_for_option(RC_Channel::AUX_FUNC::ROLL); + channel_throttle = rc().find_channel_for_option(RC_Channel::AUX_FUNC::THROTTLE); + channel_lateral = rc().find_channel_for_option(RC_Channel::AUX_FUNC::YAW); // set rc channel ranges channel_steer->set_angle(SERVO_MAX); diff --git a/Rover/wscript b/Rover/wscript index b77de5b6e40161..98dd4bf8ead472 100644 --- a/Rover/wscript +++ b/Rover/wscript @@ -12,7 +12,6 @@ def build(bld): 'AP_Mount', 'AP_Navigation', 'AR_WPNav', - 'AP_RCMapper', 'AP_Beacon', 'AP_AdvancedFailsafe', 'AP_WheelEncoder', diff --git a/Tools/Replay/wscript b/Tools/Replay/wscript index 936707364ec844..2a1319e582af90 100644 --- a/Tools/Replay/wscript +++ b/Tools/Replay/wscript @@ -5,6 +5,7 @@ import boards def configure(cfg): cfg.env.HAL_GCS_ENABLED = 0 + cfg.env.AP_RC_CHANNEL_ENABLED = 0 def build(bld): if isinstance(bld.get_board(), boards.chibios) and bld.env['WITH_FATFS'] != '1': @@ -19,7 +20,6 @@ def build(bld): ap_libraries=bld.ap_common_vehicle_libraries() + [ 'AP_Beacon', 'AP_Arming', - 'AP_RCMapper', 'AP_OSD', 'AP_Avoidance', ], diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index 49400fc5a2b316..2b8d7e7cf94a76 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -77,8 +77,8 @@ def is_rover(self): return True def rc_option_value_for_arming_channel(self): - # Rover uses the "steer" channel for arming - return 205 + # Rover uses the "roll" channel for arming + return 201 ########################################################## # TESTS DRIVE diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index 2a0a3e1fa0ac90..4dd1ea97d96cc3 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -40,7 +40,6 @@ #include #include #include -#include #include #include #include @@ -707,19 +706,25 @@ bool AP_Arming::rc_arm_checks(AP_Arming::Method method) check_failed(ARMING_CHECK_PARAMETERS, true, "Mode channel and RC%d_OPTION conflict", rc().flight_mode_channel_number()); check_passed = false; } - const RCMapper * rcmap = AP::rcmap(); - if (rcmap != nullptr) { - if (!rc().option_is_enabled(RC_Channels::Option::ARMING_SKIP_CHECK_RPY)) { - const char *names[3] = {"Roll", "Pitch", "Yaw"}; - const uint8_t channels[3] = {rcmap->roll(), rcmap->pitch(), rcmap->yaw()}; - for (uint8_t i = 0; i < ARRAY_SIZE(channels); i++) { - const RC_Channel *c = rc().channel(channels[i] - 1); + if (true) { + auto &_rc = rc(); + if (!_rc.option_is_enabled(RC_Channels::Option::ARMING_SKIP_CHECK_RPY)) { + struct { + const char *name; + RC_Channel *channel; + } channels_to_check[] { + { "Roll", _rc.find_channel_for_option(RC_Channel::AUX_FUNC::ROLL) }, + { "Pitch", _rc.find_channel_for_option(RC_Channel::AUX_FUNC::PITCH) }, + { "Yaw", _rc.find_channel_for_option(RC_Channel::AUX_FUNC::YAW) }, + }; + for (const auto &to_check : channels_to_check) { + const auto *c = to_check.channel; if (c == nullptr) { continue; } if (c->get_control_in() != 0) { - if ((method != Method::RUDDER) || (c != rc().get_arming_channel())) { // ignore the yaw input channel if rudder arming - check_failed(ARMING_CHECK_RC, true, "%s (RC%d) is not neutral", names[i], channels[i]); + if ((method != Method::RUDDER) || (c != _rc.get_arming_channel())) { // ignore the yaw input channel if rudder arming + check_failed(ARMING_CHECK_RC, true, "%s (RC%d) is not neutral", to_check.name, to_check.channel->ch_num()); check_passed = false; } } @@ -728,10 +733,10 @@ bool AP_Arming::rc_arm_checks(AP_Arming::Method method) // if throttle check is enabled, require zero input if (rc().arming_check_throttle()) { - RC_Channel *c = rc().channel(rcmap->throttle() - 1); + RC_Channel *c = _rc.find_channel_for_option(RC_Channel::AUX_FUNC::THROTTLE); if (c != nullptr) { if (c->get_control_in() != 0) { - check_failed(ARMING_CHECK_RC, true, "Throttle (RC%d) is not neutral", rcmap->throttle()); + check_failed(ARMING_CHECK_RC, true, "Throttle (RC%d) is not neutral", c->ch_num()); check_passed = false; } } diff --git a/libraries/AP_Camera/AP_RunCam.cpp b/libraries/AP_Camera/AP_RunCam.cpp index 86e7dee57c6af8..e86ee251a7ea09 100644 --- a/libraries/AP_Camera/AP_RunCam.cpp +++ b/libraries/AP_Camera/AP_RunCam.cpp @@ -451,10 +451,10 @@ void AP_RunCam::handle_in_menu(Event ev) // map rc input to an event AP_RunCam::Event AP_RunCam::map_rc_input_to_event() const { - const RC_Channel::AuxSwitchPos throttle = rc().get_channel_pos(AP::rcmap()->throttle()); - const RC_Channel::AuxSwitchPos yaw = rc().get_channel_pos(AP::rcmap()->yaw()); - const RC_Channel::AuxSwitchPos roll = rc().get_channel_pos(AP::rcmap()->roll()); - const RC_Channel::AuxSwitchPos pitch = rc().get_channel_pos(AP::rcmap()->pitch()); + const RC_Channel::AuxSwitchPos throttle = rc().get_channel_pos(RC_Channel::AUX_FUNC::THROTTLE); + const RC_Channel::AuxSwitchPos yaw = rc().get_channel_pos(RC_Channel::AUX_FUNC::YAW); + const RC_Channel::AuxSwitchPos roll = rc().get_channel_pos(RC_Channel::AUX_FUNC::ROLL); + const RC_Channel::AuxSwitchPos pitch = rc().get_channel_pos(RC_Channel::AUX_FUNC::PITCH); Event result = Event::NONE; diff --git a/libraries/AP_Camera/AP_RunCam.h b/libraries/AP_Camera/AP_RunCam.h index b689a8108e3818..1f4d72420c7fd8 100644 --- a/libraries/AP_Camera/AP_RunCam.h +++ b/libraries/AP_Camera/AP_RunCam.h @@ -31,7 +31,6 @@ #include #include -#include #include #include diff --git a/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/wscript b/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/wscript index 3e81beeee182a4..a9ae892fdeb786 100644 --- a/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/wscript +++ b/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/wscript @@ -11,7 +11,6 @@ def build(bld): dynamic_source='modules/DroneCAN/libcanard/dsdlc_generated/src/**.c', ap_libraries=bld.ap_common_vehicle_libraries() + [ 'AP_OSD', - 'AP_RCMapper', 'AP_Arming' ], ) diff --git a/libraries/AP_IOMCU/AP_IOMCU.cpp b/libraries/AP_IOMCU/AP_IOMCU.cpp index bfefb6c253cb78..ffd4a1468996c8 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.cpp +++ b/libraries/AP_IOMCU/AP_IOMCU.cpp @@ -1176,7 +1176,7 @@ void AP_IOMCU::bind_dsm(uint8_t mode) setup for mixing. This allows fixed wing aircraft to fly in manual mode if the FMU dies */ -bool AP_IOMCU::setup_mixing(RCMapper *rcmap, int8_t override_chan, +bool AP_IOMCU::setup_mixing(int8_t override_chan, float mixing_gain, uint16_t manual_rc_mask) { if (!is_chibios_backend) { @@ -1198,15 +1198,19 @@ bool AP_IOMCU::setup_mixing(RCMapper *rcmap, int8_t override_chan, MIX_UPDATE(mixing.servo_reversed[i], c->get_reversed()); } // update RCMap - MIX_UPDATE(mixing.rc_channel[0], rcmap->roll()); - MIX_UPDATE(mixing.rc_channel[1], rcmap->pitch()); - MIX_UPDATE(mixing.rc_channel[2], rcmap->throttle()); - MIX_UPDATE(mixing.rc_channel[3], rcmap->yaw()); - for (uint8_t i=0; i<4; i++) { - const RC_Channel *c = RC_Channels::rc_channel(mixing.rc_channel[i]-1); - if (!c) { + static const RC_Channel::AUX_FUNC funcs[] { + RC_Channel::AUX_FUNC::ROLL, + RC_Channel::AUX_FUNC::PITCH, + RC_Channel::AUX_FUNC::YAW, + RC_Channel::AUX_FUNC::THROTTLE, + }; + for (uint8_t i=0; ich_num()); MIX_UPDATE(mixing.rc_min[i], c->get_radio_min()); MIX_UPDATE(mixing.rc_max[i], c->get_radio_max()); MIX_UPDATE(mixing.rc_trim[i], c->get_radio_trim()); diff --git a/libraries/AP_IOMCU/AP_IOMCU.h b/libraries/AP_IOMCU/AP_IOMCU.h index 253b1b9890b457..0eca2a4477b406 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.h +++ b/libraries/AP_IOMCU/AP_IOMCU.h @@ -11,7 +11,6 @@ #if HAL_WITH_IO_MCU #include "iofirmware/ioprotocol.h" -#include #include #include @@ -145,7 +144,7 @@ class AP_IOMCU void soft_reboot(); // setup for FMU failsafe mixing - bool setup_mixing(RCMapper *rcmap, int8_t override_chan, + bool setup_mixing(int8_t override_chan, float mixing_gain, uint16_t manual_rc_mask); // Check if pin number is valid and configured for GPIO diff --git a/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp b/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp index ef4a674e745d31..d7dd23b22f3250 100644 --- a/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp +++ b/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp @@ -25,7 +25,6 @@ #include #include #include -#include #include #include #include @@ -1051,33 +1050,24 @@ MSPCommandResult AP_MSP_Telem_Backend::msp_process_out_rtc(sbuf_t *dst) #if AP_RC_CHANNEL_ENABLED MSPCommandResult AP_MSP_Telem_Backend::msp_process_out_rc(sbuf_t *dst) { -#if AP_RCMAPPER_ENABLED - const RCMapper* rcmap = AP::rcmap(); - if (rcmap == nullptr) { - return MSP_RESULT_ERROR; - } - uint16_t values[16] = {}; - rc().get_radio_in(values, ARRAY_SIZE(values)); - - const struct PACKED { - uint16_t a; - uint16_t e; - uint16_t r; - uint16_t t; - } rc { - // send only 4 channels, MSP order is AERT - // note: rcmap channels start at 1 - a : values[rcmap->roll()-1], // A - e : values[rcmap->pitch()-1], // E - r : values[rcmap->yaw()-1], // R - t : values[rcmap->throttle()-1] // T + // send only 4 channels, MSP order is AERT + uint16_t aert[4] {}; + static const RC_Channel::AUX_FUNC funcs[] { + RC_Channel::AUX_FUNC::ROLL, + RC_Channel::AUX_FUNC::PITCH, + RC_Channel::AUX_FUNC::YAW, + RC_Channel::AUX_FUNC::THROTTLE, }; + for (uint8_t i=0; iget_radio_in(); + } - sbuf_write_data(dst, &rc, sizeof(rc)); + sbuf_write_data(dst, &aert, sizeof(aert)); return MSP_RESULT_ACK; -#else - return MSP_RESULT_ERROR; -#endif } #endif // AP_RC_CHANNEL_ENABLED diff --git a/libraries/AP_OSD/AP_OSD.h b/libraries/AP_OSD/AP_OSD.h index 8594e5d2d4aaa3..e2773277bdff2f 100644 --- a/libraries/AP_OSD/AP_OSD.h +++ b/libraries/AP_OSD/AP_OSD.h @@ -455,7 +455,7 @@ class AP_OSD_ParamScreen : public AP_OSD_AbstractScreen #if AP_RC_CHANNEL_ENABLED Event map_rc_input_to_event() const; - RC_Channel::AuxSwitchPos get_channel_pos(uint8_t rcmapchan) const; + RC_Channel::AuxSwitchPos get_channel_pos(RC_Channel::AUX_FUNC func) const; #endif uint8_t _selected_param = 1; diff --git a/libraries/AP_OSD/AP_OSD_ParamScreen.cpp b/libraries/AP_OSD/AP_OSD_ParamScreen.cpp index 9dd4e77bedfdf2..fe5f906adeff94 100644 --- a/libraries/AP_OSD/AP_OSD_ParamScreen.cpp +++ b/libraries/AP_OSD/AP_OSD_ParamScreen.cpp @@ -26,7 +26,6 @@ #include #include #include -#include #include #include #include @@ -392,9 +391,9 @@ void AP_OSD_ParamScreen::modify_configured_parameter(uint8_t number, Event ev) // return radio values as LOW, MIDDLE, HIGH // this function uses different threshold values to RC_Chanel::get_channel_pos() // to avoid glitching on the stick travel -RC_Channel::AuxSwitchPos AP_OSD_ParamScreen::get_channel_pos(uint8_t rcmapchan) const +RC_Channel::AuxSwitchPos AP_OSD_ParamScreen::get_channel_pos(RC_Channel::AUX_FUNC func) const { - const RC_Channel* chan = rc().channel(rcmapchan-1); + const RC_Channel* chan = rc().find_channel_for_option(func); if (chan == nullptr) { return RC_Channel::AuxSwitchPos::LOW; } @@ -419,10 +418,10 @@ RC_Channel::AuxSwitchPos AP_OSD_ParamScreen::get_channel_pos(uint8_t rcmapchan) // map rc input to an event AP_OSD_ParamScreen::Event AP_OSD_ParamScreen::map_rc_input_to_event() const { - const RC_Channel::AuxSwitchPos throttle = get_channel_pos(AP::rcmap()->throttle()); - const RC_Channel::AuxSwitchPos yaw = get_channel_pos(AP::rcmap()->yaw()); - const RC_Channel::AuxSwitchPos roll = get_channel_pos(AP::rcmap()->roll()); - const RC_Channel::AuxSwitchPos pitch = get_channel_pos(AP::rcmap()->pitch()); + const RC_Channel::AuxSwitchPos throttle = get_channel_pos(RC_Channel::AUX_FUNC::THROTTLE); + const RC_Channel::AuxSwitchPos yaw = get_channel_pos(RC_Channel::AUX_FUNC::YAW); + const RC_Channel::AuxSwitchPos roll = get_channel_pos(RC_Channel::AUX_FUNC::ROLL); + const RC_Channel::AuxSwitchPos pitch = get_channel_pos(RC_Channel::AUX_FUNC::PITCH); Event result = Event::NONE; diff --git a/libraries/AP_Param/AP_Param.h b/libraries/AP_Param/AP_Param.h index 85d533c1fd1487..36a104d39a085c 100644 --- a/libraries/AP_Param/AP_Param.h +++ b/libraries/AP_Param/AP_Param.h @@ -493,6 +493,9 @@ class AP_Param const struct AP_Param::GroupInfo *group_info, uint16_t old_index, uint16_t old_top_element, bool is_top_level); + // return true if the parameter is configured in EEPROM/FRAM + bool configured_in_storage(void) const; + /* fetch a parameter value based on the index within a group. This is used to find the old value of a parameter that has been @@ -762,9 +765,6 @@ class AP_Param // return true if the parameter is configured in the defaults file bool configured_in_defaults_file(bool &read_only) const; - // return true if the parameter is configured in EEPROM/FRAM - bool configured_in_storage(void) const; - // send a parameter to all GCS instances void send_parameter(const char *name, enum ap_var_type param_header_type, uint8_t idx) const; diff --git a/libraries/AP_Scripting/applets/VTOL-quicktune.lua b/libraries/AP_Scripting/applets/VTOL-quicktune.lua index 4ddd6bd7824370..65e1048d2c1c09 100644 --- a/libraries/AP_Scripting/applets/VTOL-quicktune.lua +++ b/libraries/AP_Scripting/applets/VTOL-quicktune.lua @@ -171,13 +171,9 @@ local OPTIONS_TWO_POSITION = (1<<0) local INS_GYRO_FILTER = bind_param("INS_GYRO_FILTER") -local RCMAP_ROLL = bind_param("RCMAP_ROLL") -local RCMAP_PITCH = bind_param("RCMAP_PITCH") -local RCMAP_YAW = bind_param("RCMAP_YAW") - -local RCIN_ROLL = rc:get_channel(RCMAP_ROLL:get()) -local RCIN_PITCH = rc:get_channel(RCMAP_PITCH:get()) -local RCIN_YAW = rc:get_channel(RCMAP_YAW:get()) +local RCIN_ROLL = rc:find_channel_for_option(201) +local RCIN_PITCH = rc:find_channel_for_option(202) +local RCIN_YAW = rc:find_channel_for_option(204) local UPDATE_RATE_HZ = 40 local STAGE_DELAY = 4.0 diff --git a/libraries/AP_Vehicle/AP_Vehicle.cpp b/libraries/AP_Vehicle/AP_Vehicle.cpp index 04f80777fcf7fb..198c7b4e69b338 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.cpp +++ b/libraries/AP_Vehicle/AP_Vehicle.cpp @@ -326,6 +326,11 @@ void AP_Vehicle::setup() G_Dt = scheduler.get_loop_period_s(); #endif +#if AP_RC_CHANNEL_ENABLED + // configure RC library defaults for roll/pitch/yaw channels. + // Needed before set_control_channels + rc().set_control_channel_defaults(); +#endif // this is here for Plane; its failsafe_check method requires the // RC channels to be set as early as possible for maximum // survivability. diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 736e7e18d6a2df..5bedee11f4e2f6 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -59,6 +59,7 @@ extern const AP_HAL::HAL& hal; #include #include #include + #define SWITCH_DEBOUNCE_TIME_MS 200 const AP_Param::GroupInfo RC_Channel::var_info[] = { @@ -236,8 +237,10 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @Values{Copter, Rover, Plane, Blimp}: 174:Camera Image Tracking // @Values{Copter, Rover, Plane, Blimp}: 175:Camera Lens // @Values{Plane}: 176:Quadplane Fwd Throttle Override enable - // @Values{Rover}: 201:Roll - // @Values{Rover}: 202:Pitch + // @Values{Rover,Copter}: 201:Roll + // @Values{Rover,Copter}: 202:Pitch + // @Values{Copter}: 203:Throttle + // @Values{Copter}: 204:Yaw // @Values{Rover}: 207:MainSail // @Values{Rover, Plane}: 208:Flap // @Values{Plane}: 209:VTOL Forward Throttle @@ -669,6 +672,10 @@ void RC_Channel::init_aux_function(const aux_func_t ch_option, const AuxSwitchPo // not really aux functions: case AUX_FUNC::LOWEHEISER_THROTTLE: + case AUX_FUNC::ROLL: + case AUX_FUNC::PITCH: + case AUX_FUNC::YAW: + case AUX_FUNC::THROTTLE: break; case AUX_FUNC::AVOID_ADSB: case AUX_FUNC::AVOID_PROXIMITY: @@ -1720,9 +1727,9 @@ RC_Channel::AuxSwitchPos RC_Channel::get_aux_switch_pos() const // return switch position value as LOW, MIDDLE, HIGH // if reading the switch fails then it returns LOW -RC_Channel::AuxSwitchPos RC_Channels::get_channel_pos(const uint8_t rcmapchan) const +RC_Channel::AuxSwitchPos RC_Channels::get_channel_pos(RC_Channel::AUX_FUNC func) { - const RC_Channel* chan = rc().channel(rcmapchan-1); + const RC_Channel* chan = find_channel_for_option(func); return chan != nullptr ? chan->get_aux_switch_pos() : RC_Channel::AuxSwitchPos::LOW; } @@ -1784,4 +1791,65 @@ void RC_Channels::convert_options(const RC_Channel::aux_func_t old_option, const } } + +// PARAMETER_CONVERSION - Added: Feb-2024 for ArduPilot 4.6 +void RC_Channels::convert_rcmap_parameters(uint32_t param_key) +{ + if (_conversion & 0b1) { + // conversion has already been done + return; + } + // mark conversion as having been done: + _conversion.set_and_save(_conversion | 0b1); + + // for each of RCMap's parameters, + static const struct { + uint8_t idx; + RC_Channel::AUX_FUNC func; + } func_map[] { + { 0, RC_Channel::AUX_FUNC::ROLL }, + { 1, RC_Channel::AUX_FUNC::PITCH }, + { 2, RC_Channel::AUX_FUNC::THROTTLE }, + { 3, RC_Channel::AUX_FUNC::YAW }, + { 4, RC_Channel::AUX_FUNC::FWD_THR }, + { 5, RC_Channel::AUX_FUNC::LATERAL_THR }, + }; + for (auto &map : func_map) { + struct AP_Param::ConversionInfo info; + info.old_key = param_key; + info.type = AP_PARAM_INT8; + info.new_name = nullptr; + info.old_group_element = map.idx; + + uint8_t old_value; + AP_Param *ap = (AP_Param *)&old_value; + + if (!AP_Param::find_old_parameter(&info, ap)) { + // the parameter wasn't set in the old eeprom + continue; + } + + RC_Channel *c = channel(old_value-1); + if (c == nullptr) { + // old value was invalid + continue; + } + + AP_Int16 &option = c->option; + + if (!option.configured_in_storage() && + RC_Channel::AUX_FUNC(option.get()) == map.func) { + // don't over-write default values + continue; + } + + // force-overwrite the value: + option.set_and_save((uint16_t)map.func); + } + + // we need to flush here to prevent a later set_default_by_name() + // causing a save to be done on a converted parameter + AP_Param::flush(); +} + #endif // AP_RC_CHANNEL_ENABLED diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index 368e3a013eae56..486d02736a9d80 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -89,6 +89,9 @@ class RC_Channel { void set_and_save_trim() { radio_trim.set_and_save_ifchanged(radio_in);} + // returns the RC channel number, where 1 is usually roll, 3 throttle etc + uint8_t ch_num() const { return ch_in + 1; } + // set and save trim if changed void set_and_save_radio_trim(int16_t val) { radio_trim.set_and_save_ifchanged(val);} @@ -268,6 +271,7 @@ class RC_Channel { MOUNT2_PITCH = 216, // mount3 pitch input MOUNT2_YAW = 217, // mount4 yaw input LOWEHEISER_THROTTLE= 218, // allows for throttle on slider + LATERAL_THR = 219, // RC throttle command for sideways movement // inputs 248-249 are reserved for the Skybrush fork at // https://github.com/skybrush-io/ardupilot @@ -287,6 +291,10 @@ class RC_Channel { }; typedef enum AUX_FUNC aux_func_t; + void set_default_option(AUX_FUNC func) { + option.set_default((uint16_t) func); + } + // auxiliary switch handling (n.b.: we store this as 2-bits!): enum class AuxSwitchPos : uint8_t { LOW, // indicates auxiliary switch is in the low position (pwm <1200) @@ -435,6 +443,10 @@ class RC_Channels { // constructor RC_Channels(void); + // set defaults for roll/pitch/yaw/throttle control channels. + // Called *before* init! + void set_control_channel_defaults(); + void init(void); // get singleton instance @@ -484,7 +496,7 @@ class RC_Channels { class RC_Channel *find_channel_for_option(const RC_Channel::aux_func_t option); bool duplicate_options_exist(); - RC_Channel::AuxSwitchPos get_channel_pos(const uint8_t rcmapchan) const; + RC_Channel::AuxSwitchPos get_channel_pos(const RC_Channel::AUX_FUNC func); void convert_options(const RC_Channel::aux_func_t old_option, const RC_Channel::aux_func_t new_option); void init_aux_all(); @@ -598,6 +610,7 @@ class RC_Channels { // get failsafe timeout in milliseconds uint32_t get_fs_timeout_ms() const { return MAX(_fs_timeout * 1000, 100); } + void convert_rcmap_parameters(uint32_t param_key); protected: void new_override_received() { @@ -620,6 +633,8 @@ class RC_Channels { AP_Int32 _protocols; AP_Float _fs_timeout; + AP_Int8 _conversion; + // set to true if we see overrides or other RC input bool _has_ever_seen_rc_input; diff --git a/libraries/RC_Channel/RC_Channels.cpp b/libraries/RC_Channel/RC_Channels.cpp index 4beee5e5d69f2d..6b01bc9d074b62 100644 --- a/libraries/RC_Channel/RC_Channels.cpp +++ b/libraries/RC_Channel/RC_Channels.cpp @@ -45,15 +45,24 @@ RC_Channels::RC_Channels(void) AP_HAL::panic("RC_Channels must be singleton"); } _singleton = this; + } -void RC_Channels::init(void) +void RC_Channels::set_control_channel_defaults() { - // setup ch_in on channels + // setup ch_in on channels. Plane needs this initialisation early! for (uint8_t i=0; ich_in = i; } + channel(0)->set_default_option(RC_Channel::AUX_FUNC::ROLL); + channel(1)->set_default_option(RC_Channel::AUX_FUNC::PITCH); + channel(2)->set_default_option(RC_Channel::AUX_FUNC::THROTTLE); + channel(3)->set_default_option(RC_Channel::AUX_FUNC::YAW); +} + +void RC_Channels::init(void) +{ init_aux_all(); } diff --git a/libraries/RC_Channel/RC_Channels_VarInfo.h b/libraries/RC_Channel/RC_Channels_VarInfo.h index a824cc1ececc34..67c8570517fa1d 100644 --- a/libraries/RC_Channel/RC_Channels_VarInfo.h +++ b/libraries/RC_Channel/RC_Channels_VarInfo.h @@ -112,6 +112,15 @@ const AP_Param::GroupInfo RC_Channels::var_info[] = { // @Units: s AP_GROUPINFO_FRAME("_FS_TIMEOUT", 35, RC_CHANNELS_SUBCLASS, _fs_timeout, 1.0, AP_PARAM_FRAME_COPTER), + // @Param: CONVERSION + // @DisplayName: RC parameter conversion flags + // @Description: This is a hidden parameter which records whether we have done a parameter conversion or not + // @Range: 0 32766 + // @Increment: 1 + // @User: Advanced + // @ReadOnly: True + AP_GROUPINFO_FLAGS("CONVERSION", 36, RC_CHANNELS_SUBCLASS, _conversion, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY), + AP_GROUPEND };