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 Oct 21, 2018
1 parent 4139ca2 commit 25256b1
Show file tree
Hide file tree
Showing 10 changed files with 59 additions and 52 deletions.
2 changes: 1 addition & 1 deletion ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -250,7 +250,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 HAVE_PX4_MIXER
if (!hal.util->get_soft_armed() && (last_mixer_crc == -1)) {
Expand Down
14 changes: 5 additions & 9 deletions ArduPlane/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1216,15 +1216,11 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)

uint32_t tnow = AP_HAL::millis();

int16_t roll = (packet.y == INT16_MAX) ? 0 : plane.channel_roll->get_radio_min() + (plane.channel_roll->get_radio_max() - plane.channel_roll->get_radio_min()) * (packet.y + 1000) / 2000.0f;
int16_t pitch = (packet.x == INT16_MAX) ? 0 : plane.channel_pitch->get_radio_min() + (plane.channel_pitch->get_radio_max() - plane.channel_pitch->get_radio_min()) * (-packet.x + 1000) / 2000.0f;
int16_t throttle = (packet.z == INT16_MAX) ? 0 : plane.channel_throttle->get_radio_min() + (plane.channel_throttle->get_radio_max() - plane.channel_throttle->get_radio_min()) * (packet.z) / 1000.0f;
int16_t yaw = (packet.r == INT16_MAX) ? 0 : plane.channel_rudder->get_radio_min() + (plane.channel_rudder->get_radio_max() - plane.channel_rudder->get_radio_min()) * (packet.r + 1000) / 2000.0f;

RC_Channels::set_override(uint8_t(plane.rcmap.roll() - 1), roll, tnow);
RC_Channels::set_override(uint8_t(plane.rcmap.pitch() - 1), pitch, tnow);
RC_Channels::set_override(uint8_t(plane.rcmap.throttle() - 1), throttle, tnow);
RC_Channels::set_override(uint8_t(plane.rcmap.yaw() - 1), yaw, 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);
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 @@ -973,7 +973,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 @@ -1305,7 +1305,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
14 changes: 6 additions & 8 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 @@ -905,8 +905,6 @@ class Plane : public AP_HAL::HAL::Callbacks {
bool mix_passthrough(char *&buf, uint16_t &buf_size, uint8_t out_chan, uint8_t in_chan);
bool mix_trim_channel(char *&buf, uint16_t &buf_size, uint8_t out_chan);
bool setup_failsafe_mixing(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
22 changes: 11 additions & 11 deletions ArduPlane/px4_mixer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ bool Plane::mix_one_channel(char *&buf, uint16_t &buf_size, uint8_t out_chan, ui
const float limit = 10000;
const SRV_Channel *outch = SRV_Channels::srv_channel(out_chan);

bool is_throttle = in_chan==rcmap.throttle()-1;
const bool is_throttle = (RC_Channel::aux_func)(rc().channel(in_chan).option) == RC_Channel::aux_func::THROTTLE;
int16_t outch_trim = is_throttle?1500:outch->get_trim();

outch_trim = constrain_int16(outch_trim, outch->get_output_min()+1, outch->get_output_max()-1);
Expand Down Expand Up @@ -131,7 +131,7 @@ bool Plane::mix_two_channels(char *&buf, uint16_t &buf_size, uint8_t out_chan, u
/*
create a mixer for k_manual and k_rcin*
*/
bool Plane::mix_passthrough(char *&buf, uint16_t &buf_size, uint8_t out_chan, uint8_t in_chan)
bool Plane::mix_passthrough(char *&buf, uint16_t &buf_size, uint8_t out_chan, const RC_Channel *in_chan)
{
const float limit = 10000;

Expand All @@ -147,7 +147,7 @@ bool Plane::mix_passthrough(char *&buf, uint16_t &buf_size, uint8_t out_chan, ui
return false;
}
if (!print_buffer(buf, buf_size, "S: 0 %u %d %d %d %d %d\n",
in_chan,
in_chan->channel(),
int(limit), int(limit),
0,
int(-limit), int(limit))) {
Expand Down Expand Up @@ -203,33 +203,33 @@ uint16_t Plane::create_mixer(char *buf, uint16_t buf_size, const char *filename)
case SRV_Channel::k_aileron:
case SRV_Channel::k_flaperon_left:
case SRV_Channel::k_flaperon_right:
mix_one_channel(buf, buf_size, i, rcmap.roll()-1);
mix_one_channel(buf, buf_size, i, channel_roll);
break;
case SRV_Channel::k_elevator:
mix_one_channel(buf, buf_size, i, rcmap.pitch()-1);
mix_one_channel(buf, buf_size, i, channel_pitch);
break;
case SRV_Channel::k_throttle:
mix_one_channel(buf, buf_size, i, rcmap.throttle()-1);
mix_one_channel(buf, buf_size, i, channel_throttle);
break;
case SRV_Channel::k_rudder:
case SRV_Channel::k_steering:
mix_one_channel(buf, buf_size, i, rcmap.yaw()-1);
mix_one_channel(buf, buf_size, i, channel_yaw);
break;
case SRV_Channel::k_elevon_left:
case SRV_Channel::k_dspoilerLeft1:
case SRV_Channel::k_dspoilerLeft2:
mix_two_channels(buf, buf_size, i, rcmap.pitch()-1, rcmap.roll()-1, true);
mix_two_channels(buf, buf_size, i, channel_pitch, channel_roll, true);
break;
case SRV_Channel::k_elevon_right:
case SRV_Channel::k_dspoilerRight1:
case SRV_Channel::k_dspoilerRight2:
mix_two_channels(buf, buf_size, i, rcmap.pitch()-1, rcmap.roll()-1, false);
mix_two_channels(buf, buf_size, i, channel_pitch, channel_roll, false);
break;
case SRV_Channel::k_vtail_left:
mix_two_channels(buf, buf_size, i, rcmap.pitch()-1, rcmap.yaw()-1, true);
mix_two_channels(buf, buf_size, i, channel_pitch, channel_yaw, true);
break;
case SRV_Channel::k_vtail_right:
mix_two_channels(buf, buf_size, i, rcmap.pitch()-1, rcmap.yaw()-1, false);
mix_two_channels(buf, buf_size, i, channel_pitch, channel_yaw, false);
break;
case SRV_Channel::k_manual:
mix_passthrough(buf, buf_size, i, i);
Expand Down
4 changes: 4 additions & 0 deletions ArduPlane/quadplane.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,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 (aparm.throttle_min >= 0) {
if (plane.aparm.throttle_min >= 0) {
// normal operation
channel_throttle->set_range(100);
} else {
Expand All @@ -34,23 +34,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::YES_MIN_PWM) {
SRV_Channels::set_safety_limit(SRV_Channel::k_throttle, aparm.throttle_min<0?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.aparm.throttle_min<0?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
10 changes: 3 additions & 7 deletions ArduPlane/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,8 +49,9 @@ 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();

#if HAVE_PX4_MIXER
if (!quadplane.enable) {
// this must be before BoardConfig.init() so if
Expand Down Expand Up @@ -84,9 +85,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 @@ -162,8 +160,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 25256b1

Please sign in to comment.