AP_Proximity: add RPLidarC1 support

Co-authored-by: Randy Mackay <rmackay9@yahoo.com>
This commit is contained in:
FoxSuzuran 2024-03-11 19:04:15 +09:00 committed by Andrew Tridgell
parent 2319a125d5
commit c53f55fd05
2 changed files with 8 additions and 1 deletions

View File

@ -108,6 +108,8 @@ float AP_Proximity_RPLidarA2::distance_max() const
return 8.0f;
case Model::A2:
return 16.0f;
case Model::C1:
return 12.0f;
case Model::S1:
return 40.0f;
}
@ -121,8 +123,8 @@ float AP_Proximity_RPLidarA2::distance_min() const
case Model::UNKNOWN:
return 0.0f;
case Model::A1:
return 0.2f;
case Model::A2:
case Model::C1:
case Model::S1:
return 0.2f;
}
@ -334,6 +336,10 @@ void AP_Proximity_RPLidarA2::parse_response_device_info()
model = Model::A2;
device_type = "A2";
break;
case 0x41:
model=Model::C1;
device_type="C1";
break;
case 0x61:
model = Model::S1;
device_type = "S1";

View File

@ -151,6 +151,7 @@ private:
UNKNOWN,
A1,
A2,
C1,
S1,
} model = Model::UNKNOWN;