Skip to content

Commit a7a2893

Browse files
committed
Squashed 'src/moveit_pro_kinova_configs/' changes from f8e71549..66c2e46c
66c2e46c Merge pull request #1 from PickNikRobotics/subtree-sync b3c8f59f Sync 6.5 to main (#37) 1fdeeda2 Sync V6.5 to main (#29) 61d5ed47 added dependency (#21) 171c0725 version bump b4d170cf formatting git-subtree-dir: src/moveit_pro_kinova_configs git-subtree-split: 66c2e46c6f13964470c5f22c6b8f4b9d2d4ff070
1 parent c4ba3a7 commit a7a2893

File tree

60 files changed

+4035
-1199
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

60 files changed

+4035
-1199
lines changed
Lines changed: 97 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,97 @@
1+
<?xml version="1.0"?>
2+
3+
<robot xmlns:xacro="http://ros.org/wiki/xacro">
4+
5+
<xacro:macro name="load_robot" params="
6+
parent
7+
*origin
8+
prefix
9+
arm
10+
gripper
11+
gripper_joint_name
12+
dof
13+
vision
14+
robot_ip
15+
username
16+
password
17+
port
18+
port_realtime
19+
session_inactivity_timeout_ms
20+
connection_inactivity_timeout_ms
21+
use_internal_bus_gripper_comm:=false
22+
use_fake_hardware:=false
23+
fake_sensor_commands:=false
24+
sim_gazebo:=false
25+
sim_ignition:=false
26+
sim_isaac:=false
27+
isaac_joint_commands:=/isaac_joint_commands
28+
isaac_joint_states:=/isaac_joint_states
29+
use_external_cable:=false
30+
initial_positions:=${dict(joint_1=0.0,joint_2=0.0,joint_3=0.0,joint_4=0.0,joint_5=0.0,joint_6=0.0,joint_7=0.0)}
31+
gripper_max_velocity:=100.0
32+
gripper_max_force:=100.0
33+
gripper_com_port:=/dev/ttyUSB0
34+
moveit_active:=false">
35+
36+
<!-- Include and load arm macro files -->
37+
<xacro:include filename="$(find kortex_description)/arms/${arm}/${dof}dof/urdf/${arm}_macro.xacro" />
38+
39+
<!-- Load the arm -->
40+
<xacro:load_arm
41+
parent="${parent}"
42+
dof="${dof}"
43+
vision="${vision}"
44+
robot_ip="${robot_ip}"
45+
username="${username}"
46+
password="${password}"
47+
port="${port}"
48+
port_realtime="${port_realtime}"
49+
session_inactivity_timeout_ms="${session_inactivity_timeout_ms}"
50+
connection_inactivity_timeout_ms="${connection_inactivity_timeout_ms}"
51+
prefix="${prefix}"
52+
use_internal_bus_gripper_comm="${use_internal_bus_gripper_comm}"
53+
use_fake_hardware="${use_fake_hardware}"
54+
fake_sensor_commands="${fake_sensor_commands}"
55+
sim_gazebo="${sim_gazebo}"
56+
sim_ignition="${sim_ignition}"
57+
sim_isaac="${sim_isaac}"
58+
gripper_joint_name="${gripper_joint_name}"
59+
gripper_max_velocity="${gripper_max_velocity}"
60+
gripper_max_force="${gripper_max_force}"
61+
use_external_cable="${use_external_cable}"
62+
initial_positions="${initial_positions}">
63+
<xacro:insert_block name="origin" />
64+
</xacro:load_arm>
65+
66+
<!-- If no gripper, define tool frame here -->
67+
<xacro:if value="${not gripper}">
68+
<link name="${prefix}tool_frame"/>
69+
<joint name="${prefix}tool_frame_joint" type="fixed">
70+
<origin xyz="0 0 0" rpy="0 0 0" />
71+
<parent link="${prefix}${last_arm_link}" />
72+
<child link="${prefix}tool_frame" />
73+
<axis xyz="0 0 0" />
74+
</joint>
75+
</xacro:if>
76+
77+
<!-- Include and load the gripper if defined -->
78+
<xacro:unless value="${not gripper}">
79+
<xacro:include filename="$(find kinova_gen3_base_config)/description/robotiq_2f_85_macro.xacro" />
80+
<!-- last_arm_link is defined in "$(find kortex_description)/arms/${arm}/urdf/${arm}_macro.xacro" -->
81+
<xacro:load_gripper
82+
parent="${prefix}${last_arm_link}"
83+
prefix="${prefix}"
84+
use_fake_hardware="${use_fake_hardware}"
85+
fake_sensor_commands="${fake_sensor_commands}"
86+
sim_ignition="${sim_ignition}"
87+
sim_isaac="${sim_isaac}"
88+
isaac_joint_commands="${isaac_joint_commands}"
89+
isaac_joint_states="${isaac_joint_states}"
90+
com_port="${gripper_com_port}"
91+
use_internal_bus_gripper_comm="${use_internal_bus_gripper_comm}"
92+
moveit_active="${moveit_active}"/>
93+
</xacro:unless>
94+
95+
</xacro:macro>
96+
97+
</robot>

