fix: move roll joint to arm pose group, add real velocity limit to grippers

This commit is contained in:
David Sharpe
2025-08-19 13:09:43 -05:00
committed by David
parent 0d09c81802
commit 77bf59d5fd
7 changed files with 19 additions and 14 deletions

View File

@@ -7,7 +7,7 @@ moveit_setup_assistant_config:
package_settings:
author_name: David Sharpe
author_email: ds0196@uah.edu
generated_timestamp: 1755622867
generated_timestamp: 1755625929
control_xacro:
command:
- position

View File

@@ -16,9 +16,9 @@
<joint name="Axis_2_Joint"/>
<joint name="Axis_3_Joint"/>
<joint name="Wrist_Differential_Joint"/>
<joint name="Wrist-EF_Roll_Joint"/>
</group>
<group name="Hand">
<link name="End Effector"/>
<link name="EF Gripper Left"/>
<link name="EF Gripper Right"/>
</group>
@@ -28,6 +28,7 @@
<joint name="Axis_1_Joint" value="0"/>
<joint name="Axis_2_Joint" value="0"/>
<joint name="Axis_3_Joint" value="0"/>
<joint name="Wrist-EF_Roll_Joint" value="0"/>
<joint name="Wrist_Differential_Joint" value="0"/>
</group_state>
<group_state name="Stow" group="astra_arm">
@@ -35,6 +36,7 @@
<joint name="Axis_1_Joint" value="-1.05"/>
<joint name="Axis_2_Joint" value="-2"/>
<joint name="Axis_3_Joint" value="-1.6"/>
<joint name="Wrist-EF_Roll_Joint" value="0"/>
<joint name="Wrist_Differential_Joint" value="0"/>
</group_state>
<group_state name="Ready" group="astra_arm">
@@ -42,20 +44,19 @@
<joint name="Axis_1_Joint" value="0"/>
<joint name="Axis_2_Joint" value="-1.6"/>
<joint name="Axis_3_Joint" value="-1.6"/>
<joint name="Wrist-EF_Roll_Joint" value="0"/>
<joint name="Wrist_Differential_Joint" value="0"/>
</group_state>
<group_state name="Open" group="Hand">
<joint name="Gripper_Slider_Right" value="0.04"/>
<joint name="Gripper_Slider_Left" value="-0.04"/>
<joint name="Wrist-EF_Roll_Joint" value="0"/>
<joint name="Gripper_Slider_Right" value="0.04"/>
</group_state>
<group_state name="Close" group="Hand">
<joint name="Gripper_Slider_Right" value="-0.0215"/>
<joint name="Gripper_Slider_Left" value="0.0215"/>
<joint name="Wrist-EF_Roll_Joint" value="0"/>
<joint name="Gripper_Slider_Right" value="-0.0215"/>
</group_state>
<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
<end_effector name="Hand" parent_link="Diff Carrier" group="Hand"/>
<end_effector name="Hand" parent_link="End Effector" group="Hand"/>
<!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)-->
<virtual_joint name="virtual_joint" type="fixed" parent_frame="world" child_link="base_link"/>
<!--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. -->

View File

@@ -30,12 +30,12 @@ joint_limits:
max_acceleration: 0.5
Gripper_Slider_Left:
has_velocity_limits: true
max_velocity: 3.141593
max_velocity: 0.015
has_acceleration_limits: true
max_acceleration: 0.5
Gripper_Slider_Right:
has_velocity_limits: true
max_velocity: 3.141593
max_velocity: 0.015
has_acceleration_limits: true
max_acceleration: 0.5
Wrist_Differential_Joint:

View File

@@ -1,4 +1,4 @@
astra_arm:
kinematics_solver: pick_ik/PickIkPlugin
kinematics_solver_search_resolution: 0.0050000000000000001
kinematics_solver_timeout: 0.010000000000000001
kinematics_solver_timeout: 0.01

View File

@@ -15,12 +15,12 @@ moveit_simple_controller_manager:
- Axis_2_Joint
- Axis_3_Joint
- Wrist_Differential_Joint
- Wrist-EF_Roll_Joint
action_ns: follow_joint_trajectory
default: true
hand_controller:
type: GripperCommand
joints:
- Wrist-EF_Roll_Joint
- Gripper_Slider_Left
- Gripper_Slider_Right
action_ns: gripper_cmd

View File

@@ -22,6 +22,7 @@ astra_arm_controller:
- Axis_2_Joint
- Axis_3_Joint
- Wrist_Differential_Joint
- Wrist-EF_Roll_Joint
command_interfaces:
- position
- velocity
@@ -32,4 +33,4 @@ astra_arm_controller:
hand_controller:
ros__parameters:
joint: Wrist-EF_Roll_Joint
joint: Gripper_Slider_Left

View File

@@ -458,7 +458,10 @@
lower="-0.025"
upper="0.04"
effort="0"
velocity="3.1415963" />
velocity="0.015" />
<mimic
joint="Gripper_Slider_Left"
multiplier="-1" />
</joint>
<link
@@ -518,7 +521,7 @@
lower="-0.04"
upper="0.025"
effort="0"
velocity="3.1415963" />
velocity="0.015" />
</joint>
</robot>