mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
AP_RangeFinder: use separate register_driver method while contructing CAN Driver
This commit is contained in:
parent
d27acbce2d
commit
cc4fc42ed0
@ -7,9 +7,10 @@
|
|||||||
constructor
|
constructor
|
||||||
*/
|
*/
|
||||||
AP_RangeFinder_USD1_CAN::AP_RangeFinder_USD1_CAN(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) :
|
AP_RangeFinder_USD1_CAN::AP_RangeFinder_USD1_CAN(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) :
|
||||||
CANSensor("USD1", AP_CANManager::Driver_Type_USD1),
|
CANSensor("USD1"),
|
||||||
AP_RangeFinder_Backend(_state, _params)
|
AP_RangeFinder_Backend(_state, _params)
|
||||||
{
|
{
|
||||||
|
register_driver(AP_CANManager::Driver_Type_USD1);
|
||||||
}
|
}
|
||||||
|
|
||||||
// update state
|
// update state
|
||||||
|
Loading…
Reference in New Issue
Block a user