APM:Libraries
AP_RCMapper.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <inttypes.h>
4 #include <AP_Common/AP_Common.h>
5 #include <AP_Param/AP_Param.h>
6 
7 class RCMapper {
8 public:
9  RCMapper();
10 
11  /* Do not allow copies */
12  RCMapper(const RCMapper &other) = delete;
13  RCMapper &operator=(const RCMapper&) = delete;
14 
16  uint8_t roll() const { return _ch_roll; }
17 
19  uint8_t pitch() const { return _ch_pitch; }
20 
22  uint8_t throttle() const { return _ch_throttle; }
23 
25  uint8_t yaw() const { return _ch_yaw; }
26 
28  uint8_t forward() const { return _ch_forward; }
29 
31  uint8_t lateral() const { return _ch_lateral; }
32 
33  static const struct AP_Param::GroupInfo var_info[];
34 
35 private:
36  // channel mappings
37  AP_Int8 _ch_roll;
38  AP_Int8 _ch_pitch;
39  AP_Int8 _ch_yaw;
40  AP_Int8 _ch_throttle;
41  AP_Int8 _ch_forward;
42  AP_Int8 _ch_lateral;
43 };
AP_Int8 _ch_lateral
Definition: AP_RCMapper.h:42
AP_Int8 _ch_forward
Definition: AP_RCMapper.h:41
uint8_t forward() const
forward - return input channel number for forward input
Definition: AP_RCMapper.h:28
uint8_t roll() const
roll - return input channel number for roll / aileron input
Definition: AP_RCMapper.h:16
AP_Int8 _ch_yaw
Definition: AP_RCMapper.h:39
uint8_t yaw() const
yaw - return input channel number for yaw / rudder input
Definition: AP_RCMapper.h:25
uint8_t pitch() const
pitch - return input channel number for pitch / elevator input
Definition: AP_RCMapper.h:19
A system for managing and storing variables that are of general interest to the system.
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_RCMapper.h:33
uint8_t lateral() const
lateral - return input channel number for lateral input
Definition: AP_RCMapper.h:31
AP_Int8 _ch_pitch
Definition: AP_RCMapper.h:38
Common definitions and utility routines for the ArduPilot libraries.
AP_Int8 _ch_roll
Definition: AP_RCMapper.h:37
uint8_t throttle() const
throttle - return input channel number for throttle input
Definition: AP_RCMapper.h:22
RCMapper & operator=(const RCMapper &)=delete
AP_Int8 _ch_throttle
Definition: AP_RCMapper.h:40