APM:Libraries
AP_RCMapper.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 #include "AP_RCMapper.h"
3 
5  // @Param: ROLL
6  // @DisplayName: Roll channel
7  // @Description: Roll channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Roll is normally on channel 1, but you can move it to any channel with this parameter. Reboot is required for changes to take effect.
8  // @Range: 1 8
9  // @Increment: 1
10  // @User: Advanced
11  // @RebootRequired: True
12  AP_GROUPINFO("ROLL", 0, RCMapper, _ch_roll, 1),
13 
14  // @Param: PITCH
15  // @DisplayName: Pitch channel
16  // @Description: Pitch channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Pitch is normally on channel 2, but you can move it to any channel with this parameter. Reboot is required for changes to take effect.
17  // @Range: 1 8
18  // @Increment: 1
19  // @User: Advanced
20  // @RebootRequired: True
21  AP_GROUPINFO("PITCH", 1, RCMapper, _ch_pitch, 2),
22 
23  // @Param: THROTTLE
24  // @DisplayName: Throttle channel
25  // @Description: Throttle channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Throttle is normally on channel 3, but you can move it to any channel with this parameter. Warning APM 2.X: Changing the throttle channel could produce unexpected fail-safe results if connection between receiver and on-board PPM Encoder is lost. Disabling on-board PPM Encoder is recommended. Reboot is required for changes to take effect.
26  // @Range: 1 8
27  // @Increment: 1
28  // @User: Advanced
29  // @RebootRequired: True
30  AP_GROUPINFO("THROTTLE", 2, RCMapper, _ch_throttle, 3),
31 
32  // @Param: YAW
33  // @DisplayName: Yaw channel
34  // @Description: Yaw channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Yaw (also known as rudder) is normally on channel 4, but you can move it to any channel with this parameter. Reboot is required for changes to take effect.
35  // @Range: 1 8
36  // @Increment: 1
37  // @User: Advanced
38  // @RebootRequired: True
39  AP_GROUPINFO("YAW", 3, RCMapper, _ch_yaw, 4),
40 
41  // @Param: FORWARD
42  // @DisplayName: Forward channel
43  // @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.
44  // @Range: 1 8
45  // @Increment: 1
46  // @User: Advanced
47  // @RebootRequired: True
48  AP_GROUPINFO_FRAME("FORWARD", 4, RCMapper, _ch_forward, 6, AP_PARAM_FRAME_SUB),
49 
50  // @Param: LATERAL
51  // @DisplayName: Lateral channel
52  // @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.
53  // @Range: 1 8
54  // @Increment: 1
55  // @User: Advanced
56  // @RebootRequired: True
57  AP_GROUPINFO_FRAME("LATERAL", 5, RCMapper, _ch_lateral, 7, AP_PARAM_FRAME_SUB),
58 
60 };
61 
62 // object constructor.
64 {
66 }
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_RCMapper.h:33
#define AP_GROUPINFO_FRAME(name, idx, clazz, element, def, frame_flags)
Definition: AP_Param.h:96
#define AP_PARAM_FRAME_SUB
Definition: AP_Param.h:80
#define AP_GROUPEND
Definition: AP_Param.h:121
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214