Skip to content

Commit

Permalink
Plane: remove rcmap, move Channels into RC_Channels_Plane
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Apr 2, 2019
1 parent 0ec8e3e commit ee84145
Show file tree
Hide file tree
Showing 9 changed files with 47 additions and 34 deletions.
2 changes: 1 addition & 1 deletion ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -261,7 +261,7 @@ void Plane::one_second_loop()
gcs().send_message(MSG_HEARTBEAT);

// make it possible to change control channel ordering at runtime
set_control_channels();
g2.rc_channels.set_control_channels();

#if HAL_WITH_IO_MCU
iomcu.setup_mixing(&rcmap, g.override_channel.get(), g.mixing_gain, g2.manual_rc_mask);
Expand Down
9 changes: 5 additions & 4 deletions ArduPlane/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1082,10 +1082,11 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)

uint32_t tnow = AP_HAL::millis();

manual_override(plane.channel_roll, packet.y, 1000, 2000, tnow);
manual_override(plane.channel_pitch, packet.x, 1000, 2000, tnow, true);
manual_override(plane.channel_throttle, packet.z, 0, 1000, tnow);
manual_override(plane.channel_rudder, packet.r, 1000, 2000, tnow);
RC_Channels_Plane &rc = plane.g2.rc_channels;
manual_override(rc.channel_roll, packet.y, 1000, 2000, tnow);
manual_override(rc.channel_pitch, packet.x, 1000, 2000, tnow, true);
manual_override(rc.channel_throttle, packet.z, 0, 1000, tnow);
manual_override(rc.channel_rudder, packet.r, 1000, 2000, tnow);

// a manual control message is considered to be a 'heartbeat' from the ground station for failsafe purposes
plane.failsafe.last_heartbeat_ms = tnow;
Expand Down
4 changes: 2 additions & 2 deletions ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -966,7 +966,7 @@ const AP_Param::Info Plane::var_info[] = {

// @Group: RCMAP_
// @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp
GOBJECT(rcmap, "RCMAP_", RCMapper),
GOBJECT(rcmap_old, "RCMAP_", RCMapper),

// @Group: SR0_
// @Path: GCS_Mavlink.cpp
Expand Down Expand Up @@ -1322,7 +1322,7 @@ void Plane::load_parameters(void)
Parameters::k_param_rc_11_old, Parameters::k_param_rc_12_old,
Parameters::k_param_rc_13_old, Parameters::k_param_rc_14_old };
const uint16_t old_aux_chan_mask = 0x3FF0;
SRV_Channels::upgrade_parameters(old_rc_keys, old_aux_chan_mask, &rcmap);
SRV_Channels::upgrade_parameters(old_rc_keys, old_aux_chan_mask, &rcmap_old);

