12 changed files with 340 additions and 9 deletions
@ -0,0 +1,216 @@ |
|||||||
|
#include <AP_HAL/AP_HAL.h> |
||||||
|
|
||||||
|
#if HAL_WITH_UAVCAN |
||||||
|
|
||||||
|
#include "AP_Proximity_UAVCAN.h" |
||||||
|
#include <GCS_MAVLink/GCS.h> |
||||||
|
#include <AP_BoardConfig/AP_BoardConfig_CAN.h> |
||||||
|
#include <AP_UAVCAN/AP_UAVCAN.h> |
||||||
|
|
||||||
|
#include<zrzk/equipment/range_sensor/Proximity.hpp> |
||||||
|
|
||||||
|
extern const AP_HAL::HAL& hal; |
||||||
|
AP_Proximity_UAVCAN::DetectedModules AP_Proximity_UAVCAN::_detected_modules[] = {0}; |
||||||
|
UC_REGISTRY_BINDER(ProximityCb, zrzk::equipment::range_sensor::Proximity); |
||||||
|
|
||||||
|
#define debug_baro_uavcan(level_debug, can_driver, fmt, args...) do { if ((level_debug) <= AP::can().get_debug_level_driver(can_driver)) { printf(fmt, ##args); }} while (0) |
||||||
|
|
||||||
|
//HAL_Semaphore AP_Airspeed_UAVCAN::_sem_registry;
|
||||||
|
|
||||||
|
AP_Proximity_UAVCAN::AP_Proximity_UAVCAN( |
||||||
|
AP_Proximity &_frontend, |
||||||
|
AP_Proximity::Proximity_State &_state): |
||||||
|
AP_Proximity_Backend(_frontend,_state) |
||||||
|
{ |
||||||
|
AP_Proximity_UAVCAN *backend = nullptr; |
||||||
|
for (uint8_t i = 0; i < PROXIMITY_MAX_INSTANCES; i++) |
||||||
|
{ |
||||||
|
if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_uavcan != nullptr) |
||||||
|
{ |
||||||
|
backend = new AP_Proximity_UAVCAN(_frontend, _state); |
||||||
|
if (backend == nullptr) |
||||||
|
{ |
||||||
|
debug_baro_uavcan(2, |
||||||
|
_detected_modules[i].ap_uavcan->get_driver_index(), |
||||||
|
"Failed register UAVCAN Proximity Node %d on Bus %d\n", |
||||||
|
_detected_modules[i].node_id, |
||||||
|
_detected_modules[i].ap_uavcan->get_driver_index()); |
||||||
|
} |
||||||
|
else |
||||||
|
{ |
||||||
|
_detected_modules[i].driver = backend; |
||||||
|
backend->_ap_uavcan = _detected_modules[i].ap_uavcan; |
||||||
|
backend->_node_id = _detected_modules[i].node_id; |
||||||
|
backend->register_sensor(); |
||||||
|
debug_baro_uavcan(2, |
||||||
|
_detected_modules[i].ap_uavcan->get_driver_index(), |
||||||
|
"Registered UAVCAN Proximity Node %d on Bus %d\n", |
||||||
|
_detected_modules[i].node_id, |
||||||
|
_detected_modules[i].ap_uavcan->get_driver_index()); |
||||||
|
} |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void AP_Proximity_UAVCAN::subscribe_msgs(AP_UAVCAN *ap_uavcan) |
||||||
|
{ |
||||||
|
if (ap_uavcan == nullptr) |
||||||
|
{ |
||||||
|
return; |
||||||
|
} |
||||||
|
|
||||||
|
auto *node = ap_uavcan->get_node(); |
||||||
|
|
||||||
|
uavcan::Subscriber<zrzk::equipment::range_sensor::Proximity, ProximityCb> *proximity_listener; |
||||||
|
proximity_listener = new uavcan::Subscriber<zrzk::equipment::range_sensor::Proximity, ProximityCb>(*node); |
||||||
|
// Register method to handle incoming RangeFinder measurement
|
||||||
|
const int proximity_listener_res = proximity_listener->start(ProximityCb(ap_uavcan, &handle_proximity_data)); |
||||||
|
if (proximity_listener_res < 0) |
||||||
|
{ |
||||||
|
AP_HAL::panic("UAVCAN RangeFinder subscriber start problem\n\r"); |
||||||
|
return; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
bool AP_Proximity_UAVCAN::detect(AP_Proximity &_frontend, |
||||||
|
AP_Proximity::Proximity_State &_state) |
||||||
|
{ |
||||||
|
AP_Proximity_UAVCAN *backend = nullptr; |
||||||
|
for (uint8_t i = 0; i < PROXIMITY_MAX_INSTANCES; i++) |
||||||
|
{ |
||||||
|
if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_uavcan != nullptr) |
||||||
|
{ |
||||||
|
backend = new AP_Proximity_UAVCAN(_frontend, _state); |
||||||
|
if (backend == nullptr) |
||||||
|
{ |
||||||
|
debug_baro_uavcan(2, |
||||||
|
_detected_modules[i].ap_uavcan->get_driver_index(), |
||||||
|
"Failed register UAVCAN Proximity Node %d on Bus %d\n", |
||||||
|
_detected_modules[i].node_id, |
||||||
|
_detected_modules[i].ap_uavcan->get_driver_index()); |
||||||
|
} |
||||||
|
else |
||||||
|
{ |
||||||
|
_detected_modules[i].driver = backend; |
||||||
|
backend->_ap_uavcan = _detected_modules[i].ap_uavcan; |
||||||
|
backend->_node_id = _detected_modules[i].node_id; |
||||||
|
// backend->register_sensor();
|
||||||
|
debug_baro_uavcan(2, |
||||||
|
_detected_modules[i].ap_uavcan->get_driver_index(), |
||||||
|
"Registered UAVCAN Proximity Node %d on Bus %d\n", |
||||||
|
_detected_modules[i].node_id, |
||||||
|
_detected_modules[i].ap_uavcan->get_driver_index()); |
||||||
|
} |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
return backend; |
||||||
|
} |
||||||
|
|
||||||
|
AP_Proximity_UAVCAN *AP_Proximity_UAVCAN::get_uavcan_backend(AP_UAVCAN *ap_uavcan, uint8_t node_id, bool create_new) |
||||||
|
{ |
||||||
|
if (ap_uavcan == nullptr) |
||||||
|
{ |
||||||
|
return nullptr; |
||||||
|
} |
||||||
|
|
||||||
|
for (uint8_t i = 0; i < PROXIMITY_MAX_INSTANCES; i++) { |
||||||
|
if (_detected_modules[i].driver != nullptr && |
||||||
|
_detected_modules[i].ap_uavcan == ap_uavcan &&
|
||||||
|
_detected_modules[i].node_id == node_id) { |
||||||
|
return _detected_modules[i].driver; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
if (create_new) { |
||||||
|
bool already_detected = false; |
||||||
|
//Check if there's an empty spot for possible registeration
|
||||||
|
for (uint8_t i = 0; i < PROXIMITY_MAX_INSTANCES; i++) { |
||||||
|
if (_detected_modules[i].ap_uavcan == ap_uavcan && _detected_modules[i].node_id == node_id) { |
||||||
|
//Already Detected
|
||||||
|
already_detected = true; |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
if (!already_detected) { |
||||||
|
for (uint8_t i = 0; i < PROXIMITY_MAX_INSTANCES; i++) { |
||||||
|
if (_detected_modules[i].ap_uavcan == nullptr) { |
||||||
|
_detected_modules[i].ap_uavcan = ap_uavcan; |
||||||
|
_detected_modules[i].node_id = node_id; |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
return nullptr; |
||||||
|
|
||||||
|
} |
||||||
|
|
||||||
|
float AP_Proximity_UAVCAN::distance_max() const |
||||||
|
{ |
||||||
|
return 40.0f; |
||||||
|
} |
||||||
|
|
||||||
|
float AP_Proximity_UAVCAN::distance_min() const |
||||||
|
{ |
||||||
|
return 0.20f; |
||||||
|
} |
||||||
|
|
||||||
|
void AP_Proximity_UAVCAN::update(void) |
||||||
|
{ |
||||||
|
//WITH_SEMAPHORE(_sem_registry);
|
||||||
|
update_sector_data(0, d1_cm); // d1
|
||||||
|
update_sector_data(45, d8_cm); // d8
|
||||||
|
update_sector_data(90, d7_cm); // d7
|
||||||
|
update_sector_data(135, d6_cm); // d6
|
||||||
|
update_sector_data(180, d5_cm); // d5
|
||||||
|
update_sector_data(225, d4_cm); // d4
|
||||||
|
update_sector_data(270, d3_cm); // d3
|
||||||
|
update_sector_data(315, d2_cm); // d2
|
||||||
|
|
||||||
|
gcs().send_text(MAV_SEVERITY_INFO,"update data\r\n"); |
||||||
|
if ((_last_distance_received_ms == 0) || (AP_HAL::millis() - _last_distance_received_ms > PROXIMITY_UAVCAN_TIMEOUT_MS)) |
||||||
|
{ |
||||||
|
set_status(AP_Proximity::Status::NoData); |
||||||
|
gcs().send_text(MAV_SEVERITY_INFO,"NoData\r\n"); |
||||||
|
} |
||||||
|
else |
||||||
|
{ |
||||||
|
set_status(AP_Proximity::Status::Good); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void AP_Proximity_UAVCAN::handle_proximity_data(AP_UAVCAN *ap_uavcan, uint8_t node_id, const ProximityCb &cb) |
||||||
|
{ |
||||||
|
// WITH_SEMAPHORE(_sem_registry);
|
||||||
|
AP_Proximity_UAVCAN *driver = get_uavcan_backend(ap_uavcan, node_id, true); |
||||||
|
if (driver == nullptr) |
||||||
|
{ |
||||||
|
gcs().send_text(MAV_SEVERITY_INFO, "driver == nullptr\r\n"); |
||||||
|
return; |
||||||
|
} |
||||||
|
// WITH_SEMAPHORE(driver->_sem_proximity);
|
||||||
|
driver->d1_cm = cb.msg->d0; |
||||||
|
driver->d2_cm = cb.msg->d45; |
||||||
|
driver->d3_cm = cb.msg->d90; |
||||||
|
driver->d5_cm = cb.msg->d90; |
||||||
|
driver->d6_cm = cb.msg->d90; |
||||||
|
driver->d7_cm = cb.msg->d90; |
||||||
|
driver->d8_cm = cb.msg->d90; |
||||||
|
gcs().send_text(MAV_SEVERITY_INFO, "get_proximity_data\r\n"); |
||||||
|
} |
||||||
|
|
||||||
|
void AP_Proximity_UAVCAN::update_sector_data(int16_t angle_deg, uint16_t distance_cm) |
||||||
|
{ |
||||||
|
const uint8_t sector = convert_angle_to_sector(angle_deg); |
||||||
|
_angle[sector] = angle_deg; |
||||||
|
_distance[sector] = ((float)distance_cm) / 100; |
||||||
|
_distance_valid[sector] = distance_cm != 0xffff; |
||||||
|
_last_distance_received_ms = AP_HAL::millis(); |
||||||
|
// update boundary used for avoidance
|
||||||
|
update_boundary_for_sector(sector, true); |
||||||
|
} |
||||||
|
|
||||||
|
#endif |
@ -0,0 +1,54 @@ |
|||||||
|
#pragma once |
||||||
|
|
||||||
|
#include "AP_Proximity_Backend.h" |
||||||
|
|
||||||
|
#if HAL_WITH_UAVCAN |
||||||
|
#include <AP_UAVCAN/AP_UAVCAN.h> |
||||||
|
|
||||||
|
class ProximityCb; |
||||||
|
#define PROXIMITY_UAVCAN_TIMEOUT_MS 300 |
||||||
|
class AP_Proximity_UAVCAN : public AP_Proximity_Backend |
||||||
|
{ |
||||||
|
public: |
||||||
|
AP_Proximity_UAVCAN(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state); |
||||||
|
|
||||||
|
void update(void) override; |
||||||
|
// get maximum and minimum distances (in meters) of sensor
|
||||||
|
float distance_max() const override; |
||||||
|
float distance_min() const override; |
||||||
|
|
||||||
|
static void subscribe_msgs(AP_UAVCAN *ap_uavcan); |
||||||
|
static AP_Proximity_UAVCAN *get_uavcan_backend(AP_UAVCAN *ap_uavcan, uint8_t node_id, bool create_new); |
||||||
|
static bool detect(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state); |
||||||
|
static void handle_proximity_data(AP_UAVCAN *ap_uavcan, uint8_t node_id, const ProximityCb &cb); |
||||||
|
//uint8_t _instance;
|
||||||
|
AP_Proximity::Proximity_State _status; |
||||||
|
AP_UAVCAN *_ap_uavcan; |
||||||
|
uint8_t _node_id; |
||||||
|
|
||||||
|
inline void register_sensor() |
||||||
|
{ |
||||||
|
// instance = frontend.register_sensor();
|
||||||
|
} |
||||||
|
// HAL_Semaphore _sem_proximity;
|
||||||
|
//bool new_data;
|
||||||
|
//MAV_DISTANCE_SENSOR _sensor_type;
|
||||||
|
uint32_t _last_distance_received_ms; |
||||||
|
uint16_t d1_cm; |
||||||
|
uint16_t d2_cm; |
||||||
|
uint16_t d3_cm; |
||||||
|
uint16_t d4_cm; |
||||||
|
uint16_t d5_cm; |
||||||
|
uint16_t d6_cm; |
||||||
|
uint16_t d7_cm; |
||||||
|
uint16_t d8_cm; |
||||||
|
void update_sector_data(int16_t angle_deg, uint16_t distance_cm); |
||||||
|
|
||||||
|
static struct DetectedModules |
||||||
|
{ |
||||||
|
AP_UAVCAN *ap_uavcan; |
||||||
|
uint8_t node_id; |
||||||
|
AP_Proximity_UAVCAN *driver; |
||||||
|
} _detected_modules[PROXIMITY_MAX_INSTANCES]; |
||||||
|
}; |
||||||
|
#endif //HAL_WITH_UAVCAN
|
@ -0,0 +1,23 @@ |
|||||||
|
uint8 sensor_id |
||||||
|
|
||||||
|
uint5 SENSOR_TYPE_UNDEFINED = 0 |
||||||
|
uint5 SENSOR_TYPE_SONAR = 1 |
||||||
|
uint5 SENSOR_TYPE_LIDAR = 2 |
||||||
|
uint5 SENSOR_TYPE_RADAR = 3 |
||||||
|
uint5 sensor_type |
||||||
|
|
||||||
|
uint3 READING_TYPE_UNDEFINED = 0 # Range is unknown |
||||||
|
uint3 READING_TYPE_VALID_RANGE = 1 # Range field contains valid distance |
||||||
|
uint3 READING_TYPE_TOO_CLOSE = 2 # Range field contains min range for the sensor |
||||||
|
uint3 READING_TYPE_TOO_FAR = 3 # Range field contains max range for the sensor |
||||||
|
uint3 reading_type |
||||||
|
|
||||||
|
uint16 d0 # Meters distance_cm |
||||||
|
uint16 d45 |
||||||
|
uint16 d90 |
||||||
|
uint16 d135 |
||||||
|
uint16 d180 |
||||||
|
uint16 d225 |
||||||
|
uint16 d270 |
||||||
|
uint16 d315 |
||||||
|
|
@ -0,0 +1,3 @@ |
|||||||
|
uint8 id |
||||||
|
uint8 type |
||||||
|
uint8[<64] message |
Loading…
Reference in new issue