Skip to content

Commit

Permalink
kill RCMapper
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Feb 14, 2024
1 parent 8f46c4b commit 2c6e357
Show file tree
Hide file tree
Showing 45 changed files with 230 additions and 163 deletions.
1 change: 0 additions & 1 deletion AntennaTracker/wscript
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@ def build(bld):
ap_libraries=bld.ap_common_vehicle_libraries() + [
'AP_Beacon',
'AP_Arming',
'AP_RCMapper',
'AP_OSD',
],
)
Expand Down
3 changes: 0 additions & 3 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,6 @@
#include <AC_WPNav/AC_Loiter.h> // ArduCopter Loiter Mode Library
#include <AC_WPNav/AC_Circle.h> // circle navigation library
#include <AP_Declination/AP_Declination.h> // ArduPilot Mega Declination Helper Library
#include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
#include <AP_LandingGear/AP_LandingGear.h> // Landing Gear library
#include <AC_InputManager/AC_InputManager.h> // Pilot input handling library
Expand Down Expand Up @@ -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;

Expand Down
9 changes: 5 additions & 4 deletions ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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);
}
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
10 changes: 6 additions & 4 deletions ArduCopter/radio.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
1 change: 0 additions & 1 deletion ArduCopter/wscript
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@ def build(bld):
'AP_IRLock',
'AP_InertialNav',
'AP_Motors',
'AP_RCMapper',
'AP_Avoidance',
'AP_AdvancedFailsafe',
'AP_SmartRTL',
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
11 changes: 6 additions & 5 deletions ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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),
Expand Down Expand Up @@ -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),
Expand Down Expand Up @@ -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
}
2 changes: 1 addition & 1 deletion ArduPlane/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down
4 changes: 0 additions & 4 deletions ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,6 @@

#include <AP_Navigation/AP_Navigation.h>
#include <AP_L1_Control/AP_L1_Control.h>
#include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library

#include <AP_Vehicle/AP_Vehicle.h>
#include <AP_TECS/AP_TECS.h>
Expand Down Expand Up @@ -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;
Expand Down
12 changes: 7 additions & 5 deletions ArduPlane/radio.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
1 change: 0 additions & 1 deletion ArduPlane/wscript
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@ def build(bld):
'AP_Camera',
'AP_L1_Control',
'AP_Navigation',
'AP_RCMapper',
'AP_TECS',
'AP_InertialNav',
'AC_WPNav',
Expand Down
11 changes: 5 additions & 6 deletions ArduSub/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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()
Expand Down
2 changes: 1 addition & 1 deletion ArduSub/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down
9 changes: 0 additions & 9 deletions ArduSub/Sub.h
Original file line number Diff line number Diff line change
Expand Up @@ -77,11 +77,6 @@

#include <AP_OpticalFlow/AP_OpticalFlow.h> // Optical Flow library

// libraries which are dependent on #defines in defines.h and/or config.h
#if RCMAP_ENABLED == ENABLED
#include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library
#endif

#include <AP_RPM/AP_RPM_config.h>

#if AP_RPM_ENABLED
Expand Down Expand Up @@ -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
Expand Down
8 changes: 0 additions & 8 deletions ArduSub/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,14 +34,6 @@
# define CIRCLE_NAV_ENABLED ENABLED
#endif

//////////////////////////////////////////////////////////////////////////////
// RCMAP
//

#ifndef RCMAP_ENABLED
# define RCMAP_ENABLED DISABLED
#endif

//////////////////////////////////////////////////////////////////////////////
// Rangefinder
//
Expand Down
1 change: 0 additions & 1 deletion ArduSub/wscript
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@ def build(bld):
'AP_JSButton',
'AP_LeakDetector',
'AP_Motors',
'AP_RCMapper',
'AP_Beacon',
'AP_TemperatureSensor',
'AP_Arming',
Expand Down
3 changes: 0 additions & 3 deletions Blimp/Blimp.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,6 @@
#include <Filter/Filter.h> // Filter library
#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
#include <AP_InertialNav/AP_InertialNav.h> // inertial navigation library
#include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
#include <AP_Arming/AP_Arming.h>
#include <AP_Scripting/AP_Scripting.h>
Expand Down Expand Up @@ -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;

Expand Down
8 changes: 4 additions & 4 deletions Blimp/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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);
}
2 changes: 1 addition & 1 deletion Blimp/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
10 changes: 6 additions & 4 deletions Blimp/radio.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
1 change: 0 additions & 1 deletion Blimp/wscript
Original file line number Diff line number Diff line change
Expand Up @@ -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',
Expand Down
8 changes: 4 additions & 4 deletions Rover/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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),
Expand Down Expand Up @@ -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
}
2 changes: 1 addition & 1 deletion Rover/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down
4 changes: 0 additions & 4 deletions Rover/Rover.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,6 @@
#include <AP_Mount/AP_Mount.h> // Camera/Antenna mount
#include <AP_Param/AP_Param.h>
#include <AP_RangeFinder/AP_RangeFinder.h> // Range finder library
#include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library
#include <AP_RPM/AP_RPM.h> // RPM input library
#include <AP_Scheduler/AP_Scheduler.h> // main loop scheduler
#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
Expand Down Expand Up @@ -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;
Expand Down
6 changes: 3 additions & 3 deletions Rover/radio.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
Loading

0 comments on commit 2c6e357

Please sign in to comment.