Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Proximity: add RPLidarC1 support #26484

Merged
merged 1 commit into from Mar 20, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
8 changes: 7 additions & 1 deletion libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp
Expand Up @@ -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;
}
Expand All @@ -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;
}
Expand Down Expand Up @@ -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";
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Proximity/AP_Proximity_RPLidarA2.h
Expand Up @@ -151,6 +151,7 @@ class AP_Proximity_RPLidarA2 : public AP_Proximity_Backend_Serial
UNKNOWN,
A1,
A2,
C1,
S1,
} model = Model::UNKNOWN;

Expand Down