Skip to content

Commit

Permalink
AP_HAL_ChibiOS/CAN*Iface: fix C++ One Definition Rule violations
Browse files Browse the repository at this point in the history
Switch to const extern hal reference, then cast const-ness away to
modify it and store the CAN driver reference during driver init.

This does just replace one undefined behavior with another, but the
latter is not warned about and is used in other parts of the code for
the same purpose.
  • Loading branch information
tpwrules committed Oct 29, 2023
1 parent b941cbb commit 0eceafc
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 4 deletions.
4 changes: 2 additions & 2 deletions libraries/AP_HAL_ChibiOS/CANFDIface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@
#error "Unsupported MCU for FDCAN"
#endif

extern AP_HAL::HAL& hal;
extern const AP_HAL::HAL& hal;

#define STR(x) #x
#define XSTR(x) STR(x)
Expand Down Expand Up @@ -568,7 +568,7 @@ bool CANIface::init(const uint32_t bitrate, const uint32_t fdbitrate, const Oper
if (can_ifaces[self_index_] == nullptr) {
can_ifaces[self_index_] = this;
#if !defined(HAL_BOOTLOADER_BUILD)
hal.can[self_index_] = this;
const_cast <AP_HAL::HAL&> (hal).can[self_index_] = this;
#endif
}

Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_HAL_ChibiOS/CanIface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@
#endif


extern AP_HAL::HAL& hal;
extern const AP_HAL::HAL& hal;

using namespace ChibiOS;

Expand Down Expand Up @@ -846,7 +846,7 @@ bool CANIface::init(const uint32_t bitrate, const CANIface::OperatingMode mode)
if (can_ifaces[self_index_] == nullptr) {
can_ifaces[self_index_] = this;
#if !defined(HAL_BOOTLOADER_BUILD)
hal.can[self_index_] = this;
const_cast <AP_HAL::HAL&> (hal).can[self_index_] = this;
#endif
}

Expand Down

0 comments on commit 0eceafc

Please sign in to comment.