-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge pull request #1 from PickNikRobotics/subtree-sync
Subtree sync
- Loading branch information
Showing
60 changed files
with
4,035 additions
and
1,199 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,97 @@ | ||
<?xml version="1.0"?> | ||
|
||
<robot xmlns:xacro="http://ros.org/wiki/xacro"> | ||
|
||
<xacro:macro name="load_robot" params=" | ||
parent | ||
*origin | ||
prefix | ||
arm | ||
gripper | ||
gripper_joint_name | ||
dof | ||
vision | ||
robot_ip | ||
username | ||
password | ||
port | ||
port_realtime | ||
session_inactivity_timeout_ms | ||
connection_inactivity_timeout_ms | ||
use_internal_bus_gripper_comm:=false | ||
use_fake_hardware:=false | ||
fake_sensor_commands:=false | ||
sim_gazebo:=false | ||
sim_ignition:=false | ||
sim_isaac:=false | ||
isaac_joint_commands:=/isaac_joint_commands | ||
isaac_joint_states:=/isaac_joint_states | ||
use_external_cable:=false | ||
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)} | ||
gripper_max_velocity:=100.0 | ||
gripper_max_force:=100.0 | ||
gripper_com_port:=/dev/ttyUSB0 | ||
moveit_active:=false"> | ||
|
||
<!-- Include and load arm macro files --> | ||
<xacro:include filename="$(find kortex_description)/arms/${arm}/${dof}dof/urdf/${arm}_macro.xacro" /> | ||
|
||
<!-- Load the arm --> | ||
<xacro:load_arm | ||
parent="${parent}" | ||
dof="${dof}" | ||
vision="${vision}" | ||
robot_ip="${robot_ip}" | ||
username="${username}" | ||
password="${password}" | ||
port="${port}" | ||
port_realtime="${port_realtime}" | ||
session_inactivity_timeout_ms="${session_inactivity_timeout_ms}" | ||
connection_inactivity_timeout_ms="${connection_inactivity_timeout_ms}" | ||
prefix="${prefix}" | ||
use_internal_bus_gripper_comm="${use_internal_bus_gripper_comm}" | ||
use_fake_hardware="${use_fake_hardware}" | ||
fake_sensor_commands="${fake_sensor_commands}" | ||
sim_gazebo="${sim_gazebo}" | ||
sim_ignition="${sim_ignition}" | ||
sim_isaac="${sim_isaac}" | ||
gripper_joint_name="${gripper_joint_name}" | ||
gripper_max_velocity="${gripper_max_velocity}" | ||
gripper_max_force="${gripper_max_force}" | ||
use_external_cable="${use_external_cable}" | ||
initial_positions="${initial_positions}"> | ||
<xacro:insert_block name="origin" /> | ||
</xacro:load_arm> | ||
|
||
<!-- If no gripper, define tool frame here --> | ||
<xacro:if value="${not gripper}"> | ||
<link name="${prefix}tool_frame"/> | ||
<joint name="${prefix}tool_frame_joint" type="fixed"> | ||
<origin xyz="0 0 0" rpy="0 0 0" /> | ||
<parent link="${prefix}${last_arm_link}" /> | ||
<child link="${prefix}tool_frame" /> | ||
<axis xyz="0 0 0" /> | ||
</joint> | ||
</xacro:if> | ||
|
||
<!-- Include and load the gripper if defined --> | ||
<xacro:unless value="${not gripper}"> | ||
<xacro:include filename="$(find kinova_gen3_base_config)/description/robotiq_2f_85_macro.xacro" /> | ||
<!-- last_arm_link is defined in "$(find kortex_description)/arms/${arm}/urdf/${arm}_macro.xacro" --> | ||
<xacro:load_gripper | ||
parent="${prefix}${last_arm_link}" | ||
prefix="${prefix}" | ||
use_fake_hardware="${use_fake_hardware}" | ||
fake_sensor_commands="${fake_sensor_commands}" | ||
sim_ignition="${sim_ignition}" | ||
sim_isaac="${sim_isaac}" | ||
isaac_joint_commands="${isaac_joint_commands}" | ||
isaac_joint_states="${isaac_joint_states}" | ||
com_port="${gripper_com_port}" | ||
use_internal_bus_gripper_comm="${use_internal_bus_gripper_comm}" | ||
moveit_active="${moveit_active}"/> | ||
</xacro:unless> | ||
|
||
</xacro:macro> | ||
|
||
</robot> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
38 changes: 38 additions & 0 deletions
38
kinova_gen3_base_config/description/robotiq_2f_85_macro.xacro
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,38 @@ | ||
<?xml version="1.0"?> | ||
<robot name="robotiq_2f_85_model" xmlns:xacro="http://ros.org/wiki/xacro"> | ||
<xacro:macro name="load_gripper" params=" | ||
parent | ||
prefix | ||
use_fake_hardware:=false | ||
fake_sensor_commands:=false | ||
sim_ignition:=false | ||
sim_isaac:=false | ||
isaac_joint_commands:=/isaac_joint_commands | ||
isaac_joint_states:=/isaac_joint_states | ||
use_internal_bus_gripper_comm:=false | ||
com_port:=/dev/ttyUSB0 | ||
moveit_active:=false"> | ||
<xacro:include filename="$(find robotiq_description)/urdf/robotiq_2f_85_macro.urdf.xacro" /> | ||
|
||
<!-- Hardware talks directly to the gripper so we don't need ros2_control unless we are simulating --> | ||
<xacro:property name="include_ros2_control" value="false"/> | ||
<xacro:if value="${sim_ignition or sim_isaac or use_fake_hardware or not use_internal_bus_gripper_comm}"> | ||
<xacro:property name="include_ros2_control" value="true"/> | ||
</xacro:if> | ||
|
||
<xacro:robotiq_gripper | ||
name="RobotiqGripperHardwareInterface" | ||
prefix="${prefix}" | ||
parent="${parent}" | ||
include_ros2_control="${include_ros2_control}" | ||
com_port="${com_port}" | ||
use_fake_hardware="${use_fake_hardware}" | ||
mock_sensor_commands="${fake_sensor_commands}" | ||
sim_ignition="${sim_ignition}" | ||
sim_isaac="${sim_isaac}" | ||
isaac_joint_commands="${isaac_joint_commands}" | ||
isaac_joint_states="${isaac_joint_states}"> | ||
<origin xyz="0 0 0" rpy="0 0 0" /> | ||
</xacro:robotiq_gripper> | ||
</xacro:macro> | ||
</robot> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,5 +1,9 @@ | ||
<?xml version="1.0" encoding="UTF-8"?> | ||
<?xml version="1.0" encoding="UTF-8" ?> | ||
<launch> | ||
<include file="$(find-pkg-share moveit_studio_agent)/launch/studio_agent_bridge.launch.xml"/> | ||
<include file="$(find-pkg-share moveit_studio_rest_api)/launch/rest_api.launch.xml"/> | ||
<include | ||
file="$(find-pkg-share moveit_studio_agent)/launch/studio_agent_bridge.launch.xml" | ||
/> | ||
<include | ||
file="$(find-pkg-share moveit_studio_rest_api)/launch/rest_api.launch.xml" | ||
/> | ||
</launch> |
103 changes: 86 additions & 17 deletions
103
kinova_gen3_base_config/objectives/3_waypoint_pick_and_place.xml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,7 +1,10 @@ | ||
<?xml version="1.0"?> | ||
<root BTCPP_format="4" main_tree_to_execute="Clear Snapshot"> | ||
<!-- ////////// --> | ||
<BehaviorTree ID="Clear Snapshot" _description="Clear the point cloud snapshot"> | ||
<Action ID="ClearSnapshot" /> | ||
</BehaviorTree> | ||
<?xml version="1.0" ?> | ||
<root BTCPP_format="4" main_tree_to_execute="Clear Snapshot"> | ||
<!-- ////////// --> | ||
<BehaviorTree | ||
ID="Clear Snapshot" | ||
_description="Clear the point cloud snapshot" | ||
> | ||
<Action ID="ClearSnapshot" /> | ||
</BehaviorTree> | ||
</root> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,8 +1,12 @@ | ||
<?xml version="1.0"?> | ||
<?xml version="1.0" ?> | ||
<root BTCPP_format="4" main_tree_to_execute="Close Gripper"> | ||
<BehaviorTree ID="Close Gripper" _description="Close the gripper"> | ||
<Control ID="Sequence" name="root"> | ||
<Action ID="MoveGripperAction" gripper_command_action_name="/robotiq_gripper_controller/gripper_cmd" position="0.7929"/> | ||
</Control> | ||
</BehaviorTree> | ||
<BehaviorTree ID="Close Gripper" _description="Close the gripper"> | ||
<Control ID="Sequence" name="root"> | ||
<Action | ||
ID="MoveGripperAction" | ||
gripper_command_action_name="/robotiq_gripper_controller/gripper_cmd" | ||
position="0.7929" | ||
/> | ||
</Control> | ||
</BehaviorTree> | ||
</root> |
33 changes: 23 additions & 10 deletions
33
kinova_gen3_base_config/objectives/cycle_between_waypoints.xml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,11 +1,24 @@ | ||
<?xml version="1.0"?> | ||
<root BTCPP_format="4" main_tree_to_execute="Cycle Between Waypoints"> | ||
<BehaviorTree ID="Cycle Between Waypoints" _description="Cycles between two waypoints until failure"> | ||
<Decorator ID="KeepRunningUntilFailure"> | ||
<Control ID="Sequence"> | ||
<SubTree ID="Move to Waypoint" waypoint_name="Pick" joint_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" /> | ||
<SubTree ID="Move to Waypoint" waypoint_name="Place" joint_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" /> | ||
</Control> | ||
</Decorator> | ||
</BehaviorTree> | ||
<?xml version="1.0" ?> | ||
<root BTCPP_format="4" main_tree_to_execute="Cycle Between Waypoints"> | ||
<BehaviorTree | ||
ID="Cycle Between Waypoints" | ||
_description="Cycles between two waypoints until failure" | ||
> | ||
<Decorator ID="KeepRunningUntilFailure"> | ||
<Control ID="Sequence"> | ||
<SubTree | ||
ID="Move to Waypoint" | ||
waypoint_name="Pick" | ||
joint_group_name="manipulator" | ||
controller_names="/joint_trajectory_controller /robotiq_gripper_controller" | ||
/> | ||
<SubTree | ||
ID="Move to Waypoint" | ||
waypoint_name="Place" | ||
joint_group_name="manipulator" | ||
controller_names="/joint_trajectory_controller /robotiq_gripper_controller" | ||
/> | ||
</Control> | ||
</Decorator> | ||
</BehaviorTree> | ||
</root> |
35 changes: 25 additions & 10 deletions
35
kinova_gen3_base_config/objectives/get_imarker_pose_from_mesh_visualization.xml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,19 +1,34 @@ | ||
<?xml version='1.0' encoding='UTF-8'?> | ||
<root BTCPP_format="4" main_tree_to_execute="Get IMarker Pose From Mesh Visualization"> | ||
<?xml version="1.0" encoding="UTF-8" ?> | ||
<root | ||
BTCPP_format="4" | ||
main_tree_to_execute="Get IMarker Pose From Mesh Visualization" | ||
> | ||
<!--//////////--> | ||
<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"> | ||
<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" | ||
> | ||
<Control ID="Sequence" name="TopLevelSequence"> | ||
<Action ID="VisualizeMesh" marker_lifetime="0.0"/> | ||
<Action ID="AddPoseStampedToVector" input="{mesh_pose}"/> | ||
<Action ID="AdjustPoseWithIMarker" initial_poses="{pose_stamped_vector}" adjusted_poses="{adjusted_poses}" prompts="Adjust IMarker for Poses relative to the mesh"/> | ||
<Action ID="VisualizeMesh" marker_lifetime="0.0" /> | ||
<Action ID="AddPoseStampedToVector" input="{mesh_pose}" /> | ||
<Action | ||
ID="AdjustPoseWithIMarker" | ||
initial_poses="{pose_stamped_vector}" | ||
adjusted_poses="{adjusted_poses}" | ||
prompts="Adjust IMarker for Poses relative to the mesh" | ||
/> | ||
</Control> | ||
</BehaviorTree> | ||
<TreeNodesModel> | ||
<SubTree ID="Get IMarker Pose From Mesh Visualization"> | ||
<output_port name="adjusted_poses" default="{adjusted_poses}"/> | ||
<input_port name="mesh_path" default="{mesh_path}"/> | ||
<input_port name="mesh_pose" default="{mesh_pose}"/> | ||
<input_port name="_collapsed" default="false"/> | ||
<output_port name="adjusted_poses" default="{adjusted_poses}" /> | ||
<input_port name="mesh_path" default="{mesh_path}" /> | ||
<input_port name="mesh_pose" default="{mesh_pose}" /> | ||
<input_port name="_collapsed" default="false" /> | ||
<MetadataFields> | ||
<Metadata subcategory="User Input" /> | ||
</MetadataFields> | ||
</SubTree> | ||
</TreeNodesModel> | ||
</root> |
Oops, something went wrong.