AP_Proximity: add support for RPLidarA1

This commit is contained in:
Peter Barker 2021-02-05 12:30:38 +11:00 committed by Randy Mackay
parent ae6b1ffc8f
commit 3355520026
2 changed files with 8 additions and 0 deletions

View File

@ -106,6 +106,8 @@ float AP_Proximity_RPLidarA2::distance_max() const
switch (model) { switch (model) {
case Model::UNKNOWN: case Model::UNKNOWN:
return 0.0f; return 0.0f;
case Model::A1:
return 8.0f;
case Model::A2: case Model::A2:
return 16.0f; return 16.0f;
} }
@ -118,6 +120,8 @@ float AP_Proximity_RPLidarA2::distance_min() const
switch (model) { switch (model) {
case Model::UNKNOWN: case Model::UNKNOWN:
return 0.0f; return 0.0f;
case Model::A1:
return 0.2f;
case Model::A2: case Model::A2:
return 0.2f; return 0.2f;
} }
@ -316,6 +320,9 @@ void AP_Proximity_RPLidarA2::parse_response_device_info()
{ {
Debug(1, "Received DEVICE_INFO"); Debug(1, "Received DEVICE_INFO");
switch (_payload.device_info.model) { switch (_payload.device_info.model) {
case 0x18:
model = Model::A1;
break;
case 0x28: case 0x28:
model = Model::A2; model = Model::A2;
break; break;

View File

@ -136,6 +136,7 @@ private:
enum class Model { enum class Model {
UNKNOWN, UNKNOWN,
A1,
A2, A2,
} model = Model::UNKNOWN; } model = Model::UNKNOWN;