diff --git a/src/lib/drivers/device/Device.hpp b/src/lib/drivers/device/Device.hpp index f519f9c145..689467f2ab 100644 --- a/src/lib/drivers/device/Device.hpp +++ b/src/lib/drivers/device/Device.hpp @@ -148,6 +148,7 @@ public: DeviceBusType_UAVCAN = 3, DeviceBusType_SIMULATION = 4, DeviceBusType_SERIAL = 5, + DeviceBusType_MAVLINK = 6, }; /* @@ -196,6 +197,9 @@ public: case DeviceBusType_SERIAL: return "SERIAL"; + case DeviceBusType_MAVLINK: + return "MAVLINK"; + case DeviceBusType_UNKNOWN: default: return "UNKNOWN"; diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 624906c253..4ff29619eb 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -643,7 +643,7 @@ MavlinkReceiver::handle_message_optical_flow_rad(mavlink_message_t *msg) distance_sensor_s d{}; device::Device::DeviceId device_id; - device_id.devid_s.bus = device::Device::DeviceBusType::DeviceBusType_SERIAL; + device_id.devid_s.bus = device::Device::DeviceBusType::DeviceBusType_MAVLINK; device_id.devid_s.devtype = DRV_DIST_DEVTYPE_MAVLINK; device_id.devid_s.address = msg->sysid; @@ -688,7 +688,7 @@ MavlinkReceiver::handle_message_hil_optical_flow(mavlink_message_t *msg) distance_sensor_s d{}; device::Device::DeviceId device_id; - device_id.devid_s.bus = device::Device::DeviceBusType::DeviceBusType_SERIAL; + device_id.devid_s.bus = device::Device::DeviceBusType::DeviceBusType_MAVLINK; device_id.devid_s.devtype = DRV_DIST_DEVTYPE_MAVLINK; device_id.devid_s.address = msg->sysid; @@ -742,7 +742,7 @@ MavlinkReceiver::handle_message_distance_sensor(mavlink_message_t *msg) distance_sensor_s ds{}; device::Device::DeviceId device_id; - device_id.devid_s.bus = device::Device::DeviceBusType::DeviceBusType_SERIAL; + device_id.devid_s.bus = device::Device::DeviceBusType::DeviceBusType_MAVLINK; device_id.devid_s.devtype = DRV_DIST_DEVTYPE_MAVLINK; device_id.devid_s.address = dist_sensor.id;