-
Notifications
You must be signed in to change notification settings - Fork 320
/
j2s6s300_demo.launch
52 lines (40 loc) · 2.83 KB
/
j2s6s300_demo.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
<launch>
<param name="robot_type" value="j2s6s300" />
<param name="/pick_place_demo/arm/solve_type" value="Manipulation2" />
<param name="/pick_place_demo/arm/kinematics_solver_timeout" value="0.05" />
<!-- By default, we do not start a database (it can be large) -->
<arg name="db" default="false" />
<!-- Allow user to specify database location -->
<arg name="db_path" default="$(find j2s6s300_moveit_config)/default_warehouse_mongo_db" />
<!-- By default, we are not in debug mode -->
<arg name="debug" default="false" />
<!-- Load the URDF, SRDF and other .yaml configuration files on the param server -->
<include file="$(find j2s6s300_moveit_config)/launch/planning_context.launch">
<arg name="load_robot_description" value="true"/>
</include>
<!-- If needed, broadcast static tf for robot root -->
<!-- Run joint trajectory action server, which receives planned motion goal under "follow_joint_trajectory", and publish ROS standard trajectory via topic "command". Then for specified robot, the trajectory will be interpreted to their own joint trajectory controller -->
<node name="j2s6s300_joint_trajectory_action_server" pkg="kinova_driver" type="joint_trajectory_action_server" output="screen" respawn="false" args="j2s6s300"/>
<!-- Run gripper command action server, which receives planned motion goal under "gripper_command". After receiving the command from Moveit Rviz Plugin, this node act as an actionlib client and send the goal to the finger position action server from kinova_driver. -->
<node name="j2s6s300_gripper_command_action_server" pkg="kinova_driver" type="gripper_command_action_server" output="screen" respawn="false" args="j2s6s300"/>
<!-- Run the main MoveIt executable without trajectory execution (we do not have controllers configured by default) -->
<include file="$(find j2s6s300_moveit_config)/launch/move_group_j2s6s300.launch">
<arg name="allow_trajectory_execution" value="true"/>
<arg name="fake_execution" value="false"/>
<arg name="info" value="true"/>
<arg name="debug" value="$(arg debug)"/>
<arg name="joint_states_ns" value="/j2s6s300_driver/out/joint_state"/>
<arg name="controller_manager" value="j2s6s300"/>
</include>
<!-- kinova-driver Controller parameters-->
<rosparam file="$(find j2s6s300_moveit_config)/config/controllers.yaml"/>
<!-- Run Rviz and load the default config to see the state of the move_group node -->
<include file="$(find j2s6s300_moveit_config)/launch/moveit_rviz.launch">
<arg name="config" value="true"/>
<arg name="debug" value="$(arg debug)"/>
</include>
<!-- If database loading was enabled, start mongodb as well -->
<include file="$(find j2s6s300_moveit_config)/launch/default_warehouse_db.launch" if="$(arg db)">
<arg name="moveit_warehouse_database_path" value="$(arg db_path)"/>
</include>
</launch>