mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Compass: fixed uninitialised CAN device ID bits
This commit is contained in:
parent
2b80d57688
commit
c0733775bf
@ -100,24 +100,12 @@ bool AP_Compass_UAVCAN::register_uavcan_compass(uint8_t mgr, uint8_t node)
|
|||||||
if (ap_uavcan->register_mag_listener_to_node(this, node)) {
|
if (ap_uavcan->register_mag_listener_to_node(this, node)) {
|
||||||
_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;
|
mgr,
|
||||||
uint8_t bus: 5;
|
node,
|
||||||
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 = mgr;
|
|
||||||
d.devid_s.address = node;
|
|
||||||
d.devid_s.devtype = 1;
|
|
||||||
|
|
||||||
set_dev_id(_instance, d.devid);
|
|
||||||
set_external(_instance, true);
|
set_external(_instance, true);
|
||||||
|
|
||||||
_sum.zero();
|
_sum.zero();
|
||||||
|
Loading…
Reference in New Issue
Block a user