AP_RCMapper.cpp 3.4 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768
  1. #include <AP_HAL/AP_HAL.h>
  2. #include "AP_RCMapper.h"
  3. const AP_Param::GroupInfo RCMapper::var_info[] = {
  4. // @Param: ROLL
  5. // @DisplayName: Roll channel
  6. // @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.
  7. // @Range: 1 8
  8. // @Increment: 1
  9. // @User: Advanced
  10. // @RebootRequired: True
  11. AP_GROUPINFO("ROLL", 0, RCMapper, _ch_roll, 1),
  12. // @Param: PITCH
  13. // @DisplayName: Pitch channel
  14. // @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.
  15. // @Range: 1 8
  16. // @Increment: 1
  17. // @User: Advanced
  18. // @RebootRequired: True
  19. AP_GROUPINFO("PITCH", 1, RCMapper, _ch_pitch, 2),
  20. // @Param: THROTTLE
  21. // @DisplayName: Throttle channel
  22. // @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.
  23. // @Range: 1 8
  24. // @Increment: 1
  25. // @User: Advanced
  26. // @RebootRequired: True
  27. AP_GROUPINFO("THROTTLE", 2, RCMapper, _ch_throttle, 3),
  28. // @Param: YAW
  29. // @DisplayName: Yaw channel
  30. // @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.
  31. // @Range: 1 8
  32. // @Increment: 1
  33. // @User: Advanced
  34. // @RebootRequired: True
  35. AP_GROUPINFO("YAW", 3, RCMapper, _ch_yaw, 4),
  36. // @Param: FORWARD
  37. // @DisplayName: Forward channel
  38. // @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.
  39. // @Range: 1 8
  40. // @Increment: 1
  41. // @User: Advanced
  42. // @RebootRequired: True
  43. // @Values{Sub}: 1: 1, 2: 2, 3: 3, 4: 4, 5: 5, 6: 6, 7: 7, 8: 8
  44. AP_GROUPINFO_FRAME("FORWARD", 4, RCMapper, _ch_forward, 6, AP_PARAM_FRAME_SUB),
  45. // @Param: LATERAL
  46. // @DisplayName: Lateral channel
  47. // @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.
  48. // @Range: 1 8
  49. // @Increment: 1
  50. // @User: Advanced
  51. // @RebootRequired: True
  52. // @Values{Sub}: 1: 1, 2: 2, 3: 3, 4: 4, 5: 5, 6: 6, 7: 7, 8: 8
  53. AP_GROUPINFO_FRAME("LATERAL", 5, RCMapper, _ch_lateral, 7, AP_PARAM_FRAME_SUB),
  54. AP_GROUPEND
  55. };
  56. // object constructor.
  57. RCMapper::RCMapper(void)
  58. {
  59. AP_Param::setup_object_defaults(this, var_info);
  60. }