<> <> == Supported hardware == === model name : LSC Series === ~+'''web site :''' [[https://www.autonics.com/series/3001018|Autonics.com]]+~ {{attachment:LSC-C_image.png|LSC-C_Series|width=50%,height=50%}} ~+'''Features :'''+~ *Environment of use : indoor * Scanning frequency : 15Hz * Angular resolution : 0.33º * Aparture angle : 270º * Detection distance range * LSC-C5CT3 : 0.05m ~ 5m * LSC-C10CT3 : 0.05m ~ 10m * LSC-C25CT3 : 0.05m ~ 25m == ROS API == {{{ #!clearsilver CS/NodeAPI node.0 { name=lsc_ros_driver desc=lsc_ros_driver is ROS1 driver package for LSC Series of Autonics. It converts scan data from device to LaserScan topic message and publishes. pub{ 0.name= scan 0.type= sensor_msgs/LaserScan 0.desc= Scan data from the device. 1.name= diagnostics 1.type= diagnostic_msgs/DiagnosticStatus 1.desc= Scan topic status. } srv{ 0.name=self_test 0.type= diagnostic_msgs/SelfTest 0.desc= check communication connection } param { group.0 { 0.name= addr 0.default=192.168.0.1 0.type= string 0.desc= The device ip address 1.name= port 1.default=8000 1.type= string 1.desc= The port number of device 2.name= frame_id 2.default= `laser` 2.type= string 2.desc= The frame name of scan data 3.name= range_min 3.default=0.05 3.type= double 3.desc=Minimum range value [m] 4.name= range_max 4.default=25.0 4.type= double 4.desc= Maximum range value [m] 5.name= password 5.default=`0000` 5.type= string 5.desc= Password to login LSC } } }}} == Installation == === from source === {{{ #!bin/sh source /opt/ros/$ROS_DISTRO/setup.bash mkdir -p ~/catkin_ws/src/ cd ~/catkin_ws/src/ git clone https://github.com/AutonicsLiDAR/lsc_ros_driver.git cd ~/catkin_ws catkin_make source ~/catkin_ws/devel/setup.bash }}} === from binary === {{{ #!bin/sh sudo apt install ros-$ROS_DISTRO-lsc-ros-driver }}} == Start == {{{ #!bin/sh roslaunch lsc_ros_driver lsc_c25_launch.launch }}}