fix: remove space from joint name

This commit is contained in:
David Sharpe
2025-08-19 12:49:53 -05:00
committed by David
parent fa10027e2d
commit 0d09c81802
9 changed files with 34 additions and 34 deletions

View File

@@ -10,41 +10,41 @@ default_acceleration_scaling_factor: 1
joint_limits:
Axis_0_Joint:
has_velocity_limits: true
max_velocity: 0.3141593
max_velocity: 3.141593
has_acceleration_limits: true
max_acceleration: 0.1
max_acceleration: 0.5
Axis_1_Joint:
has_velocity_limits: true
max_velocity: 0.3141593
max_velocity: 3.141593
has_acceleration_limits: true
max_acceleration: 0.1
max_acceleration: 0.5
Axis_2_Joint:
has_velocity_limits: true
max_velocity: 0.3141593
max_velocity: 3.141593
has_acceleration_limits: true
max_acceleration: 0.1
max_acceleration: 0.5
Axis_3_Joint:
has_velocity_limits: true
max_velocity: 0.3141593
max_velocity: 3.141593
has_acceleration_limits: true
max_acceleration: 0.1
max_acceleration: 0.5
Gripper_Slider_Left:
has_velocity_limits: true
max_velocity: 0.3141593
max_velocity: 3.141593
has_acceleration_limits: true
max_acceleration: 0.1
max_acceleration: 0.5
Gripper_Slider_Right:
has_velocity_limits: true
max_velocity: 0.3141593
max_velocity: 3.141593
has_acceleration_limits: true
max_acceleration: 0.1
max_acceleration: 0.5
Wrist_Differential_Joint:
has_velocity_limits: true
max_velocity: 0.3141593
max_velocity: 3.141593
has_acceleration_limits: true
max_acceleration: 0.1
max_acceleration: 0.5
Wrist-EF_Roll_Joint:
has_velocity_limits: true
max_velocity: 0.3141593
max_velocity: 3.141593
has_acceleration_limits: true
max_acceleration: 0.1
max_acceleration: 0.5

View File

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

View File

@@ -103,7 +103,7 @@
lower="-3.14"
upper="3.14"
effort="0"
velocity="0.05" />
velocity="3.1415963" />
</joint>
<link
@@ -163,7 +163,7 @@
lower="-1.05"
upper="1.6"
effort="0"
velocity="0.05" />
velocity="3.1415963" />
</joint>
<link
@@ -223,7 +223,7 @@
lower="-2.0"
upper="2.0"
effort="0"
velocity="0.05" />
velocity="3.1415963" />
</joint>
<link
@@ -283,7 +283,7 @@
lower="-1.6"
upper="1.9"
effort="0"
velocity="0.05" />
velocity="3.1415963" />
</joint>
<link
@@ -343,7 +343,7 @@
lower="-1.6"
upper="1.6"
effort="0"
velocity="0.05" />
velocity="3.1415963" />
</joint>
<link
@@ -458,7 +458,7 @@
lower="-0.025"
upper="0.04"
effort="0"
velocity="0.05" />
velocity="3.1415963" />
</joint>
<link
@@ -518,7 +518,7 @@
lower="-0.04"
upper="0.025"
effort="0"
velocity="0.05" />
velocity="3.1415963" />
</joint>
</robot>