Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_CANManager: use 32 bit timeout #28399

Merged
merged 3 commits into from
Nov 16, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion libraries/AP_CANManager/AP_CANDriver.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,5 +40,5 @@ class AP_CANDriver
virtual bool add_11bit_driver(CANSensor *sensor) { return false; }

// handler for outgoing frames for auxillary drivers
virtual bool write_aux_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us) { return false; }
virtual bool write_aux_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us) { return false; }
};
6 changes: 3 additions & 3 deletions libraries/AP_CANManager/AP_CANSensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -135,7 +135,7 @@ bool CANSensor::add_interface(AP_HAL::CANIface* can_iface)
return true;
}

bool CANSensor::write_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us)
bool CANSensor::write_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us)
{
if (!_initialized) {
debug_can(AP_CANManager::LOG_ERROR, "Driver not initialized for write_frame");
Expand Down Expand Up @@ -171,12 +171,12 @@ void CANSensor::loop()
#endif

while (true) {
uint64_t timeout = AP_HAL::micros64() + LOOP_INTERVAL_US;
uint64_t deadline_us = AP_HAL::micros64() + LOOP_INTERVAL_US;

// wait to receive frame
bool read_select = true;
bool write_select = false;
bool ret = _can_iface->select(read_select, write_select, nullptr, timeout);
bool ret = _can_iface->select(read_select, write_select, nullptr, deadline_us);
if (ret && read_select) {
uint64_t time;
AP_HAL::CANIface::CanIOFlags flags {};
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_CANManager/AP_CANSensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ class CANSensor : public AP_CANDriver {
virtual void handle_frame(AP_HAL::CANFrame &frame) = 0;

// handler for outgoing frames
bool write_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us);
bool write_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us);

#ifdef HAL_BUILD_AP_PERIPH
static void set_periph(const uint8_t i, const AP_CAN::Protocol protocol, AP_HAL::CANIface* iface) {
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_DroneCAN/AP_Canard_iface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -456,7 +456,7 @@ bool CanardInterface::add_11bit_driver(CANSensor *sensor)
}

// handler for outgoing frames for auxillary drivers
bool CanardInterface::write_aux_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us)
bool CanardInterface::write_aux_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us)
{
const uint64_t tx_deadline_us = AP_HAL::micros64() + timeout_us;
bool ret = false;
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_DroneCAN/AP_Canard_iface.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ class CanardInterface : public Canard::Interface {
bool add_11bit_driver(CANSensor *sensor);

// handler for outgoing frames for auxillary drivers
bool write_aux_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us);
bool write_aux_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us);

#if AP_TEST_DRONECAN_DRIVERS
static CanardInterface& get_test_iface() { return test_iface; }
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_DroneCAN/AP_DroneCAN.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1956,7 +1956,7 @@ bool AP_DroneCAN::add_11bit_driver(CANSensor *sensor)
}

// handler for outgoing frames for auxillary drivers
bool AP_DroneCAN::write_aux_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us)
bool AP_DroneCAN::write_aux_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us)
{
if (out_frame.isExtended()) {
// don't allow extended frames to be sent by auxillary driver
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_DroneCAN/AP_DroneCAN.h
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend {
bool add_11bit_driver(CANSensor *sensor) override;

// handler for outgoing frames for auxillary drivers
bool write_aux_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us) override;
bool write_aux_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us) override;

uint8_t get_driver_index() const { return _driver_index; }

Expand Down
Loading