forked from agimus/agimus-demos-franka-manipulation
-
Notifications
You must be signed in to change notification settings - Fork 0
/
simulation.launch
73 lines (63 loc) · 2.83 KB
/
simulation.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
<?xml version="1.0"?>
<launch>
<!-- Gazebo & GUI Configuration -->
<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="rviz" default="false" doc="Should RVIz be launched?" />
<!-- Robot Customization -->
<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 panda2_joint1 0
-J panda2_joint2 -0.785398163
-J panda2_joint3 0
-J panda2_joint4 -2.35619449
-J panda2_joint5 0
-J panda2_joint6 1.57079632679
-J panda2_joint7 0.785398163397
-J panda2_finger_joint1 0.001
-J panda2_finger_joint2 0.001"
/>
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="worlds/empty.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"/>
<arg name="debug" value="false"/>
</include>
<param name="robot_description"
command="xacro $(find agimus_demos)/franka/manipulation/urdf/demo.urdf.xacro
gazebo:=true
hand:=true">
</param>
<include file="$(find agimus_demos)/launch/franka_manipulation_rosparam.launch">
<arg name="arm_id" value="panda2"/>
</include>
<param name="m_ee" value="0.76" />
<arg name="unpause" value="$(eval '' if arg('paused') else '-unpause')" />
<node name="panda2_model_spawner"
pkg="gazebo_ros"
type="spawn_model"
args="-param robot_description -urdf -model panda2 $(arg unpause)
$(arg initial_joint_positions)
"/>
<!-- Spawn required ROS controllers -->
<node pkg="controller_manager"
type="spawner"
name="panda2_gripper_spawner"
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="panda2_controller_spawner"
respawn="false" output="screen"
args="--wait-for initialized franka_state_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>
</launch>