Skip to content

Commit

Permalink
Update ros2 control usage (#192) (#193)
Browse files Browse the repository at this point in the history
* Update ros2_control usage

* Update dual_arm_panda_moveit_config/config/panda_hand.ros2_control.xacro

Co-authored-by: Sebastian Castro <[email protected]>

---------

Co-authored-by: Sebastian Castro <[email protected]>
# Conflicts:
#	dual_arm_panda_moveit_config/config/panda.ros2_control.xacro
#	dual_arm_panda_moveit_config/config/panda_hand.ros2_control.xacro
#	dual_arm_panda_moveit_config/launch/demo.launch.py
  • Loading branch information
sjahr authored Dec 21, 2023
1 parent 5cf047b commit df8401d
Show file tree
Hide file tree
Showing 5 changed files with 53 additions and 17 deletions.
24 changes: 18 additions & 6 deletions fanuc_moveit_config/config/fanuc.ros2_control.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -13,42 +13,54 @@
<state_interface name="position">
<param name="initial_value">${initial_positions['joint_1']}</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="joint_2">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['joint_2']}</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="joint_3">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['joint_3']}</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="joint_4">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['joint_4']}</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="joint_5">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['joint_5']}</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="joint_6">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['joint_6']}</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
</ros2_control>
</xacro:macro>
Expand Down
5 changes: 4 additions & 1 deletion fanuc_moveit_config/launch/demo.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,10 @@ def generate_launch_description():
ros2_control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[moveit_config.robot_description, ros2_controllers_path],
parameters=[ros2_controllers_path],
remappings=[
("/controller_manager/robot_description", "/robot_description"),
],
output="both",
)

Expand Down
28 changes: 21 additions & 7 deletions panda_moveit_config/config/panda.ros2_control.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -20,49 +20,63 @@
<state_interface name="position">
<param name="initial_value">${initial_positions['panda_joint1']}</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="panda_joint2">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['panda_joint2']}</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="panda_joint3">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['panda_joint3']}</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="panda_joint4">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['panda_joint4']}</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="panda_joint5">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['panda_joint5']}</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="panda_joint6">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['panda_joint6']}</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="panda_joint7">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['panda_joint7']}</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
</ros2_control>
</xacro:macro>
Expand Down
8 changes: 6 additions & 2 deletions panda_moveit_config/config/panda_hand.ros2_control.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,9 @@
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="panda_finger_joint2">
<param name="mimic">panda_finger_joint1</param>
Expand All @@ -27,7 +29,9 @@
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
</ros2_control>
</xacro:macro>
Expand Down
5 changes: 4 additions & 1 deletion panda_moveit_config/launch/demo.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,10 @@ def generate_launch_description():
ros2_control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[moveit_config.robot_description, ros2_controllers_path],
parameters=[ros2_controllers_path],
remappings=[
("/controller_manager/robot_description", "/robot_description"),
],
output="screen",
)

Expand Down

0 comments on commit df8401d

Please sign in to comment.