mirror of https://github.com/ArduPilot/ardupilot
RCMapper: simple mapping object for primary input channels
allows arbitrary mapping of first 4 channels
This commit is contained in:
parent
993bccc60e
commit
e9594c8b80
|
@ -0,0 +1,43 @@
|
|||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_RCMapper.h>
|
||||
|
||||
const AP_Param::GroupInfo RCMapper::var_info[] PROGMEM = {
|
||||
// @Param: ROLL
|
||||
// @DisplayName: Roll channel
|
||||
// @Description: Roll channel number
|
||||
// @Range: 1 8
|
||||
// @Increment: 1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("ROLL", 0, RCMapper, _ch_roll, 1),
|
||||
|
||||
// @Param: PITCH
|
||||
// @DisplayName: Pitch channel
|
||||
// @Description: Pitch channel number
|
||||
// @Range: 1 8
|
||||
// @Increment: 1
|
||||
AP_GROUPINFO("PITCH", 1, RCMapper, _ch_pitch, 2),
|
||||
|
||||
// @Param: THROTTLE
|
||||
// @DisplayName: Throttle channel
|
||||
// @Description: Throttle channel number
|
||||
// @Range: 1 8
|
||||
// @Increment: 1
|
||||
AP_GROUPINFO("THROTTLE", 2, RCMapper, _ch_throttle, 3),
|
||||
|
||||
// @Param: YAW
|
||||
// @DisplayName: Yaw channel
|
||||
// @Description: Yaw channel number
|
||||
// @Range: 1 8
|
||||
// @Increment: 1
|
||||
AP_GROUPINFO("YAW", 3, RCMapper, _ch_yaw, 4),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
// object constructor.
|
||||
RCMapper::RCMapper(void)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
|
@ -0,0 +1,37 @@
|
|||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
#ifndef AP_RCMAPPER_H
|
||||
#define AP_RCMAPPER_H
|
||||
|
||||
#include <inttypes.h>
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Param.h>
|
||||
|
||||
class RCMapper
|
||||
{
|
||||
public:
|
||||
/// Constructor
|
||||
///
|
||||
RCMapper();
|
||||
|
||||
/// roll - return input channel number for roll / aileron input
|
||||
uint8_t roll() const { return _ch_roll; }
|
||||
|
||||
/// pitch - return input channel number for pitch / elevator input
|
||||
uint8_t pitch() const { return _ch_pitch; }
|
||||
|
||||
/// throttle - return input channel number for throttle input
|
||||
uint8_t throttle() const { return _ch_throttle; }
|
||||
|
||||
/// yaw - return input channel number for yaw / rudder input
|
||||
uint8_t yaw() const { return _ch_yaw; }
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
private:
|
||||
// channel mappings
|
||||
AP_Int8 _ch_roll;
|
||||
AP_Int8 _ch_pitch;
|
||||
AP_Int8 _ch_yaw;
|
||||
AP_Int8 _ch_throttle;
|
||||
};
|
||||
#endif
|
Loading…
Reference in New Issue