21 lines
604 B
Plaintext
Raw Normal View History

2025-03-21 12:51:16 -07:00
<launch>
<include
file="$(find gazebo_ros)/launch/empty_world.launch" />
<node
name="tf_footprint_base"
pkg="tf"
type="static_transform_publisher"
args="0 0 0 0 0 0 base_link base_footprint 40" />
<node
name="spawn_model"
pkg="gazebo_ros"
type="spawn_model"
args="-file $(find SO_5DOF_ARM100_05d.SLDASM)/urdf/SO_5DOF_ARM100_05d.SLDASM.urdf -urdf -model SO_5DOF_ARM100_05d.SLDASM"
output="screen" />
<node
name="fake_joint_calibration"
pkg="rostopic"
type="rostopic"
args="pub /calibrated std_msgs/Bool true" />
2025-03-21 17:00:58 -07:00
</launch>