2021-11-12 06:11:48 -04:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2021-12-03 00:29:43 -04:00
|
|
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
2021-11-12 06:11:48 -04:00
|
|
|
#include "AP_RangeFinder_Benewake_CAN.h"
|
2022-07-11 04:58:31 -03:00
|
|
|
#include <AP_HAL/utility/sparse-endian.h>
|
2021-11-12 06:11:48 -04:00
|
|
|
|
2022-03-12 06:37:29 -04:00
|
|
|
#if AP_RANGEFINDER_BENEWAKE_CAN_ENABLED
|
2021-11-12 06:11:48 -04:00
|
|
|
|
2023-06-19 14:09:46 -03:00
|
|
|
RangeFinder_MultiCAN *AP_RangeFinder_Benewake_CAN::multican;
|
2021-11-12 06:11:48 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
constructor
|
|
|
|
*/
|
|
|
|
AP_RangeFinder_Benewake_CAN::AP_RangeFinder_Benewake_CAN(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) :
|
2023-06-19 14:09:46 -03:00
|
|
|
AP_RangeFinder_Backend_CAN(_state, _params)
|
2021-11-12 06:11:48 -04:00
|
|
|
{
|
2021-12-03 00:29:43 -04:00
|
|
|
if (multican == nullptr) {
|
2023-06-19 14:09:46 -03:00
|
|
|
multican = new RangeFinder_MultiCAN(AP_CAN::Protocol::Benewake, "Benewake MultiCAN");
|
2021-12-03 00:29:43 -04:00
|
|
|
if (multican == nullptr) {
|
|
|
|
AP_BoardConfig::allocation_error("Benewake_CAN");
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
{
|
|
|
|
// add to linked list of drivers
|
|
|
|
WITH_SEMAPHORE(multican->sem);
|
|
|
|
auto *prev = multican->drivers;
|
|
|
|
next = prev;
|
|
|
|
multican->drivers = this;
|
|
|
|
}
|
2021-11-12 06:11:48 -04:00
|
|
|
}
|
|
|
|
|
2022-07-11 04:58:31 -03:00
|
|
|
// handler for incoming frames for H30 radar
|
|
|
|
bool AP_RangeFinder_Benewake_CAN::handle_frame_H30(AP_HAL::CANFrame &frame)
|
|
|
|
{
|
|
|
|
/*
|
|
|
|
The H30 produces 3 targets, each as 16 bit unsigned integers in
|
|
|
|
cm. Only look at target1 for now
|
|
|
|
*/
|
|
|
|
const uint16_t target1_cm = be16toh_ptr(&frame.data[0]);
|
|
|
|
if (target1_cm == 0) {
|
|
|
|
// no target gives 0
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
//uint16_t target2 = be16toh_ptr(&frame.data[2]);
|
|
|
|
//uint16_t target3 = be16toh_ptr(&frame.data[4]);
|
|
|
|
|
2023-07-19 05:00:46 -03:00
|
|
|
accumulate_distance_m(target1_cm * 0.01);
|
2022-07-11 04:58:31 -03:00
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2021-11-12 06:11:48 -04:00
|
|
|
// handler for incoming frames. These come in at 100Hz
|
2021-12-03 00:29:43 -04:00
|
|
|
bool AP_RangeFinder_Benewake_CAN::handle_frame(AP_HAL::CANFrame &frame)
|
2021-11-12 06:11:48 -04:00
|
|
|
{
|
|
|
|
WITH_SEMAPHORE(_sem);
|
2022-07-11 04:58:31 -03:00
|
|
|
if (frame.isExtended()) {
|
|
|
|
// H30 radar uses extended frames
|
|
|
|
const int32_t id = int32_t(frame.id & AP_HAL::CANFrame::MaskExtID);
|
2023-06-19 14:09:46 -03:00
|
|
|
if (!is_correct_id(id)) {
|
2022-07-11 04:58:31 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return handle_frame_H30(frame);
|
|
|
|
}
|
|
|
|
|
2021-11-12 06:11:48 -04:00
|
|
|
const uint16_t id = frame.id & AP_HAL::CANFrame::MaskStdID;
|
2023-06-19 14:09:46 -03:00
|
|
|
if (!is_correct_id(id)) {
|
2021-12-03 00:29:43 -04:00
|
|
|
return false;
|
2021-11-12 06:11:48 -04:00
|
|
|
}
|
2021-12-03 00:29:43 -04:00
|
|
|
|
2022-07-11 04:58:31 -03:00
|
|
|
const uint16_t dist_cm = le16toh_ptr(&frame.data[0]);
|
|
|
|
const uint16_t snr = le16toh_ptr(&frame.data[2]);
|
2021-11-12 06:11:48 -04:00
|
|
|
if (snr_min != 0 && snr < uint16_t(snr_min.get())) {
|
|
|
|
// too low signal strength
|
2021-12-03 00:29:43 -04:00
|
|
|
return true;
|
2021-11-12 06:11:48 -04:00
|
|
|
}
|
2021-12-03 00:29:43 -04:00
|
|
|
|
2023-07-19 05:00:46 -03:00
|
|
|
accumulate_distance_m(dist_cm * 0.01);
|
2023-06-19 14:09:46 -03:00
|
|
|
return true;
|
2021-11-12 06:11:48 -04:00
|
|
|
}
|
|
|
|
|
2022-03-12 06:37:29 -04:00
|
|
|
#endif // AP_RANGEFINDER_BENEWAKE_CAN_ENABLED
|