kinova_gen3_base_config/description/picknik_kinova_gen3.xacro

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@
2626
<xacro:arg name="wrist_realsense" default="true" />
2727

2828
<!-- Import macros for main hardware components -->
29-
<xacro:include filename="$(find kortex_description)/robots/kortex_robot.xacro" />
29+
<xacro:include filename="$(find kinova_gen3_base_config)/description/kortex_robot.xacro" />
3030
<xacro:include filename="$(find picknik_accessories)/descriptions/sensors/realsense_d415.urdf.xacro"/>
3131

3232
<!-- Import environment macros -->
Lines changed: 38 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,38 @@
1+
<?xml version="1.0"?>
2+
<robot name="robotiq_2f_85_model" xmlns:xacro="http://ros.org/wiki/xacro">
3+
<xacro:macro name="load_gripper" params="
4+
parent
5+
prefix
6+
use_fake_hardware:=false
7+
fake_sensor_commands:=false
8+
sim_ignition:=false
9+
sim_isaac:=false
10+
isaac_joint_commands:=/isaac_joint_commands
11+
isaac_joint_states:=/isaac_joint_states
12+
use_internal_bus_gripper_comm:=false
13+
com_port:=/dev/ttyUSB0
14+
moveit_active:=false">
15+
<xacro:include filename="$(find robotiq_description)/urdf/robotiq_2f_85_macro.urdf.xacro" />
16+
17+
<!-- Hardware talks directly to the gripper so we don't need ros2_control unless we are simulating -->
18+
<xacro:property name="include_ros2_control" value="false"/>
19+
<xacro:if value="${sim_ignition or sim_isaac or use_fake_hardware or not use_internal_bus_gripper_comm}">
20+
<xacro:property name="include_ros2_control" value="true"/>
21+
</xacro:if>
22+
23+
<xacro:robotiq_gripper
24+
name="RobotiqGripperHardwareInterface"
25+
prefix="${prefix}"
26+
parent="${parent}"
27+
include_ros2_control="${include_ros2_control}"
28+
com_port="${com_port}"
29+
use_fake_hardware="${use_fake_hardware}"
30+
mock_sensor_commands="${fake_sensor_commands}"
31+
sim_ignition="${sim_ignition}"
32+
sim_isaac="${sim_isaac}"
33+
isaac_joint_commands="${isaac_joint_commands}"
34+
isaac_joint_states="${isaac_joint_states}">
35+
<origin xyz="0 0 0" rpy="0 0 0" />
36+
</xacro:robotiq_gripper>
37+
</xacro:macro>
38+
</robot>
Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,9 @@
1-
<?xml version="1.0" encoding="UTF-8"?>
1+
<?xml version="1.0" encoding="UTF-8" ?>
22
<launch>
3-
<include file="$(find-pkg-share moveit_studio_agent)/launch/studio_agent_bridge.launch.xml"/>
4-
<include file="$(find-pkg-share moveit_studio_rest_api)/launch/rest_api.launch.xml"/>
3+
<include
4+
file="$(find-pkg-share moveit_studio_agent)/launch/studio_agent_bridge.launch.xml"
5+
/>
6+
<include
7+
file="$(find-pkg-share moveit_studio_rest_api)/launch/rest_api.launch.xml"
8+
/>
59
</launch>

