Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
24 commits
Select commit Hold shift + click to select a range
d025f61
update robotstateupdater to be compatible with ros2
tkallies Jul 31, 2025
08dc311
Merge branch 'cram2:dev' into dev
tkallies Aug 10, 2025
21dcba4
update giskard interface and object state updater tests
tkallies Aug 10, 2025
c0cd6ca
Merge branch 'cram2:dev' into dev
tkallies Aug 18, 2025
91a79e1
small fix to giskard.py
tkallies Aug 20, 2025
20397f5
Merge branch 'dev' into dev
tkallies Aug 21, 2025
88230c7
small fix to giskard.py
tkallies Aug 21, 2025
607d359
allow all collisions
tkallies Aug 27, 2025
abb9513
fixed an error where giskard wouldnt have goal positions set + a smal…
tkallies Aug 28, 2025
91cd990
add DefaultMoveGripperReal implementation
tkallies Aug 29, 2025
74a6b7b
add set_straight_cart_goal
tkallies Aug 29, 2025
c9dde99
update spawn_urdf so that giskard gets the right type of posestamped
tkallies Sep 9, 2025
87af679
added spawn_box and adjustment to the execute wrapper
tkallies Sep 11, 2025
d061980
stopped the sync_worlds function from clearing and then spawning all …
tkallies Sep 11, 2025
c34b94c
Merge branch 'cram2:dev' into dev
tkallies Sep 15, 2025
476ab05
set_cart_goal wrapper
tkallies Sep 19, 2025
7619a7a
fix robot_state_updater.py so that joint states are received
tkallies Sep 23, 2025
a6760ca
small fixes
tkallies Sep 24, 2025
afe1030
new tracy.urdf that is compatible with the one used by giskard + smal…
tkallies Sep 25, 2025
8101873
update test_robot_state_updater.py
tkallies Sep 25, 2025
e0cfb3c
fixed a bug with the update of the poses + changed the grasp_orientat…
tkallies Sep 29, 2025
c5fe098
remove temporary workaround
tkallies Oct 6, 2025
18365e6
Merge branch 'cram2:dev' into dev
tkallies Nov 19, 2025
e6a8bee
add documentation to giskard.py
tkallies Nov 19, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
132 changes: 66 additions & 66 deletions resources/robots/tracy.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -56,11 +56,12 @@
- Ajit Krisshna N L
- Muhammad Asif Rana
-->
<link name="world"/>
<!--<xacro:include filename="$(find robotiq_2f_85_gripper_visualization)/urdf/robotiq_arg2f_85_model_macro.xacro" /> -->
<link name="map"/>
<joint name="table_joint" type="fixed">
<parent link="world"/>
<parent link="map"/>
<child link="table"/>
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.88"/>
</joint>
<link name="table">
<visual>
Expand Down Expand Up @@ -172,7 +173,19 @@
<child link="right_arm_mount"/>
<origin rpy="1.0472 0.0 0.0" xyz="0.135 -0.050925 0.173"/>
</joint>
<link name="left_world"/>
<joint name="left_world_joint" type="fixed">
<parent link="left_arm_mount"/>
<child link="left_world"/>
<origin rpy="0.0 0.0 3.141592653589793" xyz="0.0 0.0 0.0"/>
</joint>
<!-- links - main serial chain -->
<!-- base_link serves as the root of the robot's kinematic tree. It follows REP-103
conventions (i.e., X+ forward, Y+ left, Z+ up).
Since some kinematic solvers forbid having inertia values attached to a root link, we've
added the base_link_inertia link that carries the visual, collision and inertia
information.
-->
<link name="left_base_link"/>
<link name="left_base_link_inertia">
<visual>
Expand Down Expand Up @@ -309,8 +322,8 @@
</link>
<!-- base_joint fixes base_link to the environment -->
<joint name="left_base_joint" type="fixed">
<origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
<parent link="left_arm_mount"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="left_world"/>
<child link="left_base_link"/>
</joint>
<!-- joints - main serial chain -->
Expand Down Expand Up @@ -405,7 +418,19 @@
<parent link="left_flange"/>
<child link="left_tool0"/>
</joint>
<link name="right_world"/>
<joint name="right_world_joint" type="fixed">
<parent link="right_arm_mount"/>
<child link="right_world"/>
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
</joint>
<!-- links - main serial chain -->
<!-- base_link serves as the root of the robot's kinematic tree. It follows REP-103
conventions (i.e., X+ forward, Y+ left, Z+ up).
Since some kinematic solvers forbid having inertia values attached to a root link, we've
added the base_link_inertia link that carries the visual, collision and inertia
information.
-->
<link name="right_base_link"/>
<link name="right_base_link_inertia">
<visual>
Expand Down Expand Up @@ -543,7 +568,7 @@
<!-- base_joint fixes base_link to the environment -->
<joint name="right_base_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="right_arm_mount"/>
<parent link="right_world"/>
<child link="right_base_link"/>
</joint>
<!-- joints - main serial chain -->
Expand Down Expand Up @@ -643,9 +668,13 @@
<hardware>
<!-- Set use_dummy to true to connect to a dummy driver for testing purposes. -->
<param name="use_dummy">false</param>
<plugin>mock_components/GenericSystem</plugin>
<param name="mock_sensor_commands">False</param>
<param name="state_following_offset">0.0</param>
<plugin>robotiq_driver/RobotiqGripperHardwareInterface</plugin>
<param name="gripper_closed_position">0.7929</param>
<param name="COM_port">/dev/ttyUSB0</param>
<param name="gripper_speed_multiplier">1.0</param>
<param name="gripper_force_multiplier">0.5</param>
<param name="gripper_max_speed">0.15</param>
<param name="gripper_max_force">235.0</param>
</hardware>
<!-- Joint interfaces -->
<!-- With Gazebo or Hardware, they handle mimic joints, so we only need this command interface activated -->
Expand All @@ -656,26 +685,6 @@
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="left_robotiq_85_right_knuckle_joint">
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="left_robotiq_85_left_inner_knuckle_joint">
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="left_robotiq_85_right_inner_knuckle_joint">
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="left_robotiq_85_left_finger_tip_joint">
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="left_robotiq_85_right_finger_tip_joint">
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<gpio name="reactivate_gripper">
<command_interface name="reactivate_gripper_cmd"/>
<command_interface name="reactivate_gripper_response"/>
Expand Down Expand Up @@ -873,7 +882,7 @@
<joint name="left_robotiq_85_base_joint" type="fixed">
<parent link="left_wrist_3_link"/>
<child link="left_robotiq_85_base_link"/>
<origin rpy="0.0 0.0 1.57" xyz="0.0 0.0 0.0"/>
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
</joint>
<joint name="left_robotiq_85_left_knuckle_joint" type="revolute">
<parent link="left_robotiq_85_base_link"/>
Expand All @@ -900,42 +909,50 @@
<child link="left_robotiq_85_right_finger_link"/>
<origin rpy="0 0 0" xyz="-0.03152616 0.0 -0.00376347"/>
</joint>
<joint name="left_robotiq_85_left_inner_knuckle_joint" type="continuous">
<joint name="left_robotiq_85_left_inner_knuckle_joint" type="revolute">
<parent link="left_robotiq_85_base_link"/>
<child link="left_robotiq_85_left_inner_knuckle_link"/>
<axis xyz="0 -1 0"/>
<origin rpy="0 0 0" xyz="0.0127 0.0 0.06142"/>
<limit effort="50" lower="0.0" upper="0.8" velocity="0.5"/>
<mimic joint="left_robotiq_85_left_knuckle_joint"/>
</joint>
<joint name="left_robotiq_85_right_inner_knuckle_joint" type="continuous">
<joint name="left_robotiq_85_right_inner_knuckle_joint" type="revolute">
<parent link="left_robotiq_85_base_link"/>
<child link="left_robotiq_85_right_inner_knuckle_link"/>
<axis xyz="0 -1 0"/>
<origin rpy="0 0 0" xyz="-0.0127 0.0 0.06142"/>
<limit effort="50" lower="0.0" upper="0.8" velocity="0.5"/>
<mimic joint="left_robotiq_85_left_knuckle_joint" multiplier="-1"/>
</joint>
<joint name="left_robotiq_85_left_finger_tip_joint" type="continuous">
<joint name="left_robotiq_85_left_finger_tip_joint" type="revolute">
<parent link="left_robotiq_85_left_finger_link"/>
<child link="left_robotiq_85_left_finger_tip_link"/>
<axis xyz="0 -1 0"/>
<origin rpy="0 0 0" xyz="0.00563134 0.0 0.04718515"/>
<limit effort="50" lower="0.0" upper="0.8" velocity="0.5"/>
<mimic joint="left_robotiq_85_left_knuckle_joint" multiplier="-1"/>
</joint>
<joint name="left_robotiq_85_right_finger_tip_joint" type="continuous">
<joint name="left_robotiq_85_right_finger_tip_joint" type="revolute">
<parent link="left_robotiq_85_right_finger_link"/>
<child link="left_robotiq_85_right_finger_tip_link"/>
<axis xyz="0 -1 0"/>
<origin rpy="0 0 0" xyz="-0.00563134 0.0 0.04718515"/>
<limit effort="50" lower="0.0" upper="0.8" velocity="0.5"/>
<mimic joint="left_robotiq_85_left_knuckle_joint"/>
</joint>
<ros2_control name="right_gripper" type="system">
<!-- Plugins -->
<hardware>
<!-- Set use_dummy to true to connect to a dummy driver for testing purposes. -->
<param name="use_dummy">false</param>
<plugin>mock_components/GenericSystem</plugin>
<param name="mock_sensor_commands">False</param>
<param name="state_following_offset">0.0</param>
<plugin>robotiq_driver/RobotiqGripperHardwareInterface</plugin>
<param name="gripper_closed_position">0.7929</param>
<param name="COM_port">/dev/ttyUSB0</param>
<param name="gripper_speed_multiplier">1.0</param>
<param name="gripper_force_multiplier">0.5</param>
<param name="gripper_max_speed">0.15</param>
<param name="gripper_max_force">235.0</param>
</hardware>
<!-- Joint interfaces -->
<!-- With Gazebo or Hardware, they handle mimic joints, so we only need this command interface activated -->
Expand All @@ -946,26 +963,6 @@
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="right_robotiq_85_right_knuckle_joint">
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="right_robotiq_85_left_inner_knuckle_joint">
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="right_robotiq_85_right_inner_knuckle_joint">
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="right_robotiq_85_left_finger_tip_joint">
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="right_robotiq_85_right_finger_tip_joint">
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<gpio name="reactivate_gripper">
<command_interface name="reactivate_gripper_cmd"/>
<command_interface name="reactivate_gripper_response"/>
Expand Down Expand Up @@ -1163,7 +1160,7 @@
<joint name="right_robotiq_85_base_joint" type="fixed">
<parent link="right_wrist_3_link"/>
<child link="right_robotiq_85_base_link"/>
<origin rpy="0.0 0.0 1.57" xyz="0.0 0.0 0.0"/>
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
</joint>
<joint name="right_robotiq_85_left_knuckle_joint" type="revolute">
<parent link="right_robotiq_85_base_link"/>
Expand All @@ -1190,45 +1187,48 @@
<child link="right_robotiq_85_right_finger_link"/>
<origin rpy="0 0 0" xyz="-0.03152616 0.0 -0.00376347"/>
</joint>
<joint name="right_robotiq_85_left_inner_knuckle_joint" type="continuous">
<joint name="right_robotiq_85_left_inner_knuckle_joint" type="revolute">
<parent link="right_robotiq_85_base_link"/>
<child link="right_robotiq_85_left_inner_knuckle_link"/>
<axis xyz="0 -1 0"/>
<origin rpy="0 0 0" xyz="0.0127 0.0 0.06142"/>
<limit effort="50" lower="0.0" upper="0.8" velocity="0.5"/>
<mimic joint="right_robotiq_85_left_knuckle_joint"/>
</joint>
<joint name="right_robotiq_85_right_inner_knuckle_joint" type="continuous">
<joint name="right_robotiq_85_right_inner_knuckle_joint" type="revolute">
<parent link="right_robotiq_85_base_link"/>
<child link="right_robotiq_85_right_inner_knuckle_link"/>
<axis xyz="0 -1 0"/>
<origin rpy="0 0 0" xyz="-0.0127 0.0 0.06142"/>
<limit effort="50" lower="0.0" upper="0.8" velocity="0.5"/>
<mimic joint="right_robotiq_85_left_knuckle_joint" multiplier="-1"/>
</joint>
<joint name="right_robotiq_85_left_finger_tip_joint" type="continuous">
<joint name="right_robotiq_85_left_finger_tip_joint" type="revolute">
<parent link="right_robotiq_85_left_finger_link"/>
<child link="right_robotiq_85_left_finger_tip_link"/>
<axis xyz="0 -1 0"/>
<origin rpy="0 0 0" xyz="0.00563134 0.0 0.04718515"/>
<limit effort="50" lower="0.0" upper="0.8" velocity="0.5"/>
<mimic joint="right_robotiq_85_left_knuckle_joint" multiplier="-1"/>
</joint>
<joint name="right_robotiq_85_right_finger_tip_joint" type="continuous">
<joint name="right_robotiq_85_right_finger_tip_joint" type="revolute">
<parent link="right_robotiq_85_right_finger_link"/>
<child link="right_robotiq_85_right_finger_tip_link"/>
<axis xyz="0 -1 0"/>
<origin rpy="0 0 0" xyz="-0.00563134 0.0 0.04718515"/>
<limit effort="50" lower="0.0" upper="0.8" velocity="0.5"/>
<mimic joint="right_robotiq_85_left_knuckle_joint"/>
</joint>
<!-- Removed redundant joints as they're now handled by the robotiq_gripper macro -->
<joint name="l_gripper_tool_frame_joint" type="fixed">
<parent link="left_robotiq_85_base_link"/>
<child link="l_gripper_tool_frame"/>
<origin rpy="0.0 -1.57079632679 -1.57079632679" xyz="0.0 0.0 0.144"/>
<origin rpy="0.0 0.0 0" xyz="0.0 0.0 0.144"/>
</joint>
<link name="l_gripper_tool_frame"/>
<joint name="r_gripper_tool_frame_joint" type="fixed">
<parent link="right_robotiq_85_base_link"/>
<child link="r_gripper_tool_frame"/>
<origin rpy="0.0 -1.57079632679 -1.57079632679" xyz="0.0 0.0 0.144"/>
<origin rpy="0.0 0.0 0" xyz="0.0 0.0 0.144"/>
</joint>
<link name="r_gripper_tool_frame"/>
</robot>
</robot>
Loading