Skip to content

Commit

Permalink
Rename cartesian_limits.yaml
Browse files Browse the repository at this point in the history
  • Loading branch information
Andy Zelenak committed Jul 8, 2022
1 parent 2c58cf3 commit 8493796
Show file tree
Hide file tree
Showing 4 changed files with 63 additions and 0 deletions.
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
# Cartesian limits for the Pilz planner
cartesian_limits:
max_trans_vel: 1.0
max_trans_acc: 2.25
Expand Down
21 changes: 21 additions & 0 deletions panda_moveit_config/config/panda.ros2_control.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -10,52 +10,73 @@
</hardware>
<joint name="panda_joint1">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="acceleration"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['panda_joint1']}</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
</joint>
<joint name="panda_joint2">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="acceleration"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['panda_joint2']}</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
</joint>
<joint name="panda_joint3">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="acceleration"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['panda_joint3']}</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
</joint>
<joint name="panda_joint4">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="acceleration"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['panda_joint4']}</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
</joint>
<joint name="panda_joint5">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="acceleration"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['panda_joint5']}</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
</joint>
<joint name="panda_joint6">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="acceleration"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['panda_joint6']}</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
</joint>
<joint name="panda_joint7">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="acceleration"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['panda_joint7']}</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
</joint>
</ros2_control>
</xacro:macro>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
# Cartesian limits for the Pilz planner
cartesian_limits:
max_trans_vel: 1.0
max_trans_acc: 2.25
Expand Down
40 changes: 40 additions & 0 deletions panda_moveit_config/config/ros2_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,12 @@ panda_arm_controller:
ros__parameters:
command_interfaces:
- position
- velocity
- acceleration
state_interfaces:
- position
- velocity
- acceleration
joints:
- panda_joint1
- panda_joint2
Expand All @@ -28,6 +31,43 @@ panda_arm_controller:
- panda_joint5
- panda_joint6
- panda_joint7
interpolation_method: none
joint_limits:
panda_joint1:
has_velocity_limits: true
max_velocity: 2.1750
has_acceleration_limits: true
max_acceleration: 3.75
panda_joint2:
has_velocity_limits: true
max_velocity: 2.1750
has_acceleration_limits: true
max_acceleration: 1.875
panda_joint3:
has_velocity_limits: true
max_velocity: 2.1750
has_acceleration_limits: true
max_acceleration: 2.5
panda_joint4:
has_velocity_limits: true
max_velocity: 2.1750
has_acceleration_limits: true
max_acceleration: 3.125
panda_joint5:
has_velocity_limits: true
max_velocity: 2.6100
has_acceleration_limits: true
max_acceleration: 3.75
panda_joint6:
has_velocity_limits: true
max_velocity: 2.6100
has_acceleration_limits: true
max_acceleration: 5.0
panda_joint7:
has_velocity_limits: true
max_velocity: 2.6100
has_acceleration_limits: true
max_acceleration: 5.0

panda_hand_controller:
ros__parameters:
Expand Down

0 comments on commit 8493796

Please sign in to comment.