mirror of https://github.com/ArduPilot/ardupilot
AP_Proximity: move mutlican to AP_CANSensor
This commit is contained in:
parent
94fca60882
commit
8a24699bfa
|
@ -32,26 +32,14 @@ const AP_Param::GroupInfo AP_Proximity_MR72_CAN::var_info[] = {
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
MR72_MultiCAN *AP_Proximity_MR72_CAN::multican;
|
|
||||||
|
|
||||||
AP_Proximity_MR72_CAN::AP_Proximity_MR72_CAN(AP_Proximity &_frontend,
|
AP_Proximity_MR72_CAN::AP_Proximity_MR72_CAN(AP_Proximity &_frontend,
|
||||||
AP_Proximity::Proximity_State &_state,
|
AP_Proximity::Proximity_State &_state,
|
||||||
AP_Proximity_Params& _params):
|
AP_Proximity_Params& _params):
|
||||||
AP_Proximity_Backend(_frontend, _state, _params)
|
AP_Proximity_Backend(_frontend, _state, _params)
|
||||||
{
|
{
|
||||||
if (multican == nullptr) {
|
multican_MR72 = new MultiCAN{FUNCTOR_BIND_MEMBER(&AP_Proximity_MR72_CAN::handle_frame, bool, AP_HAL::CANFrame &), AP_CAN::Protocol::NanoRadar, "MR72 MultiCAN"};
|
||||||
multican = new MR72_MultiCAN();
|
if (multican_MR72 == nullptr) {
|
||||||
if (multican == nullptr) {
|
AP_BoardConfig::allocation_error("Failed to create proximity multican");
|
||||||
AP_BoardConfig::allocation_error("MR72_CAN");
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
{
|
|
||||||
// add to linked list of drivers
|
|
||||||
WITH_SEMAPHORE(multican->sem);
|
|
||||||
auto *prev = multican->drivers;
|
|
||||||
next = prev;
|
|
||||||
multican->drivers = this;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
|
@ -132,15 +120,4 @@ bool AP_Proximity_MR72_CAN::parse_distance_message(AP_HAL::CANFrame &frame)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
// handle frames from CANSensor, passing to the drivers
|
|
||||||
void MR72_MultiCAN::handle_frame(AP_HAL::CANFrame &frame)
|
|
||||||
{
|
|
||||||
WITH_SEMAPHORE(sem);
|
|
||||||
for (auto *d = drivers; d; d=d->next) {
|
|
||||||
if (d->handle_frame(frame)) {
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif // HAL_PROXIMITY_ENABLED
|
#endif // HAL_PROXIMITY_ENABLED
|
||||||
|
|
|
@ -45,24 +45,7 @@ private:
|
||||||
|
|
||||||
AP_Int32 receive_id; // ID of the sensor
|
AP_Int32 receive_id; // ID of the sensor
|
||||||
|
|
||||||
static MR72_MultiCAN *multican; // linked list
|
MultiCAN* multican_MR72; // Allows for multiple CAN rangefinders on a single bus
|
||||||
AP_Proximity_MR72_CAN *next;
|
|
||||||
};
|
|
||||||
|
|
||||||
// a class to allow for multiple MR_72 backends with one
|
|
||||||
// CANSensor driver
|
|
||||||
class MR72_MultiCAN : public CANSensor {
|
|
||||||
public:
|
|
||||||
MR72_MultiCAN() : CANSensor("MR72") {
|
|
||||||
register_driver(AP_CAN::Protocol::MR72);
|
|
||||||
}
|
|
||||||
|
|
||||||
// handler for incoming frames
|
|
||||||
void handle_frame(AP_HAL::CANFrame &frame) override;
|
|
||||||
|
|
||||||
HAL_Semaphore sem;
|
|
||||||
AP_Proximity_MR72_CAN *drivers;
|
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // HAL_PROXIMITY_ENABLED
|
#endif // HAL_PROXIMITY_ENABLED
|
||||||
|
|
Loading…
Reference in New Issue