Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix gripper_joint issue #314 #317

Merged
merged 1 commit into from
Mar 25, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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
Original file line number Diff line number Diff line change
Expand Up @@ -32,14 +32,16 @@
</link>

<!-- Gripper Joint -->
<joint name="${prefix}_gripper_joint" type="revolute">
<axis xyz="0 0 1"/>
<joint name="${prefix}_gripper_joint" type="fixed">
<parent link="${prefix}_${parent}"/>
<child link="${prefix}_gripper"/>
<limit lower="-.001" upper=".001" effort="1000" velocity="0" />
<origin xyz="0.0 0.0 0.01" rpy="0.0 0.0 0.0"/>
</joint>

<gazebo reference='${prefix}_gripper_joint'>
<preserveFixedJoint>true</preserveFixedJoint>
</gazebo>

<!-- Add a contact sensor to the gripper -->
<gazebo reference="${prefix}_gripper">
<sensor type="contact" name="bumper">
Expand Down
7 changes: 1 addition & 6 deletions ariac_moveit_config/config/ariac_robots.srdf
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,7 @@
</group>
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
<group_state name="home" group="floor_robot">
<joint name="floor_elbow_joint" value="1.571"/>
<joint name="floor_gripper_joint" value="0"/>
<joint name="floor_elbow_joint" value="1.571"/>>
<joint name="floor_shoulder_lift_joint" value="-1.571"/>
<joint name="floor_shoulder_pan_joint" value="0"/>
<joint name="floor_wrist_1_joint" value="-1.571"/>
Expand All @@ -37,7 +36,6 @@
</group_state>
<group_state name="home" group="ceiling_robot">
<joint name="ceiling_elbow_joint" value="1.571"/>
<joint name="ceiling_gripper_joint" value="0"/>
<joint name="ceiling_shoulder_lift_joint" value="-1.571"/>
<joint name="ceiling_shoulder_pan_joint" value="0"/>
<joint name="ceiling_wrist_1_joint" value="3.14"/>
Expand All @@ -47,9 +45,6 @@
<joint name="gantry_y_axis_joint" value="0"/>
<joint name="gantry_rotation_joint" value="-1.571"/>
</group_state>
<!--PASSIVE JOINT: Purpose: this element is used to mark joints that are not actuated-->
<passive_joint name="floor_gripper_joint"/>
<passive_joint name="ceiling_gripper_joint"/>

<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
<disable_collisions link1="agv1_base" link2="agv1_tray" reason="Adjacent"/>
Expand Down
10 changes: 0 additions & 10 deletions ariac_moveit_config/config/joint_limits.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -20,11 +20,6 @@ joint_limits:
floor_wrist_3_joint:
has_acceleration_limits: true
max_acceleration: 5.0
floor_gripper_joint:
has_velocity_limits: true
max_velocity: 1.0
has_acceleration_limits: true
max_acceleration: 0.5
gantry_x_axis_joint:
has_acceleration_limits: true
max_acceleration: 0.5
Expand Down Expand Up @@ -52,8 +47,3 @@ joint_limits:
ceiling_wrist_3_joint:
has_acceleration_limits: true
max_acceleration: 5.0
ceiling_gripper_joint:
has_velocity_limits: true
max_velocity: 1.0
has_acceleration_limits: true
max_acceleration: 0.5