diff --git a/src/sherpa/launch/pointcloud-vlp16.py b/src/sherpa/launch/pointcloud-vlp16.py index e0d5bea..1dc7e89 100755 --- a/src/sherpa/launch/pointcloud-vlp16.py +++ b/src/sherpa/launch/pointcloud-vlp16.py @@ -15,7 +15,7 @@ def generate_launch_description(): velodyne_raw = Node( package='velodyne_driver', executable='velodyne_driver_node', - arguments=["--ros-args", "-p", "model:=VLP16", "-p", "rpm:=600.0", "-p", "device_ip:=10.42.30.200"] + arguments=["--ros-args", "-p", "model:=VLP16", "-p", "rpm:=600.0", "-p", "device_ip:=10.42.200.201"] ) velodyne_pointcloud = Node( diff --git a/src/sherpa/package.xml b/src/sherpa/package.xml index 2f9d935..9820b4f 100644 --- a/src/sherpa/package.xml +++ b/src/sherpa/package.xml @@ -25,11 +25,8 @@ gazebo_msgs ros_gz_bridge - - velodyne_driver - velodyne_pointcloud - witmotion_ros - fast_lio + + sherpa_lidar_utils ament_cmake