AP_Compass: fixed uninitialised CAN device ID bits

This commit is contained in:
Andrew Tridgell 2019-08-29 16:47:07 +10:00
parent 1dc57c84c4
commit bcb139f02f

View File

@ -98,24 +98,12 @@ void AP_Compass_UAVCAN::init()
{ {
_instance = register_compass(); _instance = register_compass();
struct DeviceStructure { uint32_t devid = AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_UAVCAN,
uint8_t bus_type : 3; _ap_uavcan->get_driver_index(),
uint8_t bus: 5; _node_id,
uint8_t address; 1); // the 1 is arbitrary
uint8_t devtype;
};
union DeviceId {
struct DeviceStructure devid_s;
uint32_t devid;
};
union DeviceId d;
d.devid_s.bus_type = 3; set_dev_id(_instance, devid);
d.devid_s.bus = _ap_uavcan->get_driver_index();
d.devid_s.address = _node_id;
d.devid_s.devtype = 1;
set_dev_id(_instance, d.devid);
set_external(_instance, true); set_external(_instance, true);
debug_mag_uavcan(2, _ap_uavcan->get_driver_index(), "AP_Compass_UAVCAN loaded\n\r"); debug_mag_uavcan(2, _ap_uavcan->get_driver_index(), "AP_Compass_UAVCAN loaded\n\r");