sicklms200
SICK LMS 200 / PLS laser range-finder. More...
SICK LMS 200 / PLS laser range-finder.
The sicklms200 driver controls the SICK LMS 200 and PLS scanning laser range-finders.
- Note:
- LMS200 lasers may take several seconds to start up. You may want to set the 'alwayson' option for sicklms200 to '1' in your configuration file in order start the laser when player starts. Otherwise, your client may experience a timeout in trying to subscribe to this device.
- Compile-time dependencies
- none
- Provides
- Requires
- none
- Configuration requests
- PLAYER_LASER_REQ_GET_GEOM
- PLAYER_LASER_REQ_GET_CONFIG
- PLAYER_LASER_REQ_SET_CONFIG
- Configuration file options
- port (string)
- Default: "/dev/ttyS1"
- Serial port to which laser is attached. If you are using a USB/232 or USB/422 converter, this will be "/dev/ttyUSBx".
- connect_rate (integer tuple)
- Ordered list of rates to be tried when establishing connection with the laser.
- Default: [9600 38400 500000]
- Baud rate. Valid values are 9600, 38400 (RS232 or RS422) and 500000 (RS422 only).
- transfer_rate (integer)
- Rate desired for data transfers, negotiated after connection
- Default: 38400
- Baud rate. Valid values are 9600, 38400 (RS232 or RS422) and 500000 (RS422 only).
- serial_high_speed_mode (integer)
- Default: 0 (FTDI)
- Method to achieve high speed (RS422) communication 0: FTDI RS422 to USB, using Linux High Speed Serial 1: CP210x RS422 to USB (And maybe others). This chipset has the hardware remap some normal baudrate (230400 for example) to 500000, so the host machine doesn't need to know it's running at 500000 (Works on Mac OS X). 2: MOXA Multiport Serial Board CP-118EL (and probably other models) An ioctl call is used to set this card to 500000 baud
- serial_high_speed_baudremap (integer)
- Default: 38400 (Needed for FTDI)
- The fake baud rate to use after 500Kbps is achieved. In high_speed_mode 1, this is the baud rate that the hardware is remapping.
- retry (integer)
- Default: 0
- If the initial connection to the laser fails, retry this many times before giving up.
- delay (integer)
- Default: 0
- Delay (in seconds) before laser is initialized (set this to 32-35 if you have a newer generation Pioneer whose laser is switched on when the serial port is open).
- resolution (integer)
- Default: 50
- Angular resolution. Valid values are:
- resolution 50 : 0.5 degree increments, 361 readings @ 5Hz (38400) or 32Hz (500000).
- resolution 100 : 1 degree increments, 181 readings @ 10Hz (38400) or 75Hz (500000).
- range_res (integer)
- Default: 1
- Range resolution. Valid values are:
- range_res 1 : 1mm precision, 8.192m max range.
- range_res 10 : 10mm precision, 81.92m max range.
- range_res 100 : 100mm precision, 819.2m max range.
- invert (integer)
- Default: 0
- Is the laser physically inverted (i.e., upside-down)? Is so, scan data will be reversed accordingly.
- pose (length tuple)
- Default: [0.0 0.0 0.0]
- Pose (x,y,theta) of the laser, relative to its parent object (e.g., the robot to which the laser is attached).
- size (length tuple)
- Default: [0.15 0.15]
- Footprint (x,y) of the laser.
- pls_mode (integer)
- Default: 0
- set this to 1 to connect to a pls laser
- Example
#linux config driver ( name "sicklms200" provides [ "laser:0" ] port "/dev/ttyUSB0" resolution 50 serial_high_speed_mode 1 serial_high_speed_baudremap 230400 connect_rate [ 9600 500000 38400] transfer_rate 38400 retry 2 alwayson 1 ) # MAC config driver ( name "sicklms200" provides [ "laser:0" ] port "/dev/cu.SLAB_USBtoUART" resolution 50 serial_high_speed_mode 1 serial_high_speed_baudremap 230400 connect_rate [ 9600 500000 38400] transfer_rate 38400 retry 2 alwayson 1 ) #FTDI Config driver ( name "sicklms200" provides [ "laser:0" ] port "/dev/ttyUSB0" resolution 50 serial_high_speed_mode 0 connect_rate [ 9600 500000 38400] transfer_rate 38400 retry 2 alwayson 1 )