-
Notifications
You must be signed in to change notification settings - Fork 0
/
ur10_upload.launch
26 lines (19 loc) · 1.24 KB
/
ur10_upload.launch
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
<?xml version="1.0"?>
<launch>
<arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface" />
<param name="robot_description" command="$(find xacro)/xacro '$(find agimus_demos)/ur10/pointing/urdf/robot.urdf.xacro' transmission_hw_interface:=$(arg transmission_hw_interface) gazebo:=true" />
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher">
<param name="publish_frequency" type="double" value="50.0" />
<param name="tf_prefix" type="string" value="" />
</node>
<!-- Fake Calibration -->
<node pkg="rostopic" type="rostopic" name="fake_joint_calibration"
args="pub /calibrated std_msgs/Bool true" />
<!-- joint_state_controller -->
<rosparam file="$(find ur_gazebo)/config/ur10e_controllers.yaml" command="load"/>
<node name="joint_state_controller_spawner" pkg="controller_manager" type="controller_manager" args="spawn joint_state_controller" respawn="false" output="screen"/>
<!-- Publish pose of end-effector in topic /pose -->
<node name="publishwmc" pkg="agimus_demos" type="publishwmc.py"/>
<!-- Publish extrinsics parameters of camera -->
<node name="publish_camera_extrinsics" pkg="agimus_demos" type="publish_camera_extrinsics.py"/>
</launch>