kinova_gen3_base_config/objectives/3_waypoint_pick_and_place.xml

Lines changed: 86 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -1,32 +1,101 @@
1-
<?xml version='1.0' encoding='UTF-8'?>
1+
<?xml version="1.0" encoding="UTF-8" ?>
22
<root BTCPP_format="4" main_tree_to_execute="3 Waypoints Pick and Place">
33
<!--//////////-->
4-
<BehaviorTree ID="3 Waypoints Pick and Place" _description="Repeatedly grab a small object, place it at desired destination, and then navigate to specified waypoint until failure" _favorite="true">
4+
<BehaviorTree
5+
ID="3 Waypoints Pick and Place"
6+
_description="Repeatedly grab a small object, place it at desired destination, and then navigate to specified waypoint until failure"
7+
_favorite="true"
8+
>
59
<Control ID="Sequence">
610
<!--Clear snapshot, move to center pose, and open gripper-->
7-
<Action ID="ClearSnapshot"/>
8-
<SubTree ID="Move to Waypoint" waypoint_name="Table" joint_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" />
9-
<Action ID="MoveGripperAction" gripper_command_action_name="/robotiq_gripper_controller/gripper_cmd" position="0"/>
11+
<Action ID="ClearSnapshot" />
12+
<SubTree
13+
ID="Move to Waypoint"
14+
waypoint_name="Table"
15+
joint_group_name="manipulator"
16+
controller_names="/joint_trajectory_controller /robotiq_gripper_controller"
17+
/>
18+
<Action
19+
ID="MoveGripperAction"
20+
gripper_command_action_name="/robotiq_gripper_controller/gripper_cmd"
21+
position="0"
22+
/>
1023
<!--Keep executing the pick and place sequence until failure-->
1124
<Decorator ID="KeepRunningUntilFailure">
1225
<Control ID="Sequence">
1326
<!--Pick object from "Pick", put it down at "Place", and go back to center pose-->
1427
<Control ID="Sequence">
15-
<SubTree ID="Move to Waypoint" waypoint_name="Pick" joint_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" />
16-
<Action ID="MoveGripperAction" gripper_command_action_name="/robotiq_gripper_controller/gripper_cmd" position="0.7929"/>
17-
<SubTree ID="Move to Waypoint" waypoint_name="Table" joint_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" />
18-
<SubTree ID="Move to Waypoint" waypoint_name="Place" joint_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" />
19-
<Action ID="MoveGripperAction" gripper_command_action_name="/robotiq_gripper_controller/gripper_cmd" position="0"/>
20-
<SubTree ID="Move to Waypoint" waypoint_name="Table" joint_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" />
28+
<SubTree
29+
ID="Move to Waypoint"
30+
waypoint_name="Pick"
31+
joint_group_name="manipulator"
32+
controller_names="/joint_trajectory_controller /robotiq_gripper_controller"
33+
/>
34+
<Action
35+
ID="MoveGripperAction"
36+
gripper_command_action_name="/robotiq_gripper_controller/gripper_cmd"
37+
position="0.7929"
38+
/>
39+
<SubTree
40+
ID="Move to Waypoint"
41+
waypoint_name="Table"
42+
joint_group_name="manipulator"
43+
controller_names="/joint_trajectory_controller /robotiq_gripper_controller"
44+
/>
45+
<SubTree
46+
ID="Move to Waypoint"
47+
waypoint_name="Place"
48+
joint_group_name="manipulator"
49+
controller_names="/joint_trajectory_controller /robotiq_gripper_controller"
50+
/>
51+
<Action
52+
ID="MoveGripperAction"
53+
gripper_command_action_name="/robotiq_gripper_controller/gripper_cmd"
54+
position="0"
55+
/>
56+
<SubTree
57+
ID="Move to Waypoint"
58+
waypoint_name="Table"
59+
joint_group_name="manipulator"
60+
controller_names="/joint_trajectory_controller /robotiq_gripper_controller"
61+
/>
2162
</Control>
2263
<!--Pick object from "Place", put it down at "Pick", and go back to center pose-->
2364
<Control ID="Sequence">
24-
<SubTree ID="Move to Waypoint" waypoint_name="Place" joint_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" />
25-
<Action ID="MoveGripperAction" gripper_command_action_name="/robotiq_gripper_controller/gripper_cmd" position="0.7929"/>
26-
<SubTree ID="Move to Waypoint" waypoint_name="Table" joint_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" />
27-
<SubTree ID="Move to Waypoint" waypoint_name="Pick" joint_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" />
28-
<Action ID="MoveGripperAction" gripper_command_action_name="/robotiq_gripper_controller/gripper_cmd" position="0"/>
29-
<SubTree ID="Move to Waypoint" waypoint_name="Table" joint_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" />
65+
<SubTree
66+
ID="Move to Waypoint"
67+
waypoint_name="Place"
68+
joint_group_name="manipulator"
69+
controller_names="/joint_trajectory_controller /robotiq_gripper_controller"
70+
/>
71+
<Action
72+
ID="MoveGripperAction"
73+
gripper_command_action_name="/robotiq_gripper_controller/gripper_cmd"
74+
position="0.7929"
75+
/>
76+
<SubTree
77+
ID="Move to Waypoint"
78+
waypoint_name="Table"
79+
joint_group_name="manipulator"
80+
controller_names="/joint_trajectory_controller /robotiq_gripper_controller"
81+
/>
82+
<SubTree
83+
ID="Move to Waypoint"
84+
waypoint_name="Pick"
85+
joint_group_name="manipulator"
86+
controller_names="/joint_trajectory_controller /robotiq_gripper_controller"
87+
/>
88+
<Action
89+
ID="MoveGripperAction"
90+
gripper_command_action_name="/robotiq_gripper_controller/gripper_cmd"
91+
position="0"
92+
/>
93+
<SubTree
94+
ID="Move to Waypoint"
95+
waypoint_name="Table"
96+
joint_group_name="manipulator"
97+
controller_names="/joint_trajectory_controller /robotiq_gripper_controller"
98+
/>
3099
</Control>
31100
</Control>
32101
</Decorator>
Lines changed: 9 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,10 @@
1-
<?xml version="1.0"?>
2-
<root BTCPP_format="4" main_tree_to_execute="Clear Snapshot">
3-
<!-- ////////// -->
4-
<BehaviorTree ID="Clear Snapshot" _description="Clear the point cloud snapshot">
5-
<Action ID="ClearSnapshot" />
6-
</BehaviorTree>
1+
<?xml version="1.0" ?>
2+
<root BTCPP_format="4" main_tree_to_execute="Clear Snapshot">
3+
<!-- ////////// -->
4+
<BehaviorTree
5+
ID="Clear Snapshot"
6+
_description="Clear the point cloud snapshot"
7+
>
8+
<Action ID="ClearSnapshot" />
9+
</BehaviorTree>
710
</root>
Lines changed: 10 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,12 @@
1-
<?xml version="1.0"?>
1+
<?xml version="1.0" ?>
22
<root BTCPP_format="4" main_tree_to_execute="Close Gripper">
3-
<BehaviorTree ID="Close Gripper" _description="Close the gripper">
4-
<Control ID="Sequence" name="root">
5-
<Action ID="MoveGripperAction" gripper_command_action_name="/robotiq_gripper_controller/gripper_cmd" position="0.7929"/>
6-
</Control>
7-
</BehaviorTree>
3+
<BehaviorTree ID="Close Gripper" _description="Close the gripper">
4+
<Control ID="Sequence" name="root">
5+
<Action
6+
ID="MoveGripperAction"
7+
gripper_command_action_name="/robotiq_gripper_controller/gripper_cmd"
8+
position="0.7929"
9+
/>
10+
</Control>
11+
</BehaviorTree>
812
</root>
Lines changed: 23 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -1,11 +1,24 @@
1-
<?xml version="1.0"?>
2-
<root BTCPP_format="4" main_tree_to_execute="Cycle Between Waypoints">
3-
<BehaviorTree ID="Cycle Between Waypoints" _description="Cycles between two waypoints until failure">
4-
<Decorator ID="KeepRunningUntilFailure">
5-
<Control ID="Sequence">
6-
<SubTree ID="Move to Waypoint" waypoint_name="Pick" joint_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" />
7-
<SubTree ID="Move to Waypoint" waypoint_name="Place" joint_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" />
8-
</Control>
9-
</Decorator>
10-
</BehaviorTree>
1+
<?xml version="1.0" ?>
2+
<root BTCPP_format="4" main_tree_to_execute="Cycle Between Waypoints">
3+
<BehaviorTree
4+
ID="Cycle Between Waypoints"
5+
_description="Cycles between two waypoints until failure"
6+
>
7+
<Decorator ID="KeepRunningUntilFailure">
8+
<Control ID="Sequence">
9+
<SubTree
10+
ID="Move to Waypoint"
11+
waypoint_name="Pick"
12+
joint_group_name="manipulator"
13+
controller_names="/joint_trajectory_controller /robotiq_gripper_controller"
14+
/>
15+
<SubTree
16+
ID="Move to Waypoint"
17+
waypoint_name="Place"
18+
joint_group_name="manipulator"
19+
controller_names="/joint_trajectory_controller /robotiq_gripper_controller"
20+
/>
21+
</Control>
22+
</Decorator>
23+
</BehaviorTree>
1124
</root>
Lines changed: 25 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -1,19 +1,34 @@
1-
<?xml version='1.0' encoding='UTF-8'?>
2-
<root BTCPP_format="4" main_tree_to_execute="Get IMarker Pose From Mesh Visualization">
1+
<?xml version="1.0" encoding="UTF-8" ?>
2+
<root
3+
BTCPP_format="4"
4+
main_tree_to_execute="Get IMarker Pose From Mesh Visualization"
5+
>
36
<!--//////////-->
4-
<BehaviorTree ID="Get IMarker Pose From Mesh Visualization" _description="Visualize a mesh in the UI and use an IMarker to get a grasp pose based on that mesh" _favorite="false">
7+
<BehaviorTree
8+
ID="Get IMarker Pose From Mesh Visualization"
9+
_description="Visualize a mesh in the UI and use an IMarker to get a grasp pose based on that mesh"
10+
_favorite="false"
11+
>
512
<Control ID="Sequence" name="TopLevelSequence">
6-
<Action ID="VisualizeMesh" marker_lifetime="0.0"/>
7-
<Action ID="AddPoseStampedToVector" input="{mesh_pose}"/>
8-
<Action ID="AdjustPoseWithIMarker" initial_poses="{pose_stamped_vector}" adjusted_poses="{adjusted_poses}" prompts="Adjust IMarker for Poses relative to the mesh"/>
13+
<Action ID="VisualizeMesh" marker_lifetime="0.0" />
14+
<Action ID="AddPoseStampedToVector" input="{mesh_pose}" />
15+
<Action
16+
ID="AdjustPoseWithIMarker"
17+
initial_poses="{pose_stamped_vector}"
18+
adjusted_poses="{adjusted_poses}"
19+
prompts="Adjust IMarker for Poses relative to the mesh"
20+
/>
921
</Control>
1022
</BehaviorTree>
1123
<TreeNodesModel>
1224
<SubTree ID="Get IMarker Pose From Mesh Visualization">
13-
<output_port name="adjusted_poses" default="{adjusted_poses}"/>
14-
<input_port name="mesh_path" default="{mesh_path}"/>
15-
<input_port name="mesh_pose" default="{mesh_pose}"/>
16-
<input_port name="_collapsed" default="false"/>
25+
<output_port name="adjusted_poses" default="{adjusted_poses}" />
26+
<input_port name="mesh_path" default="{mesh_path}" />
27+
<input_port name="mesh_pose" default="{mesh_pose}" />
28+
<input_port name="_collapsed" default="false" />
29+
<MetadataFields>
30+
<Metadata subcategory="User Input" />
31+
</MetadataFields>
1732
</SubTree>
1833
</TreeNodesModel>
1934
</root>

0 commit comments

Comments
 (0)