// possibly convert elevon and vtail mixers
convert_mixers();
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -323,7 +323,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
13 changes: 6 additions & 7 deletions ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -175,8 +175,8 @@ class Plane : public AP_HAL::HAL::Callbacks {
// main loop scheduler
AP_Scheduler scheduler;

// mapping between input channels
RCMapper rcmap;
// mapping between input channels; only used for parameter conversion
RCMapper rcmap_old;

// board specific config
AP_BoardConfig BoardConfig;
Expand All @@ -187,10 +187,10 @@ class Plane : public AP_HAL::HAL::Callbacks {
#endif

// primary input channels
RC_Channel *channel_roll;
RC_Channel *channel_pitch;
RC_Channel *channel_throttle;
RC_Channel *channel_rudder;
RC_Channel *&channel_roll = g2.rc_channels.channel_roll;
RC_Channel *&channel_pitch = g2.rc_channels.channel_pitch;
RC_Channel *&channel_throttle = g2.rc_channels.channel_throttle;
RC_Channel *&channel_rudder = g2.rc_channels.channel_rudder;

// notification object for LEDs, buzzers etc (parameter set to false disables external leds)
AP_Notify notify;
Expand Down Expand Up @@ -890,7 +890,6 @@ class Plane : public AP_HAL::HAL::Callbacks {
void setup_turn_angle(void);
bool reached_loiter_target(void);
void set_control_channels(void);
void init_rc_in();
void init_rc_out_main();
void init_rc_out_aux();
void rudder_arm_disarm_check();
Expand Down
9 changes: 9 additions & 0 deletions ArduPlane/RC_Channel.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@ class RC_Channels_Plane : public RC_Channels
{
public:

void init() override;

RC_Channel_Plane obj_channels[NUM_RC_CHANNELS];
RC_Channel_Plane *channel(const uint8_t chan) override {
if (chan > NUM_RC_CHANNELS) {
Expand All @@ -32,6 +34,13 @@ class RC_Channels_Plane : public RC_Channels

bool has_valid_input() const override;

void set_control_channels(void);

// primary input control channels
RC_Channel *channel_roll;
RC_Channel *channel_pitch;
RC_Channel *channel_rudder;

protected:

// note that these callbacks are not presently used on Plane:
Expand Down
4 changes: 4 additions & 0 deletions ArduPlane/quadplane.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,10 @@ class QuadPlane
return initialised;
}

bool enabled(void) const {
return enable;
}

// is quadplane assisting?
bool in_assisted_flight(void) const {
return available() && assisted_flight;
Expand Down
30 changes: 17 additions & 13 deletions ArduPlane/radio.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,24 +6,24 @@
/*
allow for runtime change of control channel ordering
*/
void Plane::set_control_channels(void)
void RC_Channels_Plane::set_control_channels(void)
{
if (g.rudder_only) {
init_channel(channel_pitch, RC_Channel::aux_func::PITCH, "Pitch", 2);
init_channel(channel_throttle, RC_Channel::aux_func::THROTTLE, "Throttle", 3);
init_channel(channel_rudder, RC_Channel::aux_func::YAW, "Yaw", 4);
if (plane.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 = channel_rudder;
} else {
channel_roll = RC_Channels::rc_channel(rcmap.roll()-1);
init_channel(channel_roll, RC_Channel::aux_func::ROLL, "Roll", 1);
}
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);

// set rc channel ranges
channel_roll->set_angle(SERVO_MAX);
channel_pitch->set_angle(SERVO_MAX);
channel_rudder->set_angle(SERVO_MAX);
if (!have_reverse_thrust()) {
if (!plane.have_reverse_thrust()) {
// normal operation
channel_throttle->set_range(100);
} else {
Expand All @@ -40,23 +40,27 @@ void Plane::set_control_channels(void)
SRV_Channels::set_angle(SRV_Channel::k_throttleRight, 100);
}

if (!arming.is_armed() && arming.arming_required() == AP_Arming::Required::YES_MIN_PWM) {
SRV_Channels::set_safety_limit(SRV_Channel::k_throttle, have_reverse_thrust()?SRV_Channel::SRV_CHANNEL_LIMIT_TRIM:SRV_Channel::SRV_CHANNEL_LIMIT_MIN);
if (!plane.arming.is_armed() && plane.arming.arming_required() == AP_Arming::YES_MIN_PWM) {
SRV_Channels::set_safety_limit(SRV_Channel::k_throttle, plane.have_reverse_thrust()?SRV_Channel::SRV_CHANNEL_LIMIT_TRIM:SRV_Channel::SRV_CHANNEL_LIMIT_MIN);
}

if (!quadplane.enable) {
if (!plane.quadplane.enabled()) {
// setup correct scaling for ESCs like the UAVCAN PX4ESC which
// take a proportion of speed. For quadplanes we use AP_Motors
// scaling
g2.servo_channels.set_esc_scaling_for(SRV_Channel::k_throttle);
plane.g2.servo_channels.set_esc_scaling_for(SRV_Channel::k_throttle);
}
}

/*
initialise RC input channels
*/
void Plane::init_rc_in()
void RC_Channels_Plane::init()
{
RC_Channels::init();

set_control_channels();

// set rc dead zones
channel_roll->set_default_dead_zone(30);
channel_pitch->set_default_dead_zone(30);
Expand Down
8 changes: 2 additions & 6 deletions ArduPlane/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,8 @@ void Plane::init_ardupilot()

ins.set_log_raw_bit(MASK_LOG_IMU_RAW);

set_control_channels();
// initialise rc channels including setting mode
g2.rc_channels.init();

mavlink_system.sysid = g.sysid_this_mav;

Expand All @@ -67,9 +68,6 @@ void Plane::init_ardupilot()
BoardConfig_CAN.init();
#endif

// initialise rc channels including setting mode
rc().init();

relay.init();

// initialise notify system
Expand Down Expand Up @@ -123,8 +121,6 @@ void Plane::init_ardupilot()
gps.set_log_gps_bit(MASK_LOG_GPS);
gps.init(serial_manager);

init_rc_in(); // sets up rc channels from radio

#if MOUNT == ENABLED
// initialise camera mount
camera_mount.init(serial_manager);
Expand Down

0 comments on commit ee84145

Please sign in to comment.