wpb_home/wpb_home_tutorials/launch/lidar_demo.launch
2020-07-18 16:47:46 +08:00

32 lines
1.4 KiB
XML

<launch>
<arg name="model" default="$(find wpb_home_bringup)/urdf/wpb_home.urdf"/>
<arg name="gui" default="false" />
<arg name="rvizconfig" default="$(find wpb_home_bringup)/rviz/sensor.rviz" />
<param name="robot_description" command="$(find xacro)/xacro.py $(arg model)" />
<param name="use_gui" value="$(arg gui)"/>
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
<!--- Run Rplidar -->
<node name="rplidarNode" pkg="rplidar_ros" type="rplidarNode" output="screen">
<param name="serial_port" type="string" value="/dev/rplidar"/>
<param name="serial_baudrate" type="int" value="115200"/>
<param name="frame_id" type="string" value="laser"/>
<param name="inverted" type="bool" value="false"/>
<param name="angle_compensate" type="bool" value="true"/>
</node>
<!-- wpb_home core-->
<node pkg="wpb_home_bringup" type="wpb_home_core" name="wpb_home_core" output="screen">
<param name="serial_port" type="string" value="/dev/ftdi"/>
<rosparam file="$(find wpb_home_bringup)/config/wpb_home.yaml" command="load" />
</node>
<!-- wpb_home_lidar_obstacle-->
<node name="wpb_home_lidar_obstacle" pkg="wpb_home_tutorials" type="wpb_home_lidar_obstacle" output="screen"/>
</launch>