Skip to content

Commit

Permalink
AP_RCMapper: Add forward and strafe channel mappings for Sub
Browse files Browse the repository at this point in the history
  • Loading branch information
jaxxzer authored and tridge committed Feb 21, 2017
1 parent 1e8c1e8 commit 2bacc2f
Show file tree
Hide file tree
Showing 2 changed files with 26 additions and 0 deletions.
18 changes: 18 additions & 0 deletions libraries/AP_RCMapper/AP_RCMapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,24 @@ const AP_Param::GroupInfo RCMapper::var_info[] = {
// @RebootRequired: True
AP_GROUPINFO("YAW", 3, RCMapper, _ch_yaw, 4),

// @Param: FORWARD
// @DisplayName: Forward channel
// @Description: Forward channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Forward is normally on channel 5, but you can move it to any channel with this parameter. Reboot is required for changes to take effect.
// @Range: 1 8
// @Increment: 1
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO_FRAME("FORWARD", 4, RCMapper, _ch_forward, 6, AP_PARAM_FRAME_SUB),

// @Param: LATERAL
// @DisplayName: Lateral channel
// @Description: Lateral channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Lateral is normally on channel 6, but you can move it to any channel with this parameter. Reboot is required for changes to take effect.
// @Range: 1 8
// @Increment: 1
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO_FRAME("LATERAL", 5, RCMapper, _ch_lateral, 7, AP_PARAM_FRAME_SUB),

AP_GROUPEND
};

Expand Down
8 changes: 8 additions & 0 deletions libraries/AP_RCMapper/AP_RCMapper.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,12 @@ class RCMapper
/// yaw - return input channel number for yaw / rudder input
uint8_t yaw() const { return _ch_yaw; }

/// forward - return input channel number for forward input
uint8_t forward() const { return _ch_forward; }

/// lateral - return input channel number for lateral input
uint8_t lateral() const { return _ch_lateral; }

static const struct AP_Param::GroupInfo var_info[];

private:
Expand All @@ -31,4 +37,6 @@ class RCMapper
AP_Int8 _ch_pitch;
AP_Int8 _ch_yaw;
AP_Int8 _ch_throttle;
AP_Int8 _ch_forward;
AP_Int8 _ch_lateral;
};

0 comments on commit 2bacc2f

Please sign in to comment.