mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Rangefinder: adapt to new serial manager enum name
Lidar is now called Rangefinder
This commit is contained in:
parent
0340188a8f
commit
146143ff2e
@ -29,9 +29,9 @@ AP_RangeFinder_LeddarOne::AP_RangeFinder_LeddarOne(RangeFinder::RangeFinder_Stat
|
||||
uint8_t serial_instance) :
|
||||
AP_RangeFinder_Backend(_state)
|
||||
{
|
||||
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar, serial_instance);
|
||||
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
|
||||
if (uart != nullptr) {
|
||||
uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Lidar, serial_instance));
|
||||
uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance));
|
||||
}
|
||||
}
|
||||
|
||||
@ -42,7 +42,7 @@ AP_RangeFinder_LeddarOne::AP_RangeFinder_LeddarOne(RangeFinder::RangeFinder_Stat
|
||||
*/
|
||||
bool AP_RangeFinder_LeddarOne::detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
|
||||
{
|
||||
return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar, serial_instance) != nullptr;
|
||||
return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
|
||||
}
|
||||
|
||||
// read - return last value measured by sensor
|
||||
|
@ -30,9 +30,9 @@ AP_RangeFinder_LightWareSerial::AP_RangeFinder_LightWareSerial(RangeFinder::Rang
|
||||
uint8_t serial_instance) :
|
||||
AP_RangeFinder_Backend(_state)
|
||||
{
|
||||
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar, serial_instance);
|
||||
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
|
||||
if (uart != nullptr) {
|
||||
uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Lidar, serial_instance));
|
||||
uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance));
|
||||
}
|
||||
}
|
||||
|
||||
@ -43,7 +43,7 @@ AP_RangeFinder_LightWareSerial::AP_RangeFinder_LightWareSerial(RangeFinder::Rang
|
||||
*/
|
||||
bool AP_RangeFinder_LightWareSerial::detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
|
||||
{
|
||||
return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar, serial_instance) != nullptr;
|
||||
return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
|
||||
}
|
||||
|
||||
// read - return last value measured by sensor
|
||||
|
@ -34,9 +34,9 @@ AP_RangeFinder_MaxsonarSerialLV::AP_RangeFinder_MaxsonarSerialLV(RangeFinder::Ra
|
||||
uint8_t serial_instance) :
|
||||
AP_RangeFinder_Backend(_state)
|
||||
{
|
||||
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar, serial_instance);
|
||||
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
|
||||
if (uart != nullptr) {
|
||||
uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Lidar, serial_instance));
|
||||
uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance));
|
||||
}
|
||||
}
|
||||
|
||||
@ -47,7 +47,7 @@ AP_RangeFinder_MaxsonarSerialLV::AP_RangeFinder_MaxsonarSerialLV(RangeFinder::Ra
|
||||
*/
|
||||
bool AP_RangeFinder_MaxsonarSerialLV::detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
|
||||
{
|
||||
return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar, serial_instance) != nullptr;
|
||||
return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
|
||||
}
|
||||
|
||||
// read - return last value measured by sensor
|
||||
|
@ -37,7 +37,7 @@ AP_RangeFinder_uLanding::AP_RangeFinder_uLanding(RangeFinder::RangeFinder_State
|
||||
uint8_t serial_instance) :
|
||||
AP_RangeFinder_Backend(_state)
|
||||
{
|
||||
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar, serial_instance);
|
||||
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
|
||||
if (uart != nullptr) {
|
||||
uart->begin(ULANDING_BAUD, ULANDING_BUFSIZE_RX, ULANDING_BUFSIZE_TX);
|
||||
}
|
||||
@ -50,7 +50,7 @@ AP_RangeFinder_uLanding::AP_RangeFinder_uLanding(RangeFinder::RangeFinder_State
|
||||
*/
|
||||
bool AP_RangeFinder_uLanding::detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
|
||||
{
|
||||
return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar, serial_instance) != nullptr;
|
||||
return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user