From: Alexis M. <mal...@cs...> - 2008-08-20 20:41:12
|
Hi *! I spent a good part of the day (and night) trying to get our Sick LMS200 laser to work. It was not easy, but I managed to get it running, and I would like share some of the details. Hopefully they will be helpful to someone else! My system: Laser: Sick LMS200 ( LMS200;301063;V02.05 ) Serial communication: a) RS232 (Using this card: Comtrol RocketPort Universal PCI 4J) b) RS-422 (USB-COMi-M converters using the FTDI chips). Linux Kernel: 2.6.24-1-amd64 SMP Player: SVN version from today (20th August 2008) Drivers: a) sicklms200 b) gbxsickacfr (using the gearbox library) Comments: - With the Comtrol RocketPort card, the RS232 communication does not work. The reason is that the kernel module from Comtrol does not support all the serial ioctls, and the player driver fails to set the correct parameters for the serial port. I did not try it with a regular RS232 (needed to make a new cable). - The driver from Gearbox does not work with the LMS200, and it is said on the Gearbox website that it is only tested with LMS-291, LMS-211. It only displays many errors like this one: RESP_INCORRECT_COMMAND(0x92). - The sicklms200 driver together with the USB-> RS-422 converters works, with the following details: - There are spurius segfaults when starting the driver, and I've tracked them down using Valgrind to the SickLMS200::ReadFromLaser() function after being called by GetLaserType() or by SetLaserMode(). It fails sometimes because it tries to read to a section of memory that is not addressable. I guess the size of the buffer is not being checked correctly when reading. Right now I don't have time to dig deeper, but maybe someone from the list can check it. - Communication at 500kbps worked, but the following change in the function SetLaserConfig() has to be made: // Wait for laser to return data //PLAYER_MSG0(2, "waiting for reply"); len = ReadFromLaser(packet, sizeof(packet), false, -1, -1); // This was 25000 and 5000 With the original values for the timeouts, the driver just timeouts many times during initialization, until it segfaults or gives up. This change was suggested by someone in this mailing list before (Thanks!) Here is my configuration file: driver ( name "sicklms200" provides [ "laser:0" ] port "/dev/ttyUSB0" resolution 50 serial_high_speed_mode 0 serial_high_speed_baudremap 38400 connect_rate [ 9600 500000 38400] transfer_rate 500000 retry 1 alwayson 1 ) - Communication at 38400bps (still using RS422) does not work, unless the call to SetLaserConfig is removed completely from the Setup() function, like this: // Configure the laser if (SetLaserRes(this->scan_width, this->scan_res)) return 1; //if (SetLaserConfig(this->intensity)) // return 1; This was also mentioned in this mailing list. I only add it here for completeness. And the configuration file: driver ( name "sicklms200" provides [ "laser:0" ] port "/dev/ttyUSB0" resolution 50 connect_rate [ 38400 9600 ] transfer_rate 38400 retry 5 alwayson 1 ) I don't know why the lower baudrate makes the call to SetLaserConfig fail. Could it be that sending intensity values is only supported at 500kbps? I tried resetting the Laser scanner and the USB converters before every test, to avoid problems from previous runs. If anyone has a similar system, I would love to hear if you have the same issues! Greetings, Alexis Maldonado Phd Student http://www9.cs.tum.edu/people/maldonad |