ardupilot/libraries/AP_RCMapper/AP_RCMapper.cpp

78 lines
3.4 KiB
C++
Raw Normal View History

#include <AP_HAL/AP_HAL.h>
#include "AP_RCMapper.h"
const AP_Param::GroupInfo RCMapper::var_info[] = {
// @Param: ROLL
// @DisplayName: Roll channel
// @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.
// @Range: 1 16
// @Increment: 1
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("ROLL", 0, RCMapper, _ch_roll, 1),
// @Param: PITCH
// @DisplayName: Pitch channel
// @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.
// @Range: 1 16
// @Increment: 1
2013-06-03 03:28:05 -03:00
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("PITCH", 1, RCMapper, _ch_pitch, 2),
// @Param: THROTTLE
// @DisplayName: Throttle channel
// @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. Reboot is required for changes to take effect.
// @Range: 1 16
// @Increment: 1
2013-06-03 03:28:05 -03:00
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("THROTTLE", 2, RCMapper, _ch_throttle, 3),
// @Param: YAW
// @DisplayName: Yaw channel
// @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.
// @Range: 1 16
// @Increment: 1
2013-06-03 03:28:05 -03:00
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("YAW", 3, RCMapper, _ch_yaw, 4),
// @Param{Sub}: 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 16
// @Increment: 1
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO_FRAME("FORWARD", 4, RCMapper, _ch_forward, 6, AP_PARAM_FRAME_SUB),
// @Param{Sub}: 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 16
// @Increment: 1
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO_FRAME("LATERAL", 5, RCMapper, _ch_lateral, 7, AP_PARAM_FRAME_SUB),
AP_GROUPEND
};
2019-12-01 11:32:14 -04:00
// singleton instance
RCMapper *RCMapper::_singleton;
// object constructor.
RCMapper::RCMapper(void)
{
2019-12-01 11:32:14 -04:00
if (_singleton != nullptr) {
AP_HAL::panic("RCMapper must be singleton");
}
AP_Param::setup_object_defaults(this, var_info);
2019-12-01 11:32:14 -04:00
_singleton = this;
}
RCMapper *AP::rcmap() {
return RCMapper::get_singleton();
}