From 701dbd9a1f1634a53640b3b77796b06689fe0f2e Mon Sep 17 00:00:00 2001 From: alejandrojginerd <126397782+alejandrojginerd@users.noreply.github.com> Date: Fri, 13 Sep 2024 13:48:52 +0200 Subject: [PATCH] MoveGroup naming inconsitency The MoveGroup name in hello_moveit.cpp does not match the one sued in panda.srdf, leading to errors while running `ros2 run hello_moveit hello_moveit` --- doc/tutorials/your_first_project/your_first_project.rst | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/doc/tutorials/your_first_project/your_first_project.rst b/doc/tutorials/your_first_project/your_first_project.rst index 2c15798feb..a4f6dc85ca 100644 --- a/doc/tutorials/your_first_project/your_first_project.rst +++ b/doc/tutorials/your_first_project/your_first_project.rst @@ -139,7 +139,7 @@ In place of the comment that says "Next step goes here", add this code: // Create the MoveIt MoveGroup Interface using moveit::planning_interface::MoveGroupInterface; - auto move_group_interface = MoveGroupInterface(node, "manipulator"); + auto move_group_interface = MoveGroupInterface(node, "panda_arm"); // Set a target Pose auto const target_pose = []{ @@ -222,7 +222,7 @@ That is the group of joints as defined in the robot description that we are goin .. code-block:: C++ using moveit::planning_interface::MoveGroupInterface; - auto move_group_interface = MoveGroupInterface(node, "manipulator"); + auto move_group_interface = MoveGroupInterface(node, "panda_arm"); Then, we set our target pose and plan. Note that only the target pose is set (via ``setPoseTarget``). The starting pose is implicitly the position published by the joint state publisher, which could be changed using the