123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228 |
- #include <AP_BoardConfig/AP_BoardConfig.h>
- #include "OpticalFlow.h"
- #include "AP_OpticalFlow_Onboard.h"
- #include "AP_OpticalFlow_SITL.h"
- #include "AP_OpticalFlow_Pixart.h"
- #include "AP_OpticalFlow_PX4Flow.h"
- #include "AP_OpticalFlow_CXOF.h"
- #include "AP_OpticalFlow_MAV.h"
- #include "AP_OpticalFlow_HereFlow.h"
- #include <AP_Logger/AP_Logger.h>
- extern const AP_HAL::HAL& hal;
- #ifndef OPTICAL_FLOW_TYPE_DEFAULT
- #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412 || defined(HAL_HAVE_PIXARTFLOW_SPI)
- #define OPTICAL_FLOW_TYPE_DEFAULT OpticalFlowType::PIXART
- #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
- #define OPTICAL_FLOW_TYPE_DEFAULT OpticalFlowType::BEBOP
- #else
- #define OPTICAL_FLOW_TYPE_DEFAULT OpticalFlowType::NONE
- #endif
- #endif
- const AP_Param::GroupInfo OpticalFlow::var_info[] = {
-
-
-
-
-
-
- AP_GROUPINFO("_TYPE", 0, OpticalFlow, _type, (int8_t)OPTICAL_FLOW_TYPE_DEFAULT),
-
-
-
-
-
-
- AP_GROUPINFO("_FXSCALER", 1, OpticalFlow, _flowScalerX, 0),
-
-
-
-
-
-
- AP_GROUPINFO("_FYSCALER", 2, OpticalFlow, _flowScalerY, 0),
-
-
-
-
-
-
- AP_GROUPINFO("_ORIENT_YAW", 3, OpticalFlow, _yawAngle_cd, 0),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("_POS", 4, OpticalFlow, _pos_offset, 0.0f),
-
-
-
-
-
- AP_GROUPINFO("_ADDR", 5, OpticalFlow, _address, 0),
-
-
-
-
-
-
- AP_GROUPEND
- };
- OpticalFlow::OpticalFlow()
- {
- _singleton = this;
- AP_Param::setup_object_defaults(this, var_info);
- }
- void OpticalFlow::init(uint32_t log_bit)
- {
- _log_bit = log_bit;
-
- if ((_type == (int8_t)OpticalFlowType::NONE) || (backend != nullptr)) {
- return;
- }
- switch ((OpticalFlowType)_type.get()) {
- case OpticalFlowType::NONE:
- break;
- case OpticalFlowType::PX4FLOW:
- backend = AP_OpticalFlow_PX4Flow::detect(*this);
- break;
- case OpticalFlowType::PIXART:
- backend = AP_OpticalFlow_Pixart::detect("pixartflow", *this);
- if (backend == nullptr) {
- backend = AP_OpticalFlow_Pixart::detect("pixartPC15", *this);
- }
- break;
- case OpticalFlowType::BEBOP:
- #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
- backend = new AP_OpticalFlow_Onboard(*this);
- #endif
- break;
- case OpticalFlowType::CXOF:
- backend = AP_OpticalFlow_CXOF::detect(*this);
- break;
- case OpticalFlowType::MAVLINK:
- backend = AP_OpticalFlow_MAV::detect(*this);
- break;
- case OpticalFlowType::UAVCAN:
- #if HAL_WITH_UAVCAN
- backend = new AP_OpticalFlow_HereFlow(*this);
- #endif
- break;
- case OpticalFlowType::SITL:
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- backend = new AP_OpticalFlow_SITL(*this);
- #endif
- break;
- }
- if (backend != nullptr) {
- backend->init();
- }
- }
- void OpticalFlow::update(void)
- {
-
- if (!enabled()) {
- return;
- }
- if (backend != nullptr) {
- backend->update();
- }
-
- _flags.healthy = (AP_HAL::millis() - _last_update_ms < 500);
- }
- void OpticalFlow::handle_msg(const mavlink_message_t &msg)
- {
-
- if (!enabled()) {
- return;
- }
- if (backend != nullptr) {
- backend->handle_msg(msg);
- }
- }
- void OpticalFlow::update_state(const OpticalFlow_state &state)
- {
- _state = state;
- _last_update_ms = AP_HAL::millis();
-
- AP::ahrs_navekf().writeOptFlowMeas(quality(),
- _state.flowRate,
- _state.bodyRate,
- _last_update_ms,
- get_pos_offset());
- Log_Write_Optflow();
- }
- void OpticalFlow::Log_Write_Optflow()
- {
- AP_Logger *logger = AP_Logger::get_singleton();
- if (logger == nullptr) {
- return;
- }
- if (_log_bit != (uint32_t)-1 &&
- !logger->should_log(_log_bit)) {
- return;
- }
- struct log_Optflow pkt = {
- LOG_PACKET_HEADER_INIT(LOG_OPTFLOW_MSG),
- time_us : AP_HAL::micros64(),
- surface_quality : _state.surface_quality,
- flow_x : _state.flowRate.x,
- flow_y : _state.flowRate.y,
- body_x : _state.bodyRate.x,
- body_y : _state.bodyRate.y
- };
- logger->WriteBlock(&pkt, sizeof(pkt));
- }
- OpticalFlow *OpticalFlow::_singleton;
- namespace AP {
- OpticalFlow *opticalflow()
- {
- return OpticalFlow::get_singleton();
- }
- }
|