Skip to content

Commit 8e3881a

Browse files
Claudio-ChiesMaEtUgRoystubdakejahl
authored
UAVCAN: fix and improve device_id logic (#26135)
* UAVCAN: extent SENS_GPS_PRIME usage to UAVCAN GNSS devices * use convenience function Co-authored-by: Matthias Grob <maetugr@gmail.com> * Update src/drivers/uavcan/sensors/gnss.cpp Co-authored-by: Øyvind Taksdal Stubhaug <o_github@oystub.com> * Apply suggestion from @MaEtUgR Co-authored-by: Matthias Grob <maetugr@gmail.com> * Fix type casting in GPS prime range check * UAVCAN: fix and improve device_id logic * Added bus information to more UAVCAN drivers * Fix device_id registration in UavcanBarometerBridge --------- Co-authored-by: Matthias Grob <maetugr@gmail.com> Co-authored-by: Øyvind Taksdal Stubhaug <o_github@oystub.com> Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com>
1 parent 3769434 commit 8e3881a

File tree

13 files changed

+75
-62
lines changed

13 files changed

+75
-62
lines changed

src/drivers/drv_sensor.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -184,6 +184,7 @@
184184
#define DRV_IMU_DEVTYPE_UAVCAN 0x87
185185
#define DRV_MAG_DEVTYPE_UAVCAN 0x88
186186
#define DRV_DIST_DEVTYPE_UAVCAN 0x89
187+
#define DRV_HYGRO_DEVTYPE_UAVCAN 0x8A
187188

188189
#define DRV_ADC_DEVTYPE_ADS1115 0x90
189190

src/drivers/uavcan/sensors/accel.cpp

Lines changed: 7 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,9 @@ const char *const UavcanAccelBridge::NAME = "accel";
4343
UavcanAccelBridge::UavcanAccelBridge(uavcan::INode &node, NodeInfoPublisher *node_info_publisher) :
4444
UavcanSensorBridgeBase("uavcan_accel", ORB_ID(sensor_accel), node_info_publisher),
4545
_sub_imu_data(node)
46-
{ }
46+
{
47+
set_device_type(DRV_ACC_DEVTYPE_UAVCAN);
48+
}
4749

4850
int UavcanAccelBridge::init()
4951
{
@@ -59,7 +61,7 @@ int UavcanAccelBridge::init()
5961

6062
void UavcanAccelBridge::imu_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::ahrs::RawIMU> &msg)
6163
{
62-
uavcan_bridge::Channel *channel = get_channel_for_node(msg.getSrcNodeID().get());
64+
uavcan_bridge::Channel *channel = get_channel_for_node(msg.getSrcNodeID().get(), msg.getIfaceIndex());
6365

6466
const hrt_abstime timestamp_sample = hrt_absolute_time();
6567

@@ -87,13 +89,10 @@ void UavcanAccelBridge::imu_sub_cb(const uavcan::ReceivedDataStructure<uavcan::e
8789

8890
int UavcanAccelBridge::init_driver(uavcan_bridge::Channel *channel)
8991
{
90-
// update device id as we now know our device node_id
91-
DeviceId device_id{_device_id};
92-
93-
device_id.devid_s.devtype = DRV_ACC_DEVTYPE_UAVCAN;
94-
device_id.devid_s.address = static_cast<uint8_t>(channel->node_id);
92+
// Build device ID using node_id and interface index
93+
uint32_t device_id = make_uavcan_device_id(static_cast<uint8_t>(channel->node_id), channel->iface_index);
9594

96-
channel->h_driver = new PX4Accelerometer(device_id.devid);
95+
channel->h_driver = new PX4Accelerometer(device_id);
9796

9897
if (channel->h_driver == nullptr) {
9998
return PX4_ERROR;

src/drivers/uavcan/sensors/baro.cpp

Lines changed: 7 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,9 @@ UavcanBarometerBridge::UavcanBarometerBridge(uavcan::INode &node, NodeInfoPublis
4949
UavcanSensorBridgeBase("uavcan_baro", ORB_ID(sensor_baro), node_info_publisher),
5050
_sub_air_pressure_data(node),
5151
_sub_air_temperature_data(node)
52-
{ }
52+
{
53+
set_device_type(DRV_BARO_DEVTYPE_UAVCAN);
54+
}
5355

5456
int UavcanBarometerBridge::init()
5557
{
@@ -91,7 +93,7 @@ void UavcanBarometerBridge::air_pressure_sub_cb(const
9193
{
9294
const hrt_abstime timestamp_sample = hrt_absolute_time();
9395

94-
uavcan_bridge::Channel *channel = get_channel_for_node(msg.getSrcNodeID().get());
96+
uavcan_bridge::Channel *channel = get_channel_for_node(msg.getSrcNodeID().get(), msg.getIfaceIndex());
9597

9698
if (channel == nullptr) {
9799
// Something went wrong - no channel to publish on; return
@@ -105,23 +107,18 @@ void UavcanBarometerBridge::air_pressure_sub_cb(const
105107
return;
106108
}
107109

108-
DeviceId device_id{};
109-
device_id.devid_s.bus = 0;
110-
device_id.devid_s.bus_type = DeviceBusType_UAVCAN;
111-
112-
device_id.devid_s.devtype = DRV_BARO_DEVTYPE_UAVCAN;
113-
device_id.devid_s.address = static_cast<uint8_t>(channel->node_id);
110+
uint32_t device_id = make_uavcan_device_id(msg);
114111

115112
// Register barometer capability with NodeInfoPublisher after first successful message
116113
if (_node_info_publisher != nullptr) {
117-
_node_info_publisher->registerDeviceCapability(msg.getSrcNodeID().get(), device_id.devid,
114+
_node_info_publisher->registerDeviceCapability(msg.getSrcNodeID().get(), device_id,
118115
NodeInfoPublisher::DeviceCapability::BAROMETER);
119116
}
120117

121118
// publish
122119
sensor_baro_s sensor_baro{};
123120
sensor_baro.timestamp_sample = timestamp_sample;
124-
sensor_baro.device_id = device_id.devid;
121+
sensor_baro.device_id = device_id;
125122
sensor_baro.pressure = msg.static_pressure;
126123

127124
if (PX4_ISFINITE(_last_temperature_kelvin) && (_last_temperature_kelvin >= 0.f)) {

src/drivers/uavcan/sensors/differential_pressure.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,7 @@ UavcanDifferentialPressureBridge::UavcanDifferentialPressureBridge(uavcan::INode
4949
UavcanSensorBridgeBase("uavcan_differential_pressure", ORB_ID(differential_pressure), node_info_publisher),
5050
_sub_air(node)
5151
{
52+
set_device_type(DRV_DIFF_PRESS_DEVTYPE_UAVCAN);
5253
}
5354

5455
int UavcanDifferentialPressureBridge::init()
@@ -68,8 +69,6 @@ void UavcanDifferentialPressureBridge::air_sub_cb(const
6869
{
6970
const hrt_abstime timestamp_sample = hrt_absolute_time();
7071

71-
_device_id.devid_s.devtype = DRV_DIFF_PRESS_DEVTYPE_UAVCAN;
72-
_device_id.devid_s.address = msg.getSrcNodeID().get() & 0xFF;
7372
float diff_press_pa = msg.differential_pressure;
7473
int32_t differential_press_rev = 0;
7574
param_get(param_find("SENS_DPRES_REV"), &differential_press_rev);
@@ -83,7 +82,7 @@ void UavcanDifferentialPressureBridge::air_sub_cb(const
8382

8483
differential_pressure_s report{};
8584
report.timestamp_sample = timestamp_sample;
86-
report.device_id = _device_id.devid;
85+
report.device_id = make_uavcan_device_id(msg);
8786
report.differential_pressure_pa = diff_press_pa;
8887
report.temperature = temperature_c;
8988
report.timestamp = hrt_absolute_time();

src/drivers/uavcan/sensors/flow.cpp

Lines changed: 2 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,7 @@ UavcanFlowBridge::UavcanFlowBridge(uavcan::INode &node, NodeInfoPublisher *node_
4141
UavcanSensorBridgeBase("uavcan_flow", ORB_ID(sensor_optical_flow), node_info_publisher),
4242
_sub_flow(node)
4343
{
44+
set_device_type(DRV_FLOW_DEVTYPE_UAVCAN);
4445
}
4546

4647
int
@@ -61,13 +62,7 @@ void UavcanFlowBridge::flow_sub_cb(const uavcan::ReceivedDataStructure<com::hex:
6162
sensor_optical_flow_s flow{};
6263
flow.timestamp_sample = hrt_absolute_time(); // TODO
6364

64-
device::Device::DeviceId device_id;
65-
device_id.devid_s.bus_type = device::Device::DeviceBusType::DeviceBusType_UAVCAN;
66-
device_id.devid_s.bus = 0;
67-
device_id.devid_s.devtype = DRV_FLOW_DEVTYPE_UAVCAN;
68-
device_id.devid_s.address = msg.getSrcNodeID().get() & 0xFF;
69-
70-
flow.device_id = device_id.devid;
65+
flow.device_id = make_uavcan_device_id(msg);
7166

7267
flow.pixel_flow[0] = msg.flow_integral[0];
7368
flow.pixel_flow[1] = msg.flow_integral[1];

src/drivers/uavcan/sensors/gnss.cpp

Lines changed: 1 addition & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -405,12 +405,7 @@ void UavcanGnssBridge::process_fixx(const uavcan::ReceivedDataStructure<FixType>
405405
{
406406
sensor_gps_s sensor_gps{};
407407

408-
device::Device::DeviceId device_id{};
409-
device_id.devid_s.devtype = get_device_type();
410-
device_id.devid_s.address = static_cast<uint8_t>(msg.getSrcNodeID().get());
411-
device_id.devid_s.bus_type = device::Device::DeviceBusType_UAVCAN;
412-
device_id.devid_s.bus = 0;
413-
sensor_gps.device_id = device_id.devid;
408+
sensor_gps.device_id = make_uavcan_device_id(msg);
414409

415410
// Register GPS capability with NodeInfoPublisher after first successful message
416411
if (_node_info_publisher != nullptr) {

src/drivers/uavcan/sensors/gnss_relative.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,7 @@ UavcanGnssRelativeBridge::UavcanGnssRelativeBridge(uavcan::INode &node, NodeInfo
4242
UavcanSensorBridgeBase("uavcan_gnss_relative", ORB_ID(sensor_gnss_relative), node_info_publisher),
4343
_sub_rel_pos_heading(node)
4444
{
45+
set_device_type(DRV_GPS_DEVTYPE_UAVCAN);
4546
}
4647

4748
int
@@ -70,7 +71,7 @@ void UavcanGnssRelativeBridge::rel_pos_heading_sub_cb(const
7071
sensor_gnss_relative.position_length = msg.relative_distance_m;
7172
sensor_gnss_relative.position[2] = msg.relative_down_pos_m;
7273

73-
sensor_gnss_relative.device_id = get_device_id();
74+
sensor_gnss_relative.device_id = make_uavcan_device_id(msg);
7475

7576
// Register GPS capability with NodeInfoPublisher after first successful message
7677
if (_node_info_publisher != nullptr) {

src/drivers/uavcan/sensors/gyro.cpp

Lines changed: 7 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,9 @@ const char *const UavcanGyroBridge::NAME = "gyro";
4343
UavcanGyroBridge::UavcanGyroBridge(uavcan::INode &node, NodeInfoPublisher *node_info_publisher) :
4444
UavcanSensorBridgeBase("uavcan_gyro", ORB_ID(sensor_gyro), node_info_publisher),
4545
_sub_imu_data(node)
46-
{ }
46+
{
47+
set_device_type(DRV_GYR_DEVTYPE_UAVCAN);
48+
}
4749

4850
int UavcanGyroBridge::init()
4951
{
@@ -59,7 +61,7 @@ int UavcanGyroBridge::init()
5961

6062
void UavcanGyroBridge::imu_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::ahrs::RawIMU> &msg)
6163
{
62-
uavcan_bridge::Channel *channel = get_channel_for_node(msg.getSrcNodeID().get());
64+
uavcan_bridge::Channel *channel = get_channel_for_node(msg.getSrcNodeID().get(), msg.getIfaceIndex());
6365

6466
if (channel == nullptr) {
6567
// Something went wrong - no channel to publish on; return
@@ -87,13 +89,10 @@ void UavcanGyroBridge::imu_sub_cb(const uavcan::ReceivedDataStructure<uavcan::eq
8789

8890
int UavcanGyroBridge::init_driver(uavcan_bridge::Channel *channel)
8991
{
90-
// update device id as we now know our device node_id
91-
DeviceId device_id{_device_id};
92-
93-
device_id.devid_s.devtype = DRV_GYR_DEVTYPE_UAVCAN;
94-
device_id.devid_s.address = static_cast<uint8_t>(channel->node_id);
92+
// Build device ID using node_id and interface index
93+
uint32_t device_id = make_uavcan_device_id(static_cast<uint8_t>(channel->node_id), channel->iface_index);
9594

96-
channel->h_driver = new PX4Gyroscope(device_id.devid);
95+
channel->h_driver = new PX4Gyroscope(device_id);
9796

9897
if (channel->h_driver == nullptr) {
9998
return PX4_ERROR;

src/drivers/uavcan/sensors/hygrometer.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,7 @@ UavcanHygrometerBridge::UavcanHygrometerBridge(uavcan::INode &node, NodeInfoPubl
4242
UavcanSensorBridgeBase("uavcan_hygrometer_sensor", ORB_ID(sensor_hygrometer), node_info_publisher),
4343
_sub_hygro(node)
4444
{
45+
set_device_type(DRV_HYGRO_DEVTYPE_UAVCAN);
4546
}
4647

4748
int UavcanHygrometerBridge::init()
@@ -64,7 +65,7 @@ void UavcanHygrometerBridge::hygro_sub_cb(const uavcan::ReceivedDataStructure<dr
6465

6566
sensor_hygrometer_s report{};
6667
report.timestamp_sample = timestamp_sample;
67-
report.device_id = 0; // TODO
68+
report.device_id = make_uavcan_device_id(msg);
6869
report.temperature = msg.temperature + atmosphere::kAbsoluteNullCelsius;
6970
report.humidity = msg.humidity;
7071
report.timestamp = hrt_absolute_time();

src/drivers/uavcan/sensors/mag.cpp

Lines changed: 6 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,7 @@ UavcanMagnetometerBridge::UavcanMagnetometerBridge(uavcan::INode &node, NodeInfo
4949
_sub_mag(node),
5050
_sub_mag2(node)
5151
{
52+
set_device_type(DRV_MAG_DEVTYPE_UAVCAN);
5253
}
5354

5455
int UavcanMagnetometerBridge::init()
@@ -73,7 +74,7 @@ int UavcanMagnetometerBridge::init()
7374
void UavcanMagnetometerBridge::mag_sub_cb(const
7475
uavcan::ReceivedDataStructure<uavcan::equipment::ahrs::MagneticFieldStrength> &msg)
7576
{
76-
uavcan_bridge::Channel *channel = get_channel_for_node(msg.getSrcNodeID().get());
77+
uavcan_bridge::Channel *channel = get_channel_for_node(msg.getSrcNodeID().get(), msg.getIfaceIndex());
7778

7879
if (channel == nullptr) {
7980
// Something went wrong - no channel to publish on; return
@@ -104,7 +105,7 @@ void
104105
UavcanMagnetometerBridge::mag2_sub_cb(const
105106
uavcan::ReceivedDataStructure<uavcan::equipment::ahrs::MagneticFieldStrength2> &msg)
106107
{
107-
uavcan_bridge::Channel *channel = get_channel_for_node(msg.getSrcNodeID().get());
108+
uavcan_bridge::Channel *channel = get_channel_for_node(msg.getSrcNodeID().get(), msg.getIfaceIndex());
108109

109110
if (channel == nullptr || channel->instance < 0) {
110111
// Something went wrong - no channel to publish on; return
@@ -134,13 +135,10 @@ UavcanMagnetometerBridge::mag2_sub_cb(const
134135

135136
int UavcanMagnetometerBridge::init_driver(uavcan_bridge::Channel *channel)
136137
{
137-
// update device id as we now know our device node_id
138-
DeviceId device_id{_device_id};
138+
// Build device ID using node_id and interface index
139+
uint32_t device_id = make_uavcan_device_id(static_cast<uint8_t>(channel->node_id), channel->iface_index);
139140

140-
device_id.devid_s.devtype = DRV_MAG_DEVTYPE_UAVCAN;
141-
device_id.devid_s.address = static_cast<uint8_t>(channel->node_id);
142-
143-
channel->h_driver = new PX4Magnetometer(device_id.devid, ROTATION_NONE);
141+
channel->h_driver = new PX4Magnetometer(device_id, ROTATION_NONE);
144142

145143
if (channel->h_driver == nullptr) {
146144
return PX4_ERROR;

0 commit comments

Comments
 (0)