-
Notifications
You must be signed in to change notification settings - Fork 311
/
robot.launch
102 lines (89 loc) · 5.48 KB
/
robot.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
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
<?xml version="1.0"?>
<launch>
<!-- Gazebo & GUI Configuration -->
<arg name="gazebo" default="true" doc="Should the gazebo simulation be launched? Use false in case if you want to include this file and launch gazebo yourself" />
<arg name="headless" default="false" doc="Should the gazebo GUI be launched?" />
<arg name="paused" default="false" doc="Should the simulation directly be stopped at 0s?" />
<arg name="world" default="worlds/empty.world" doc="Filename to a SDF World for gazebo to use" />
<arg name="rviz" default="false" doc="Should RVIz be launched?" />
<!-- Robot Customization -->
<arg name="robot" doc="Which robot to spawn (one of {panda,fr3})" />
<arg name="arm_id" default="$(arg robot)" doc="Name of the robot to spawn" />
<arg name="use_gripper" default="true" doc="Should a franka hand be mounted on the flange?" />
<arg name="controller" default=" " doc="Which example controller should be started? (One of {cartesian_impedance,model,force,joint_position,joint_velocity}_example_controller)" />
<arg name="x" default="0" doc="How far forward to place the base of the robot in [m]?" />
<arg name="y" default="0" doc="How far leftwards to place the base of the robot in [m]?" />
<arg name="z" default="0" doc="How far upwards to place the base of the robot in [m]?" />
<arg name="roll" default="0" doc="How much to rotate the base of the robot around its X-axis in [rad]?" />
<arg name="pitch" default="0" doc="How much to rotate the base of the robot around its Y-axis in [rad]?" />
<arg name="yaw" default="0" doc="How much to rotate the base of the robot around its Z-axis in [rad]?" />
<arg name="xacro_args" default="" doc="Additional arguments to pass to panda.urdf.xacro" />
<arg name="initial_joint_positions"
doc="Initial joint configuration of the panda. Specify as a list of name/value pairs in form of '-J [name-of-joint] [value-in-rad]'. Default is a 90 degree bend in the elbow"
default="-J $(arg arm_id)_joint1 0
-J $(arg arm_id)_joint2 -0.785398163
-J $(arg arm_id)_joint3 0
-J $(arg arm_id)_joint4 -2.35619449
-J $(arg arm_id)_joint5 0
-J $(arg arm_id)_joint6 1.57079632679
-J $(arg arm_id)_joint7 0.785398163397
-J $(arg arm_id)_finger_joint1 0.001
-J $(arg arm_id)_finger_joint2 0.001"
/>
<arg name="interactive_marker" default="$(eval arg('controller') == 'cartesian_impedance_example_controller')" doc="Should the interactive marker node be started?" />
<include file="$(find gazebo_ros)/launch/empty_world.launch" if="$(arg gazebo)">
<arg name="world_name" value="$(arg world)"/>
<!-- Always start in paused mode, and only unpause when spawning the model -->
<arg name="paused" value="true"/>
<arg name="gui" value="$(eval not arg('headless'))"/>
<arg name="use_sim_time" value="true"/>
</include>
<param name="robot_description"
command="xacro $(find franka_description)/robots/$(arg robot)/$(arg robot).urdf.xacro
gazebo:=true
hand:=$(arg use_gripper)
arm_id:=$(arg arm_id)
xyz:='$(arg x) $(arg y) $(arg z)'
rpy:='$(arg roll) $(arg pitch) $(arg yaw)'
$(arg xacro_args)">
</param>
<rosparam file="$(find franka_gazebo)/config/franka_hw_sim.yaml" subst_value="true" />
<rosparam file="$(find franka_gazebo)/config/sim_controllers.yaml" subst_value="true" />
<param name="m_ee" value="0.76" if="$(arg use_gripper)" />
<arg name="unpause" value="$(eval '' if arg('paused') else '-unpause')" />
<node name="$(arg arm_id)_model_spawner"
pkg="gazebo_ros"
type="spawn_model"
args="-param robot_description -urdf -model $(arg arm_id) $(arg unpause)
$(arg initial_joint_positions)
"/>
<!-- Spawn required ROS controllers -->
<node pkg="controller_manager"
type="spawner"
name="$(arg arm_id)_gripper_spawner"
if="$(arg use_gripper)"
args="franka_gripper"
respawn="false"
/>
<!-- spawns the controller after the robot was put into its initial joint pose -->
<node pkg="controller_manager"
type="spawner"
name="$(arg arm_id)_controller_spawner"
respawn="false" output="screen"
args="--wait-for initialized franka_state_controller $(arg controller)"
/>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="joint_state_publisher" type="joint_state_publisher" pkg="joint_state_publisher">
<rosparam param="source_list">[franka_state_controller/joint_states, franka_gripper/joint_states] </rosparam>
<param name="rate" value="30"/>
</node>
<!-- Start only if cartesian_impedance_example_controller -->
<node name="interactive_marker"
pkg="franka_example_controllers"
type="interactive_marker.py"
if="$(arg interactive_marker)">
<param name="link_name" value="$(arg arm_id)_link0" />
<remap to="cartesian_impedance_example_controller/equilibrium_pose" from="equilibrium_pose" />
</node>
<node pkg="rviz" type="rviz" output="screen" name="rviz" args="-f $(arg arm_id)_link0 -d $(find franka_example_controllers)/launch/rviz/franka_description_with_marker.rviz --splash-screen $(find franka_visualization)/splash.png" if="$(arg rviz)"/>
</launch>