You can not select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
 
 

32 lines
1.3 KiB

<launch>
<arg name="urdf_file" value="$(find stretch_description)/urdf/stretch.urdf"/>
<arg name="controller_yaml_file" value="$(find stretch_core)/config/controller_calibration_head.yaml"/>
<arg name="calibration_directory" value="$(env HELLO_FLEET_PATH)/$(env HELLO_FLEET_ID)/calibration_ros/"/>
<!-- REALSENSE D435i -->
<include file="$(find stretch_core)/launch/d435i_low_resolution.launch" />
<node name="d435i_configure" pkg="stretch_core" type="d435i_configure" output="screen" >
<param name="initial_mode" type="string" value="High Accuracy"/>
</node>
<!-- -->
<!-- STRETCH DRIVER -->
<param name="/stretch_driver/broadcast_odom_tf" type="bool" value="true"/>
<param name="/stretch_driver/fail_out_of_range_goal" type="bool" value="false"/>
<include file="$(find stretch_core)/launch/stretch_driver.launch" pass_all_args="true"/>
<!-- -->
<!-- LASER RANGE FINDER -->
<include file="$(find stretch_core)/launch/rplidar.launch" />
<!-- -->
<!-- KEYBOARD TELEOP -->
<node name="keyboard_teleop" pkg="stretch_core" type="keyboard_teleop" output="screen" args=''/>
<!-- -->
<!-- VISUALIZE -->
<node name="rviz" pkg="rviz" type="rviz" output="screen" args="-d $(find stretch_core)/rviz/wheel_odometry_test.rviz" />
<!-- -->
</launch>