|
|
|
@ -8,6 +8,13 @@
@@ -8,6 +8,13 @@
|
|
|
|
|
#include <AP_UAVCAN/AP_UAVCAN.h> |
|
|
|
|
|
|
|
|
|
#include <zrzk/equipment/range_sensor/Proximity.hpp> |
|
|
|
|
#define PRX_DEBUG 1 |
|
|
|
|
#if PRX_DEBUG |
|
|
|
|
#include <GCS_MAVLink/GCS.h> |
|
|
|
|
# define Prx_Debug(fmt, args ...) gcs().send_text(MAV_SEVERITY_INFO, "prx-%d: " fmt "", __LINE__, ## args) |
|
|
|
|
#else |
|
|
|
|
# define Prx_Debug(fmt, args ...) |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL &hal; |
|
|
|
|
|
|
|
|
@ -16,18 +23,24 @@ extern const AP_HAL::HAL &hal;
@@ -16,18 +23,24 @@ extern const AP_HAL::HAL &hal;
|
|
|
|
|
{ \
|
|
|
|
|
if ((level_debug) <= AP::can().get_debug_level_driver(can_driver)) \
|
|
|
|
|
{ \
|
|
|
|
|
printf(fmt, ##args); \
|
|
|
|
|
hal.console->printf(fmt, ##args); \
|
|
|
|
|
} \
|
|
|
|
|
} while (0) |
|
|
|
|
|
|
|
|
|
HAL_Semaphore AP_Proximity_UAVCAN::_sem_registry; |
|
|
|
|
UC_REGISTRY_BINDER(ProximityCb, zrzk::equipment::range_sensor::Proximity); |
|
|
|
|
|
|
|
|
|
uint8_t AP_Proximity_UAVCAN::_node_id = 0; |
|
|
|
|
AP_Proximity_UAVCAN* AP_Proximity_UAVCAN::_driver = nullptr; |
|
|
|
|
AP_UAVCAN* AP_Proximity_UAVCAN::_ap_uavcan = nullptr; |
|
|
|
|
|
|
|
|
|
AP_Proximity_UAVCAN::DetectedModules AP_Proximity_UAVCAN::_detected_modules[] = {0}; |
|
|
|
|
|
|
|
|
|
AP_Proximity_UAVCAN::AP_Proximity_UAVCAN(AP_Proximity &_frontend, |
|
|
|
|
AP_Proximity::Proximity_State &_state) :
|
|
|
|
|
AP_Proximity_Backend(_frontend, _state) |
|
|
|
|
{ |
|
|
|
|
_driver = this; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void AP_Proximity_UAVCAN::subscribe_msgs(AP_UAVCAN *ap_uavcan) |
|
|
|
@ -56,7 +69,16 @@ AP_Proximity_Backend *AP_Proximity_UAVCAN::probe(AP_Proximity &_frontend,
@@ -56,7 +69,16 @@ AP_Proximity_Backend *AP_Proximity_UAVCAN::probe(AP_Proximity &_frontend,
|
|
|
|
|
WITH_SEMAPHORE(_sem_registry); |
|
|
|
|
|
|
|
|
|
AP_Proximity_UAVCAN *backend = nullptr; |
|
|
|
|
|
|
|
|
|
Prx_Debug("---------- AP_Proximity_UAVCAN ----------"); |
|
|
|
|
backend = new AP_Proximity_UAVCAN(_frontend, _state); |
|
|
|
|
if (backend == nullptr) |
|
|
|
|
{ |
|
|
|
|
Prx_Debug("backend:%d",(int)backend); |
|
|
|
|
}else{ |
|
|
|
|
|
|
|
|
|
Prx_Debug("faild,backend"); |
|
|
|
|
} |
|
|
|
|
/*
|
|
|
|
|
for (uint8_t i = 0; i < PROXIMITY_MAX_INSTANCES; i++) |
|
|
|
|
{ |
|
|
|
|
if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_uavcan != nullptr) |
|
|
|
@ -64,6 +86,11 @@ AP_Proximity_Backend *AP_Proximity_UAVCAN::probe(AP_Proximity &_frontend,
@@ -64,6 +86,11 @@ AP_Proximity_Backend *AP_Proximity_UAVCAN::probe(AP_Proximity &_frontend,
|
|
|
|
|
backend = new AP_Proximity_UAVCAN(_frontend, _state); |
|
|
|
|
if (backend == nullptr) |
|
|
|
|
{ |
|
|
|
|
Prx_Debug("------index:%d, Failed register Node %d on Bus %d\n", |
|
|
|
|
_detected_modules[i].ap_uavcan->get_driver_index(), |
|
|
|
|
_detected_modules[i].node_id, |
|
|
|
|
_detected_modules[i].ap_uavcan->get_driver_index()); |
|
|
|
|
|
|
|
|
|
debug_proximity_uavcan(2, |
|
|
|
|
_detected_modules[i].ap_uavcan->get_driver_index(), |
|
|
|
|
"Failed register UAVCAN Proximity Node %d on Bus %d\n", |
|
|
|
@ -72,6 +99,11 @@ AP_Proximity_Backend *AP_Proximity_UAVCAN::probe(AP_Proximity &_frontend,
@@ -72,6 +99,11 @@ AP_Proximity_Backend *AP_Proximity_UAVCAN::probe(AP_Proximity &_frontend,
|
|
|
|
|
} |
|
|
|
|
else |
|
|
|
|
{ |
|
|
|
|
Prx_Debug("-----index:%d, Registered Node %d on Bus %d\n", |
|
|
|
|
_detected_modules[i].ap_uavcan->get_driver_index(), |
|
|
|
|
_detected_modules[i].node_id, |
|
|
|
|
_detected_modules[i].ap_uavcan->get_driver_index()); |
|
|
|
|
|
|
|
|
|
_detected_modules[i].driver = backend; |
|
|
|
|
debug_proximity_uavcan(2, |
|
|
|
|
_detected_modules[i].ap_uavcan->get_driver_index(), |
|
|
|
@ -82,6 +114,8 @@ AP_Proximity_Backend *AP_Proximity_UAVCAN::probe(AP_Proximity &_frontend,
@@ -82,6 +114,8 @@ AP_Proximity_Backend *AP_Proximity_UAVCAN::probe(AP_Proximity &_frontend,
|
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
*/ |
|
|
|
|
Prx_Debug("---------- AP_Proximity_UAVCAN ----------\n"); |
|
|
|
|
return backend; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -166,14 +200,37 @@ void AP_Proximity_UAVCAN::update(void)
@@ -166,14 +200,37 @@ void AP_Proximity_UAVCAN::update(void)
|
|
|
|
|
|
|
|
|
|
void AP_Proximity_UAVCAN::handle_proximity_data_trampoline(AP_UAVCAN *ap_uavcan, uint8_t node_id, const ProximityCb &cb) |
|
|
|
|
{ |
|
|
|
|
WITH_SEMAPHORE(_sem_registry); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if (_driver == nullptr) { |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (_ap_uavcan == nullptr) { |
|
|
|
|
_ap_uavcan = ap_uavcan; |
|
|
|
|
_node_id = node_id; |
|
|
|
|
Prx_Debug("---- uavcan: ap:%d,id:%d ----",(int)_ap_uavcan,_node_id); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (_ap_uavcan == ap_uavcan && _node_id == node_id) { |
|
|
|
|
WITH_SEMAPHORE(_sem_registry); |
|
|
|
|
_driver->_interim_data.d1_cm = cb.msg->d0; |
|
|
|
|
_driver->_interim_data.d2_cm = cb.msg->d45; |
|
|
|
|
_driver->_interim_data.d3_cm = cb.msg->d90; |
|
|
|
|
_driver->_interim_data.d4_cm = cb.msg->d135; |
|
|
|
|
_driver->_interim_data.d5_cm = cb.msg->d180; |
|
|
|
|
_driver->_interim_data.d6_cm = cb.msg->d225; |
|
|
|
|
_driver->_interim_data.d7_cm = cb.msg->d270; |
|
|
|
|
_driver->_interim_data.d8_cm = cb.msg->d315; |
|
|
|
|
_driver->_last_distance_received_ms = AP_HAL::millis(); |
|
|
|
|
} |
|
|
|
|
/*
|
|
|
|
|
AP_Proximity_UAVCAN *driver = get_uavcan_backend(ap_uavcan,node_id); |
|
|
|
|
if (driver == nullptr) |
|
|
|
|
{ |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
driver->handle_proximity_data(cb); |
|
|
|
|
*/ |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void AP_Proximity_UAVCAN::handle_proximity_data(const ProximityCb &cb) |
|
|
|
@ -207,13 +264,20 @@ void AP_Proximity_UAVCAN::handle_proximity_data(const ProximityCb &cb)
@@ -207,13 +264,20 @@ void AP_Proximity_UAVCAN::handle_proximity_data(const ProximityCb &cb)
|
|
|
|
|
|
|
|
|
|
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) / 1000; |
|
|
|
|
_distance_valid[sector] = distance_cm != 0xffff; |
|
|
|
|
//_last_distance_received_ms = AP_HAL::millis();
|
|
|
|
|
// update boundary used for avoidance
|
|
|
|
|
update_boundary_for_sector(sector, true); |
|
|
|
|
// if(convert_angle_to_sector(angle_deg,sector)){
|
|
|
|
|
_angle[sector] = angle_deg; |
|
|
|
|
_distance[sector] = ((float)distance_cm) / 1000; |
|
|
|
|
// _distance_valid[sector] = distance_cm != 0xffff;
|
|
|
|
|
//_last_distance_received_ms = AP_HAL::millis();
|
|
|
|
|
// update boundary used for avoidance
|
|
|
|
|
|
|
|
|
|
_distance_valid[sector] = (_distance[sector] >= distance_min()) && (_distance[sector] <= distance_max()); |
|
|
|
|
|
|
|
|
|
update_boundary_for_sector(sector, true); |
|
|
|
|
// }
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
#endif |
|
|
|
|