Rplidar C1 has different results in firmware Copter 4.5 and Copter 4.4

As mentioned, I purchased Rplidar C1 for multi-rotor obstacle avoidance function, using Pixhawk 6X flight control

I started with Copter4.4 firmware, and after following the documentation Settings, I found that the radar did not start properly, and MissionPlanner reported an error: PRX1: No Data. I was sure that the radar I was using was fine, because it worked properly when I connected it to the official application. When I use the official app to send the start command to make it work, and then connect to the flight control can read the data normally

Then I saw the Rplidar update for Copter 4.5 in Realease Note. In fact, after updating the firmware to 4.5-beta, flight control did start the radar normally, and I could feel a slight vibration when the radar was rotating. But at this point it seems that I can’t read and retrieve the data properly, and I can’t see any red lines in the Promixity UI of MissionPlanner,and errors such as Proximity 263 deg, 0.03m (want > 0.6m) are reported.
image

I tried to compare the two firmware codes on Github, but did not fully understand them. I felt that the code in the AP_Proximity_RPLidarA2.cpp file for reading data seemed to be the same logic, so it confused me, but I did not have the ability to solve this problem

Below are some of the parameters I used

  • SERIAL5_BAUD = 460800 (Because of C1 datasheet)
  • SERIAL5_PROTOCOL = 11 (Lidar360)
  • PRX1_TYPE = 5 (RPLidarA2)
  • BRD_SER5_RTSCTS = 0 (According to document)

That lidar is not officially supported. im surprised you got it working at all. but from what your saying it might just be a matter of initialising it for it to be compatible, so its probably something that can get fixed.
@Tomatila did you get anywhere with your c1?

1 Like

As @geofrancis says, we only support the RPLidars A2 and S1 so the C1 is not on the supported list. Each type of RPLidar sends a different startup string and sadly the AP driver was written in a way that makes it unable to handle these differences.

By the way, these RPLidar, in my experience, do not work outdoors in bright sunlight. If your usecase involves flying outdoors then it’s best not to waste time trying to get these sensors to work.

We also have this known issue related to the startup order of the autopilot and sensor.

Thank you for your reply

After reading the communication protocol documents of radar and the code of Copter 4.5, I found that the communication protocols of RPLidar A,S, and C series are basically the same, so it seems that the reason why radar can’t work before is just because the maximum and minimum distance are set to 0 when the recognition is UNKNOWN.

So I pulled the Copter 4.5 code and made some minor changes.

AS:
In AP_Proximity_RPLidarA2.h

enum class Model {
        UNKNOWN,
        A1,
        A2,
        S1,
        C1,//new add Model
    } model = Model::UNKNOWN;

In AP_Proximity_RPLidarA2.cpp

case Model::A1:
        return 0.2f;
case Model::C1://new add
case Model::A2:
case Model::S1:
        return 0.2f;
case Model::A1:
        return 8.0f;
case Model::C1: // new add
        return 10.0f;
case Model::A2:
        return 16.0f;

In AP_Proximity_RPLidarA2::parse_response_device_info():

 case 0x41:
 model=Model::C1;
 device_type="C1";
 break;

After recompiling the firmware, the radar worked properly and produced correct results

So it looks like we just need to write the identification parameters for each model based on the radar documentation (if necessary)

By the way, our aircraft does need to fly outdoors, but we have no experience before, so we purchased this radar, because the Ardupilot document mentions Rplidar A2. If you don’t mind, could you please provide us with the radar model with better performance, or the discussion post about the radar model?

Thank you

Can you do a GitHub - ArduPilot/ardupilot: ArduPlane, ArduCopter, ArduRover, ArduSub source pull-request with your code changes?

Hi @FoxSuzuran,

Thanks very much for that! As @amilcarlucas says we need a PR so I’ve created one here attributed to you with me as a co-author.

Are you happy to build this code a re-test just to be sure it works OK?

Thanks!

I would like to add it to the codebase, but this is my first exposure to the Ardupilot’s big PR process, what should I do next to help the update work properly

The only work I have done so far is to upload the new firmware to the physical flight control, which connects to the radar and sees the output in MissionPlanner

Glad to see further developments with RPlidar.

Can you please checkout the rmackay9:rplidar-c1 branch, compile it and test that it works?

@FoxSuzuran,

I can build a firmware for you for testing if you tell me which autopilot you’re using.

Thanks again for your help on this.

@FoxSuzuran,

Sorry to be pushy but I wonder if you could help us test? I’d like to get it merged at next week’s developer meeting (Tuesday morning Asia time).

Sorry for the lack of timely reply, I have compiled the firmware for the Pixhawk 6X and driven the radar, but since our new aircraft was not assembled until this evening, I cannot actually test its obstacle avoidance performance.
If all goes well, we should have usable results this weekend

1 Like

I’ve ordered one of these from Amazon and can test in 4/5 days after it arrives if needed

1 Like

@LuisVale,

OK, thanks very much! We might have merged this PR by then if other devs are happy but in any case, we eventually need to test it on real hardware.

From the actual results I think it is relatively accurate


YY@DW_3PB$_EKP{ZYUPAWD

1 Like

Hi FoxSuzuran,

Thank you very much for your assistance! I applied the same approach to a rover, but this time using a Pixhawk 2.4.8. I noticed something on the radar in Mission Planner, but the values were incorrect. I’ve just received a Pixhawk 6X, so I’ll test it and let you know whether it works.

Additionally, I have a small note regarding your code: According to the datasheet, the detection range for the RPLIDAR C1 with a white object is 0.05-12 meters, not 0.2-10 meters.

Thanks again!

@FoxSuzuran,

Thanks very much for the testing!

I also noticed what @potcha noticed that the maximum range on the datasheet is 12m while the driver change makes it 10m. I guess that was on purpose because in practice you’ve found that it can’t actually reliably report distances of 12m?

Thanks @potcha,

When you say the distances were incorrect you mean they were too long or too short? … or were they completely random? … I ask because I suspect what you’ve seen are environmental issues but sometimes it is clear from how the distances are incorrect.

In fact, I did not have a 12m test environment when I changed the code, so I used a relatively conservative value. As for the lower limit of 0.05m, I saw that it was always 0.2m in the code and thought it was a convention. After all, the lower limit of S1 in the manual is 0.1m.

1 Like

@FoxSuzuran,

OK, maybe I’ll change it to 12m then. Users can always make it shorter by changing the PRX_MAX value