mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Proximity: rename AP_UAVCAN to AP_DroneCAN
This commit is contained in:
parent
6bc060d8ab
commit
739fb91439
@ -19,7 +19,7 @@
|
|||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_CANManager/AP_CANManager.h>
|
#include <AP_CANManager/AP_CANManager.h>
|
||||||
#include <AP_UAVCAN/AP_UAVCAN.h>
|
#include <AP_DroneCAN/AP_DroneCAN.h>
|
||||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
|
|
||||||
@ -32,21 +32,21 @@ ObjectBuffer_TS<AP_Proximity_DroneCAN::ObstacleItem> AP_Proximity_DroneCAN::item
|
|||||||
|
|
||||||
|
|
||||||
//links the Proximity DroneCAN message to this backend
|
//links the Proximity DroneCAN message to this backend
|
||||||
void AP_Proximity_DroneCAN::subscribe_msgs(AP_UAVCAN* ap_uavcan)
|
void AP_Proximity_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
|
||||||
{
|
{
|
||||||
if (ap_uavcan == nullptr) {
|
if (ap_dronecan == nullptr) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_measurement, ap_uavcan->get_driver_index()) == nullptr) {
|
if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_measurement, ap_dronecan->get_driver_index()) == nullptr) {
|
||||||
AP_BoardConfig::allocation_error("measurement_sub");
|
AP_BoardConfig::allocation_error("measurement_sub");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
//Method to find the backend relating to the node id
|
//Method to find the backend relating to the node id
|
||||||
AP_Proximity_DroneCAN* AP_Proximity_DroneCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id, uint8_t address, bool create_new)
|
AP_Proximity_DroneCAN* AP_Proximity_DroneCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new)
|
||||||
{
|
{
|
||||||
if (ap_uavcan == nullptr) {
|
if (ap_dronecan == nullptr) {
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -64,7 +64,7 @@ AP_Proximity_DroneCAN* AP_Proximity_DroneCAN::get_uavcan_backend(AP_UAVCAN* ap_u
|
|||||||
}
|
}
|
||||||
//Double check if the driver was initialised as DroneCAN Type
|
//Double check if the driver was initialised as DroneCAN Type
|
||||||
if (driver != nullptr && (driver->_backend_type == AP_Proximity::Type::DroneCAN)) {
|
if (driver != nullptr && (driver->_backend_type == AP_Proximity::Type::DroneCAN)) {
|
||||||
if (driver->_ap_uavcan == ap_uavcan &&
|
if (driver->_ap_dronecan == ap_dronecan &&
|
||||||
driver->_node_id == node_id) {
|
driver->_node_id == node_id) {
|
||||||
return driver;
|
return driver;
|
||||||
} else {
|
} else {
|
||||||
@ -99,8 +99,8 @@ AP_Proximity_DroneCAN* AP_Proximity_DroneCAN::get_uavcan_backend(AP_UAVCAN* ap_u
|
|||||||
unsigned(i), unsigned(i));
|
unsigned(i), unsigned(i));
|
||||||
}
|
}
|
||||||
//Assign node id and respective dronecan driver, for identification
|
//Assign node id and respective dronecan driver, for identification
|
||||||
if (driver->_ap_uavcan == nullptr) {
|
if (driver->_ap_dronecan == nullptr) {
|
||||||
driver->_ap_uavcan = ap_uavcan;
|
driver->_ap_dronecan = ap_dronecan;
|
||||||
driver->_node_id = node_id;
|
driver->_node_id = node_id;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
@ -154,10 +154,10 @@ float AP_Proximity_DroneCAN::distance_min() const
|
|||||||
}
|
}
|
||||||
|
|
||||||
//Proximity message handler
|
//Proximity message handler
|
||||||
void AP_Proximity_DroneCAN::handle_measurement(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const ardupilot_equipment_proximity_sensor_Proximity &msg)
|
void AP_Proximity_DroneCAN::handle_measurement(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_equipment_proximity_sensor_Proximity &msg)
|
||||||
{
|
{
|
||||||
//fetch the matching DroneCAN driver, node id and sensor id backend instance
|
//fetch the matching DroneCAN driver, node id and sensor id backend instance
|
||||||
AP_Proximity_DroneCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id, msg.sensor_id, true);
|
AP_Proximity_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, msg.sensor_id, true);
|
||||||
if (driver == nullptr) {
|
if (driver == nullptr) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -2,7 +2,7 @@
|
|||||||
|
|
||||||
#include "AP_Proximity_Backend.h"
|
#include "AP_Proximity_Backend.h"
|
||||||
|
|
||||||
#include <AP_UAVCAN/AP_UAVCAN.h>
|
#include <AP_DroneCAN/AP_DroneCAN.h>
|
||||||
|
|
||||||
#ifndef AP_PROXIMITY_DRONECAN_ENABLED
|
#ifndef AP_PROXIMITY_DRONECAN_ENABLED
|
||||||
#define AP_PROXIMITY_DRONECAN_ENABLED (HAL_ENABLE_LIBUAVCAN_DRIVERS && HAL_PROXIMITY_ENABLED)
|
#define AP_PROXIMITY_DRONECAN_ENABLED (HAL_ENABLE_LIBUAVCAN_DRIVERS && HAL_PROXIMITY_ENABLED)
|
||||||
@ -24,18 +24,18 @@ public:
|
|||||||
float distance_min() const override;
|
float distance_min() const override;
|
||||||
|
|
||||||
|
|
||||||
static AP_Proximity_DroneCAN* get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id, uint8_t address, bool create_new);
|
static AP_Proximity_DroneCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new);
|
||||||
|
|
||||||
|
|
||||||
static void subscribe_msgs(AP_UAVCAN* ap_uavcan);
|
static void subscribe_msgs(AP_DroneCAN* ap_dronecan);
|
||||||
|
|
||||||
static void handle_measurement(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const ardupilot_equipment_proximity_sensor_Proximity &msg);
|
static void handle_measurement(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_equipment_proximity_sensor_Proximity &msg);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
uint32_t _last_update_ms; // system time of last message received
|
uint32_t _last_update_ms; // system time of last message received
|
||||||
|
|
||||||
AP_UAVCAN* _ap_uavcan;
|
AP_DroneCAN* _ap_dronecan;
|
||||||
uint8_t _node_id;
|
uint8_t _node_id;
|
||||||
|
|
||||||
struct ObstacleItem {
|
struct ObstacleItem {
|
||||||
|
Loading…
Reference in New Issue
Block a user