OpticalFlow.cpp 7.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228
  1. #include <AP_BoardConfig/AP_BoardConfig.h>
  2. #include "OpticalFlow.h"
  3. #include "AP_OpticalFlow_Onboard.h"
  4. #include "AP_OpticalFlow_SITL.h"
  5. #include "AP_OpticalFlow_Pixart.h"
  6. #include "AP_OpticalFlow_PX4Flow.h"
  7. #include "AP_OpticalFlow_CXOF.h"
  8. #include "AP_OpticalFlow_MAV.h"
  9. #include "AP_OpticalFlow_HereFlow.h"
  10. #include <AP_Logger/AP_Logger.h>
  11. extern const AP_HAL::HAL& hal;
  12. #ifndef OPTICAL_FLOW_TYPE_DEFAULT
  13. #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412 || defined(HAL_HAVE_PIXARTFLOW_SPI)
  14. #define OPTICAL_FLOW_TYPE_DEFAULT OpticalFlowType::PIXART
  15. #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
  16. #define OPTICAL_FLOW_TYPE_DEFAULT OpticalFlowType::BEBOP
  17. #else
  18. #define OPTICAL_FLOW_TYPE_DEFAULT OpticalFlowType::NONE
  19. #endif
  20. #endif
  21. const AP_Param::GroupInfo OpticalFlow::var_info[] = {
  22. // @Param: _TYPE
  23. // @DisplayName: Optical flow sensor type
  24. // @Description: Optical flow sensor type
  25. // @Values: 0:None, 1:PX4Flow, 2:Pixart, 3:Bebop, 4:CXOF, 5:MAVLink, 6:UAVCAN
  26. // @User: Standard
  27. // @RebootRequired: True
  28. AP_GROUPINFO("_TYPE", 0, OpticalFlow, _type, (int8_t)OPTICAL_FLOW_TYPE_DEFAULT),
  29. // @Param: _FXSCALER
  30. // @DisplayName: X axis optical flow scale factor correction
  31. // @Description: This sets the parts per thousand scale factor correction applied to the flow sensor X axis optical rate. It can be used to correct for variations in effective focal length. Each positive increment of 1 increases the scale factor applied to the X axis optical flow reading by 0.1%. Negative values reduce the scale factor.
  32. // @Range: -200 +200
  33. // @Increment: 1
  34. // @User: Standard
  35. AP_GROUPINFO("_FXSCALER", 1, OpticalFlow, _flowScalerX, 0),
  36. // @Param: _FYSCALER
  37. // @DisplayName: Y axis optical flow scale factor correction
  38. // @Description: This sets the parts per thousand scale factor correction applied to the flow sensor Y axis optical rate. It can be used to correct for variations in effective focal length. Each positive increment of 1 increases the scale factor applied to the Y axis optical flow reading by 0.1%. Negative values reduce the scale factor.
  39. // @Range: -200 +200
  40. // @Increment: 1
  41. // @User: Standard
  42. AP_GROUPINFO("_FYSCALER", 2, OpticalFlow, _flowScalerY, 0),
  43. // @Param: _ORIENT_YAW
  44. // @DisplayName: Flow sensor yaw alignment
  45. // @Description: Specifies the number of centi-degrees that the flow sensor is yawed relative to the vehicle. A sensor with its X-axis pointing to the right of the vehicle X axis has a positive yaw angle.
  46. // @Range: -18000 +18000
  47. // @Increment: 1
  48. // @User: Standard
  49. AP_GROUPINFO("_ORIENT_YAW", 3, OpticalFlow, _yawAngle_cd, 0),
  50. // @Param: _POS_X
  51. // @DisplayName: X position offset
  52. // @Description: X position of the optical flow sensor focal point in body frame. Positive X is forward of the origin.
  53. // @Units: m
  54. // @Range: -10 10
  55. // @User: Advanced
  56. // @Param: _POS_Y
  57. // @DisplayName: Y position offset
  58. // @Description: Y position of the optical flow sensor focal point in body frame. Positive Y is to the right of the origin.
  59. // @Units: m
  60. // @Range: -10 10
  61. // @User: Advanced
  62. // @Param: _POS_Z
  63. // @DisplayName: Z position offset
  64. // @Description: Z position of the optical flow sensor focal point in body frame. Positive Z is down from the origin.
  65. // @Units: m
  66. // @Range: -10 10
  67. // @User: Advanced
  68. AP_GROUPINFO("_POS", 4, OpticalFlow, _pos_offset, 0.0f),
  69. // @Param: _ADDR
  70. // @DisplayName: Address on the bus
  71. // @Description: This is used to select between multiple possible I2C addresses for some sensor types. For PX4Flow you can choose 0 to 7 for the 8 possible addresses on the I2C bus.
  72. // @Range: 0 127
  73. // @User: Advanced
  74. AP_GROUPINFO("_ADDR", 5, OpticalFlow, _address, 0),
  75. // the parameter description below is for GCSs (like MP) that use master for the parameter descriptions. This should be removed when Copter-3.7 is released
  76. // @Param: _ENABLE
  77. // @DisplayName: Optical flow enable/disable
  78. // @Description: Setting this to Enabled(1) will enable optical flow. Setting this to Disabled(0) will disable optical flow
  79. // @Values: 0:Disabled, 1:Enabled
  80. // @User: Standard
  81. AP_GROUPEND
  82. };
  83. // default constructor
  84. OpticalFlow::OpticalFlow()
  85. {
  86. _singleton = this;
  87. AP_Param::setup_object_defaults(this, var_info);
  88. }
  89. void OpticalFlow::init(uint32_t log_bit)
  90. {
  91. _log_bit = log_bit;
  92. // return immediately if not enabled or backend already created
  93. if ((_type == (int8_t)OpticalFlowType::NONE) || (backend != nullptr)) {
  94. return;
  95. }
  96. switch ((OpticalFlowType)_type.get()) {
  97. case OpticalFlowType::NONE:
  98. break;
  99. case OpticalFlowType::PX4FLOW:
  100. backend = AP_OpticalFlow_PX4Flow::detect(*this);
  101. break;
  102. case OpticalFlowType::PIXART:
  103. backend = AP_OpticalFlow_Pixart::detect("pixartflow", *this);
  104. if (backend == nullptr) {
  105. backend = AP_OpticalFlow_Pixart::detect("pixartPC15", *this);
  106. }
  107. break;
  108. case OpticalFlowType::BEBOP:
  109. #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
  110. backend = new AP_OpticalFlow_Onboard(*this);
  111. #endif
  112. break;
  113. case OpticalFlowType::CXOF:
  114. backend = AP_OpticalFlow_CXOF::detect(*this);
  115. break;
  116. case OpticalFlowType::MAVLINK:
  117. backend = AP_OpticalFlow_MAV::detect(*this);
  118. break;
  119. case OpticalFlowType::UAVCAN:
  120. #if HAL_WITH_UAVCAN
  121. backend = new AP_OpticalFlow_HereFlow(*this);
  122. #endif
  123. break;
  124. case OpticalFlowType::SITL:
  125. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  126. backend = new AP_OpticalFlow_SITL(*this);
  127. #endif
  128. break;
  129. }
  130. if (backend != nullptr) {
  131. backend->init();
  132. }
  133. }
  134. void OpticalFlow::update(void)
  135. {
  136. // exit immediately if not enabled
  137. if (!enabled()) {
  138. return;
  139. }
  140. if (backend != nullptr) {
  141. backend->update();
  142. }
  143. // only healthy if the data is less than 0.5s old
  144. _flags.healthy = (AP_HAL::millis() - _last_update_ms < 500);
  145. }
  146. void OpticalFlow::handle_msg(const mavlink_message_t &msg)
  147. {
  148. // exit immediately if not enabled
  149. if (!enabled()) {
  150. return;
  151. }
  152. if (backend != nullptr) {
  153. backend->handle_msg(msg);
  154. }
  155. }
  156. void OpticalFlow::update_state(const OpticalFlow_state &state)
  157. {
  158. _state = state;
  159. _last_update_ms = AP_HAL::millis();
  160. // write to log and send to EKF if new data has arrived
  161. AP::ahrs_navekf().writeOptFlowMeas(quality(),
  162. _state.flowRate,
  163. _state.bodyRate,
  164. _last_update_ms,
  165. get_pos_offset());
  166. Log_Write_Optflow();
  167. }
  168. void OpticalFlow::Log_Write_Optflow()
  169. {
  170. AP_Logger *logger = AP_Logger::get_singleton();
  171. if (logger == nullptr) {
  172. return;
  173. }
  174. if (_log_bit != (uint32_t)-1 &&
  175. !logger->should_log(_log_bit)) {
  176. return;
  177. }
  178. struct log_Optflow pkt = {
  179. LOG_PACKET_HEADER_INIT(LOG_OPTFLOW_MSG),
  180. time_us : AP_HAL::micros64(),
  181. surface_quality : _state.surface_quality,
  182. flow_x : _state.flowRate.x,
  183. flow_y : _state.flowRate.y,
  184. body_x : _state.bodyRate.x,
  185. body_y : _state.bodyRate.y
  186. };
  187. logger->WriteBlock(&pkt, sizeof(pkt));
  188. }
  189. // singleton instance
  190. OpticalFlow *OpticalFlow::_singleton;
  191. namespace AP {
  192. OpticalFlow *opticalflow()
  193. {
  194. return OpticalFlow::get_singleton();
  195. }
  196. }