-
Notifications
You must be signed in to change notification settings - Fork 13.6k
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
[Bug] Distance sensor LIDAR Lightware SF45 Serial not working on fmu-v6x #23308
Comments
If it is rotating when you start the driver, it's getting some data (but maybe not the right data). Can you show the printout on the mavlink console of Also what is |
With the LIDAR connected to TELEM3 and nothing connected to TELEM1, this is the printout of mavlink status:
I don't really know what data is being transmitted in instance #0 if nothing is connected to TELEM1 (/dev/ttyS6). The SER_TEL3_BAUD parameter does not appear in the QGC for me. But it seems that a default baudrate of 57600 is set to TEL3 in
Trying to use TELEM1 to connect the LIDAR, this is the mavlink status:
The previous instance of TELEM1 does not appear. |
Getting the mavlink status is just confirming that mavlink isn't running on the serial port you want to run the SF45 driver on. You will need to match the baud rate of 921600 on whichever telem port you use. 57600 won't work |
Changed the default baudrate of TELEM3 to 921600 in
And, also, included the line
in the initialization script file for standard plane airframe Such that the SER_TEL3_BAUD parameter appears in QGC with 921600:
But it is still not publishing in the distance_sensor topic. |
Can you print the driver status? I don't have a 6x to test on, but sounds like it's getting data but unsure if it's the right data. If it worked on a previous autopilot than I am really not sure where the issue could be other than the serial port you are using? |
@brunopedro1 you need a couple of settings preconfigured in lightware studio Connect to a computer over usb and set these settings using lightware studio The first one is scan on startup: Next is baudrate, which must be set to 921600: I don't have a regular 6x but I tested on the nxp version (6xrt) and was able to get it working over TELEM1 |
My configuration in Lightware Studio of the sensor already had the scan on startup and baudrate of 921600. I have now tried using the 1.14.2 PX4 release instead of 1.14.3 and, fortunately, the distance_sensor topic is aleady published (connected in TELEM3). However, there are errors in the measurements of current_distance:
Not all measurements present error, but most of them do. Using TELEM1 instead (after changing its baudrate to 921600) presents similar results, but the number of measurements with error seems to be lower. In this case, this is the driver status:
The errors in the measurements are not related to the distance of the sensor to any obstacles being lower than the minimum or higher than the maximum, because it is pointed to a reasonable area, in which the sensor gives accurate results in fmu-v3. |
At this point is probably necessary to attach to the nuttx console via the debug port on the 6x, since there isn't much else you can do through mavlink console on QGC for debugging. |
It looks like TELEM3 is on USART2 which has a baud rate of 57600 in the nuttx config, and dma disabled. Attaching to this port did not work out of the box (probably possible with some nuttx kconfig changes) TELEM2 worked out of the box for me without configuring anything other than enabling the sensor in the boardconfig and setting it to TELEM2 on the 6x. TELEM2 is on uart5, which has larger buffer sizes, 115200 baud, and dma enabled TEL2 is the default in the module yaml file since not all autopilots have 3 telem ports (6c mini for example) |
In the Pixhawk RPi CM4 Baseboard, TELEM2 is internally connected to the CM4 so I cannot use it for the LiDAR, unfortunately. I tried changing the USART2 nuttX config, increasing the transmit buffer size to 10000 and the baudrate to 115200 (or 912600), but it doesn't seem to make any difference. Also enabled DMA support for USART2 in the config, but it may require a few more steps, because the error "USART2 DMA map not defined (DMAMAP_USART2_RX)" appears when compiling. Despite this, I don't think DMA is the source of the issue, since there are also problems using TELEM1, which is on UART7 and has DMA enabled. Increasing transmit buffer size and baudrate of UART7 and connecting the LiDAR to TELEM1 didn’t make any difference either. This bug is very strange, since LIDAR works fine on other pixhawks. Everything points to a configuration problem specific to this board. I really appreciate your help so far in trying to resolve this issue. |
@brunopedro1 I wouldn't rule out the physical connection itself. As mentioned earlier if you get some data on TELEM3 but not valid distance data, your best bet is to use the debug port. There are debug messages that the SF45 driver prints out |
@dirksavage88
dmesg:
|
No, I haven't figured out what the issues are with specific uart ports. I did find that on a recent version of a 6x, TELEM3 did not work but TELEM 2 did. The OP mentions TELEM1 on the 6x also not working, but is DMA enabled. So likely not a DMA issue unless there is a flow control + DMA issue. For the px4 v5x it doesn't look like you have DMA on TELEM1:
I have seen CRC mismatch errors with long uart cable lengths, but usually I can at least get the start of packet correctly, and the driver starts and reports data with maybe a few CRC errors here and there (it throws out those packets in the driver). I don't have a v5x to test. Are all other UARTS giving the same issue? |
@Claudio-Chies I believe the issue is related to sending data to the sensor to get rangefinder measurements started. We get some data back but it's not a continuous stream, so the sensor stops sending data after that initial burst. I tried on TEL1, TEL2, & TEL3 and the only issue I had was with TEL3 where it fails to start on the intial try, but after rebooting the 6x it picks it up and reports distance data. I have attached a patch for the holybro 6x, you may need to modify it. It will now report comms errors if we have issues receiving and sending data. plus flush out any unread data after an error. |
@dirksavage88 I have tested your patch on TELEM3 of Holybro Pixhawk 6x and it successfully solved the issue of publishing a continuous flow of measurement data to the distance_sensor uORB topic. I agree that this issue may be closed with the merge of #23565. Thank you for your help! |
Describe the bug
The distance sensor LIDAR Lightware SF45 Serial is not publishing to the distance_sensor uORB topic on fmu-v6x using a Pixhawk 6X on the Pixhawk RPI CM4 Baseboard.
First, I started the driver in TELEM3 serial port (or configured the parameter SENS_EN_SF45_CFG to TELEM3):
The sensor starts rotating, as supposed, but no distance measurements are read or published in the distance_sensor uORB topic:
There is also a weird behaviour when I stop the driver and start it again in the same serial port:
(It works well on fmu-v3 using a Hex Cube Black Flight Controller)
To Reproduce
Expected behavior
The lightware_sf45_serial driver was expected to publish the measurements of the sensor in the distance_sensor uORB topic.
It works well on fmu-v3 using a Hex Cube Black Flight Controller.
Screenshot / Media
No response
Flight Log
/
Software Version
1.14.3
Flight controller
Pixhawk 6X on Pixhawk RPI CM4 Baseboard
Vehicle type
Plane
How are the different components wired up (including port information)
Pixhawk RPI CM4 Baseboard is powered through the PM03D Power Module with a 2S Li-Po Battery and connected to a computer (GCS) through USB-C cable.
LiDAR Lightware SF45 is powered throught 5V BEC of the PM03D and connected to TELEM3 serial power of the pixhawk (with common ground between TELEM3 port and power)
Additional context
No response
The text was updated successfully, but these errors were encountered: