moveit / moveit2_tutorials

A sphinx-based centralized documentation repo for MoveIt 2
https://moveit.picknik.ai
BSD 3-Clause "New" or "Revised" License
156 stars 195 forks source link

the robot won't move when I following official tutorials[Move Group C++ Interface] #202

Closed mengyin98 closed 2 years ago

mengyin98 commented 2 years ago

Description

I am studying the official tutorials of moveit2, things went well until I get to the chapter [Move Group C++ Interface] According to the tutorial, I should see the robot arm moving from one pose to another or "climb" over the obstacle with a cylinder on its gripper. However, I can only see robot arm simulating in step 3(The robot moves its arm back to a new pose goal while maintaining the end-effector level.) and step 4(The robot moves its arm along the desired Cartesian path (a triangle down, right, up+left). In step1 and step2, I can only see the goal pose, no moving. In step6 7, I can only see the obstacle and cylinder and cartesian path, but robot keep still.

All the code and packages was downloaded following the tutorials[Getting Started].

Your environment

Here are some error information when press the "next" [ompl]: /tmp/binarydeb/ros-foxy-ompl-1.5.0/src/ompl/base/src/Planner.cpp:257 - panda_arm/panda_arm: Skipping invalid start state (invalid state) [ERROR] [1636452054.051086261] [ompl]: /tmp/binarydeb/ros-foxy-ompl-1.5.0/src/ompl/geometric/planners/rrt/src/RRTConnect.cpp:207 - panda_arm/panda_arm: Motion planning start tree could not be initialized!

[INFO] [1636452054.051090566] [ompl]: /tmp/binarydeb/ros-foxy-ompl-1.5.0/src/ompl/geometric/src/SimpleSetup.cpp:140 - No solution found after 0.000033 seconds [WARN] [1636452054.061120905] [ompl]: /tmp/binarydeb/ros-foxy-ompl-1.5.0/src/ompl/base/goals/src/GoalLazySamples.cpp:129 - Goal sampling thread never did any work.

[INFO] [1636452054.061204578] [moveit.ompl_planning.model_based_planning_context]: Unable to solve the planning problem [move_group-4]

[INFO] [1636452054.061237439] [moveit_move_group_default_capabilities.move_action_capability]: No motion plan found

vatanaksoytezer commented 2 years ago

Hello @mengyin98, thanks for the issue! Do you mind sharing the full log from the start, and possibly a video / gif on what's happening so that we can try to understand what might the problem?

mengyin98 commented 2 years ago

Hello @mengyin98, thanks for the issue! Do you mind sharing the full log from the start, and possibly a video / gif on what's happening so that we can try to understand what might the problem?

Thanks for your help sir, here are all the log from the shell and the video

[move_group-4] You can start planning now! [move_group-4] [move_group-4] [INFO] [1636509654.205142648] [moveit_move_group_default_capabilities.move_action_capability]: Received request

[move_group-4] [INFO] [1636509654.218207394] [moveit_move_group_default_capabilities.move_action_capability]: Planning request received for MoveGroup action. Forwarding to planning pipeline. [move_group-4] [INFO] [1636509654.257353411] [moveit_collision_detection_fcl.collision_common]: Found a contact between 'panda_link5' (type 'Robot link') and 'panda_link7' (type 'Robot link'), which constitutes a collision. Contact information is not stored. [move_group-4] [INFO] [1636509654.257375816] [moveit_collision_detection_fcl.collision_common]: Collision checking is considered complete (collision was found and 0 contacts are stored) [move_group-4] [INFO] [1636509654.257380707] [moveit_ros.fix_start_state_collision]: Start state appears to be in collision with respect to group panda_arm [move_group-4] [WARN] [1636509654.263700543] [moveit_ros.fix_start_state_collision]: Unable to find a valid state nearby the start state (using jiggle fraction of 0.020000 and 100 sampling attempts). Passing the original planning request to the planner. [move_group-4] [INFO] [1636509654.299678507] [moveit.ompl_planning.model_based_planning_context]: Planner configuration 'panda_arm' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed. [move_group-4] [WARN] [1636509654.342196237] [ompl]: /tmp/binarydeb/ros-foxy-ompl-1.5.0/src/ompl/base/src/Planner.cpp:257 - panda_arm/panda_arm: Skipping invalid start state (invalid state) [move_group-4] [ERROR] [1636509654.342354070] [ompl]: /tmp/binarydeb/ros-foxy-ompl-1.5.0/src/ompl/geometric/planners/rrt/src/RRTConnect.cpp:207 - panda_arm/panda_arm: Motion planning start tree could not be initialized! [move_group-4] [INFO] [1636509654.342381106] [ompl]: /tmp/binarydeb/ros-foxy-ompl-1.5.0/src/ompl/geometric/src/SimpleSetup.cpp:140 - No solution found after 0.000354 seconds [move_group-4] [INFO] [1636509654.342511826] [moveit.ompl_planning.model_based_planning_context]: Unable to solve the planning problem [move_group-4] [INFO] [1636509654.342627062] [moveit_move_group_default_capabilities.move_action_capability]: No motion plan found. No execution attempted. [move_group-4] [INFO] [1636509656.318558536] [moveit_move_group_default_capabilities.move_action_capability]: Received request

[move_group-4] [INFO] [1636509656.419004768] [moveit_move_group_default_capabilities.move_action_capability]: Planning request received for MoveGroup action. Forwarding to planning pipeline. [move_group-4] [INFO] [1636509656.419586387] [moveit_collision_detection_fcl.collision_common]: Found a contact between 'panda_link5' (type 'Robot link') and 'panda_link7' (type 'Robot link'), which constitutes a collision. Contact information is not stored. [move_group-4] [INFO] [1636509656.419646201] [moveit_collision_detection_fcl.collision_common]: Collision checking is considered complete (collision was found and 0 contacts are stored) [move_group-4] [INFO] [1636509656.419677308] [moveit_ros.fix_start_state_collision]: Start state appears to be in collision with respect to group panda_arm [move_group-4] [WARN] [1636509656.433509642] [moveit_ros.fix_start_state_collision]: Unable to find a valid state nearby the start state (using jiggle fraction of 0.020000 and 100 sampling attempts). Passing the original planning request to the planner. [move_group-4] [INFO] [1636509656.433824356] [moveit.ompl_planning.model_based_planning_context]: Planner configuration 'panda_arm' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed. [move_group-4] [WARN] [1636509656.433892117] [ompl]: /tmp/binarydeb/ros-foxy-ompl-1.5.0/src/ompl/base/src/Planner.cpp:257 - panda_arm/panda_arm: Skipping invalid start state (invalid state) [move_group-4] [ERROR] [1636509656.433907251] [ompl]: /tmp/binarydeb/ros-foxy-ompl-1.5.0/src/ompl/geometric/planners/rrt/src/RRTConnect.cpp:207 - panda_arm/panda_arm: Motion planning start tree could not be initialized! [move_group-4] [INFO] [1636509656.433911427] [ompl]: /tmp/binarydeb/ros-foxy-ompl-1.5.0/src/ompl/geometric/src/SimpleSetup.cpp:140 - No solution found after 0.000038 seconds [move_group-4] [WARN] [1636509656.443902022] [ompl]: /tmp/binarydeb/ros-foxy-ompl-1.5.0/src/ompl/base/goals/src/GoalLazySamples.cpp:129 - Goal sampling thread never did any work. [move_group-4] [INFO] [1636509656.443992530] [moveit.ompl_planning.model_based_planning_context]: Unable to solve the planning problem [move_group-4] [INFO] [1636509656.444027444] [moveit_move_group_default_capabilities.move_action_capability]: No motion plan found. No execution attempted. [move_group-4] [INFO] [1636509658.919347986] [moveit_move_group_default_capabilities.move_action_capability]: Received request

[move_group-4] [INFO] [1636509659.018108082] [moveit_move_group_default_capabilities.move_action_capability]: Planning request received for MoveGroup action. Forwarding to planning pipeline. [move_group-4] Link panda_link1 had 1 children [move_group-4] Link panda_link2 had 1 children [move_group-4] Link panda_link3 had 1 children [move_group-4] Link panda_link4 had 1 children [move_group-4] Link panda_link5 had 1 children [move_group-4] Link panda_link6 had 1 children [move_group-4] Link panda_link7 had 1 children [move_group-4] Link panda_link8 had 1 children [move_group-4] Link panda_hand had 2 children [move_group-4] Link panda_leftfinger had 0 children [move_group-4] Link panda_rightfinger had 0 children [move_group-4] [INFO] [1636509659.036614206] [moveit.ompl_planning.model_based_planning_context]: Planner configuration 'panda_arm' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed. [move_group-4] [INFO] [1636509659.036734764] [moveit.ompl_planning.model_based_planning_context]: panda_arm: Allocating specialized state sampler for state space [move_group-4] [INFO] [1636509659.036766432] [ompl]: /tmp/binarydeb/ros-foxy-ompl-1.5.0/src/ompl/geometric/planners/rrt/src/RRTConnect.cpp:220 - panda_arm/panda_arm: Starting planning with 1 states already in datastructure [move_group-4] [INFO] [1636509659.206169818] [ompl]: /tmp/binarydeb/ros-foxy-ompl-1.5.0/src/ompl/geometric/planners/rrt/src/RRTConnect.cpp:354 - panda_arm/panda_arm: Created 5 states (3 start + 2 goal) [move_group-4] [INFO] [1636509659.206187701] [ompl]: /tmp/binarydeb/ros-foxy-ompl-1.5.0/src/ompl/geometric/src/SimpleSetup.cpp:138 - Solution found in 0.169517 seconds [move_group-4] [INFO] [1636509659.243564420] [ompl]: /tmp/binarydeb/ros-foxy-ompl-1.5.0/src/ompl/geometric/src/SimpleSetup.cpp:179 - SimpleSetup: Path simplification took 0.037354 seconds and changed from 3 to 2 states [move_group-4] [INFO] [1636509659.249893866] [moveit_move_group_default_capabilities.move_action_capability]: Motion plan was computed succesfully. [move_group-4] [INFO] [1636509663.509775690] [moveit_move_group_default_capabilities.cartersian_path_service_capability]: Received request to compute Cartesian path [move_group-4] [INFO] [1636509663.509985139] [moveit_move_group_default_capabilities.cartersian_path_service_capability]: Attempting to follow 4 waypoints for link 'panda_link8' using a step of 0.010000 m and jump threshold 0.000000 (in global reference frame) [move_group-4] [INFO] [1636509663.516020516] [moveit_move_group_default_capabilities.cartersian_path_service_capability]: Computed Cartesian path with 77 points (followed 100.000000% of requested trajectory) [move_group-4] [INFO] [1636509668.318320322] [moveit_move_group_default_capabilities.move_action_capability]: Received request

[move_group-4] [INFO] [1636509668.418275750] [moveit_move_group_default_capabilities.move_action_capability]: Planning request received for MoveGroup action. Forwarding to planning pipeline. [move_group-4] [INFO] [1636509668.418410229] [moveit_collision_detection_fcl.collision_common]: Found a contact between 'panda_link5' (type 'Robot link') and 'panda_link7' (type 'Robot link'), which constitutes a collision. Contact information is not stored. [move_group-4] [INFO] [1636509668.418423186] [moveit_collision_detection_fcl.collision_common]: Collision checking is considered complete (collision was found and 0 contacts are stored) [move_group-4] [INFO] [1636509668.418428093] [moveit_ros.fix_start_state_collision]: Start state appears to be in collision with respect to group panda_arm [move_group-4] [WARN] [1636509668.426758707] [moveit_ros.fix_start_state_collision]: Unable to find a valid state nearby the start state (using jiggle fraction of 0.020000 and 100 sampling attempts). Passing the original planning request to the planner. [move_group-4] [INFO] [1636509668.426945844] [moveit.ompl_planning.model_based_planning_context]: Planner configuration 'panda_arm' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed. [move_group-4] [WARN] [1636509668.427014708] [ompl]: /tmp/binarydeb/ros-foxy-ompl-1.5.0/src/ompl/base/src/Planner.cpp:257 - panda_arm/panda_arm: Skipping invalid start state (invalid state) [move_group-4] [ERROR] [1636509668.427027885] [ompl]: /tmp/binarydeb/ros-foxy-ompl-1.5.0/src/ompl/geometric/planners/rrt/src/RRTConnect.cpp:207 - panda_arm/panda_arm: Motion planning start tree could not be initialized! [move_group-4] [INFO] [1636509668.427031785] [ompl]: /tmp/binarydeb/ros-foxy-ompl-1.5.0/src/ompl/geometric/src/SimpleSetup.cpp:140 - No solution found after 0.000034 seconds [move_group-4] [INFO] [1636509668.428202425] [moveit.ompl_planning.model_based_planning_context]: Unable to solve the planning problem [move_group-4] [INFO] [1636509668.428232603] [moveit_move_group_default_capabilities.move_action_capability]: No motion plan found. No execution attempted. [move_group-4] [INFO] [1636509680.675224498] [moveit_move_group_default_capabilities.move_action_capability]: Received request

[move_group-4] [INFO] [1636509680.719055164] [moveit_move_group_default_capabilities.move_action_capability]: Planning request received for MoveGroup action. Forwarding to planning pipeline. [move_group-4] [INFO] [1636509680.719698778] [moveit_collision_detection_fcl.collision_common]: Found a contact between 'panda_link5' (type 'Robot link') and 'panda_link7' (type 'Robot link'), which constitutes a collision. Contact information is not stored. [move_group-4] [INFO] [1636509680.719770800] [moveit_collision_detection_fcl.collision_common]: Collision checking is considered complete (collision was found and 0 contacts are stored) [move_group-4] [INFO] [1636509680.719795176] [moveit_ros.fix_start_state_collision]: Start state appears to be in collision with respect to group panda_arm [move_group-4] [WARN] [1636509680.745477611] [moveit_ros.fix_start_state_collision]: Unable to find a valid state nearby the start state (using jiggle fraction of 0.020000 and 100 sampling attempts). Passing the original planning request to the planner. [move_group-4] [INFO] [1636509680.745815267] [moveit.ompl_planning.model_based_planning_context]: Planner configuration 'panda_arm' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed. [move_group-4] [WARN] [1636509680.745951799] [ompl]: /tmp/binarydeb/ros-foxy-ompl-1.5.0/src/ompl/base/src/Planner.cpp:257 - panda_arm/panda_arm: Skipping invalid start state (invalid state) [move_group-4] [ERROR] [1636509680.745980741] [ompl]: /tmp/binarydeb/ros-foxy-ompl-1.5.0/src/ompl/geometric/planners/rrt/src/RRTConnect.cpp:207 - panda_arm/panda_arm: Motion planning start tree could not be initialized! [move_group-4] [INFO] [1636509680.745989714] [ompl]: /tmp/binarydeb/ros-foxy-ompl-1.5.0/src/ompl/geometric/src/SimpleSetup.cpp:140 - No solution found after 0.000073 seconds [move_group-4] [WARN] [1636509680.755891279] [ompl]: /tmp/binarydeb/ros-foxy-ompl-1.5.0/src/ompl/base/goals/src/GoalLazySamples.cpp:129 - Goal sampling thread never did any work. [move_group-4] [INFO] [1636509680.755954415] [moveit.ompl_planning.model_based_planning_context]: Unable to solve the planning problem [move_group-4] [INFO] [1636509680.756004835] [moveit_move_group_default_capabilities.move_action_capability]: No motion plan found. No execution attempted. [move_group-4] [INFO] [1636509689.427233518] [moveit_move_group_default_capabilities.move_action_capability]: Received request

[move_group-4] [INFO] [1636509689.518140063] [moveit_move_group_default_capabilities.move_action_capability]: Planning request received for MoveGroup action. Forwarding to planning pipeline. [move_group-4] [INFO] [1636509689.550356556] [moveit_collision_detection_fcl.collision_common]: Found a contact between 'panda_link4' (type 'Robot link') and 'cylinder1' (type 'Robot attached'), which constitutes a collision. Contact information is not stored. [move_group-4] [INFO] [1636509689.550378908] [moveit_collision_detection_fcl.collision_common]: Collision checking is considered complete (collision was found and 0 contacts are stored) [move_group-4] [INFO] [1636509689.550384421] [moveit_ros.fix_start_state_collision]: Start state appears to be in collision with respect to group panda_arm [move_group-4] [WARN] [1636509689.556755425] [moveit_ros.fix_start_state_collision]: Unable to find a valid state nearby the start state (using jiggle fraction of 0.020000 and 100 sampling attempts). Passing the original planning request to the planner. [move_group-4] [INFO] [1636509689.556990043] [moveit.ompl_planning.model_based_planning_context]: Planner configuration 'panda_arm' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed. [move_group-4] [WARN] [1636509689.557077232] [ompl]: /tmp/binarydeb/ros-foxy-ompl-1.5.0/src/ompl/base/src/Planner.cpp:257 - panda_arm/panda_arm: Skipping invalid start state (invalid state) [move_group-4] [ERROR] [1636509689.557093725] [ompl]: /tmp/binarydeb/ros-foxy-ompl-1.5.0/src/ompl/geometric/planners/rrt/src/RRTConnect.cpp:207 - panda_arm/panda_arm: Motion planning start tree could not be initialized! [move_group-4] [INFO] [1636509689.557098048] [ompl]: /tmp/binarydeb/ros-foxy-ompl-1.5.0/src/ompl/geometric/src/SimpleSetup.cpp:140 - No solution found after 0.000045 seconds [move_group-4] [WARN] [1636509689.567090437] [ompl]: /tmp/binarydeb/ros-foxy-ompl-1.5.0/src/ompl/base/goals/src/GoalLazySamples.cpp:129 - Goal sampling thread never did any work. [move_group-4] [INFO] [1636509689.567168646] [moveit.ompl_planning.model_based_planning_context]: Unable to solve the planning problem [move_group-4] [INFO] [1636509689.567197535] [moveit_move_group_default_capabilities.move_action_capability]: No motion plan found. No execution attempted.

https://user-images.githubusercontent.com/92976030/141037537-5f11a83f-f553-441c-9792-cbf36243c82f.mp4

vatanaksoytezer commented 2 years ago

Unfortunately I can't reproduce this.

Though from the video I can see that the arm is not positioned correctly but instead starting from its default position. Normally the arm should look like the following in the start position:

image

I am guessing something wrong with ros2_control packages but I would need to see the logs before [move_group-4] You can start planning now! as well. If the logs are too long for your shell, you can redirect the logs to a file with the following command:

ros2 launch moveit2_tutorials move_group.launch.py > log.txt

and send the file so we can have a look.

mengyin98 commented 2 years ago

Unfortunately I can't reproduce this.

Though from the video I can see that the arm is not positioned correctly but instead starting from its default position. Normally the arm should look like the following in the start position:

image

I am guessing something wrong with ros2_control packages but I would need to see the logs before [move_group-4] You can start planning now! as well. If the logs are too long for your shell, you can redirect the logs to a file with the following command:

ros2 launch moveit2_tutorials move_group.launch.py > log.txt

and send the file so we can have a look.

Thanks again, I will upload the log.txt
log.txt

Meanwhile, I use "colcon build --packages-select move_group_interface_tutorial" in package move_group_interface(~/moveit2/src/moveit2_tutorials/doc) to see if there are some problems, turns out there are a lot of errors, I look up it in the internet and seems it is because something wrong with DLL. I am not sure. (This problem has been solved, I put details at the last )

Here are the logs when I build this package.

~/moveit2/src/moveit2_tutorials/doc$ colcon build --packages-select move_group_interface_tutorial Starting >>> move_group_interface_tutorial --- stderr: move_group_interface_tutorial
/usr/bin/ld: CMakeFiles/move_group_interface_tutorial.dir/src/move_group_interface_tutorial.cpp.o: in function main': move_group_interface_tutorial.cpp:(.text+0x41d): undefined reference tomoveit::planning_interface::MoveGroupInterface::MoveGroupInterface(std::shared_ptr const&, std::cxx11::basic_string<char, std::char_traits, std::allocator > const&, std::shared_ptr const&, rclcpp::Duration const&)' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x485): undefined reference to `moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterface(std::cxx11::basic_string<char, std::char_traits, std::allocator > const&, bool)' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x4c8): undefined reference to moveit::planning_interface::MoveGroupInterface::getCurrentState(double) const' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x515): undefined reference tomoveit::planning_interface::MoveGroupInterface::getRobotModel() const' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x7ca): undefined reference to moveit::planning_interface::MoveGroupInterface::getPlanningFrame[abi:cxx11]() const' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x912): undefined reference tomoveit::planning_interface::MoveGroupInterface::getEndEffectorLink[abi:cxx11]() const' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0xab8): undefined reference to moveit::planning_interface::MoveGroupInterface::getJointModelGroupNames[abi:cxx11]() const' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0xad2): undefined reference tomoveit::planning_interface::MoveGroupInterface::getJointModelGroupNames[abi:cxx11]() const' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0xbfc): undefined reference to moveit::planning_interface::MoveGroupInterface::setPoseTarget(geometry_msgs::msg::Pose_<std::allocator<void> > const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&)' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0xc42): undefined reference tomoveit::planning_interface::MoveGroupInterface::plan(moveit::planning_interface::MoveGroupInterface::Plan&)' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x1099): undefined reference to moveit::planning_interface::MoveGroupInterface::getCurrentState(double) const' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x110c): undefined reference tomoveit::planning_interface::MoveGroupInterface::setJointValueTarget(std::vector<double, std::allocator > const&)' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x1127): undefined reference to moveit::planning_interface::MoveGroupInterface::setMaxVelocityScalingFactor(double)' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x1142): undefined reference tomoveit::planning_interface::MoveGroupInterface::setMaxAccelerationScalingFactor(double)' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x115b): undefined reference to moveit::planning_interface::MoveGroupInterface::plan(moveit::planning_interface::MoveGroupInterface::Plan&)' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x14d2): undefined reference tomoveit::planning_interface::MoveGroupInterface::setPathConstraints(moveitmsgs::msg::Constraints<std::allocator > const&)' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x14f7): undefined reference to moveit::planning_interface::MoveGroupInterface::getCurrentState(double) const' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x1622): undefined reference tomoveit::planning_interface::MoveGroupInterface::setStartState(moveit::core::RobotState const&)' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x166e): undefined reference to moveit::planning_interface::MoveGroupInterface::setPoseTarget(geometry_msgs::msg::Pose_<std::allocator<void> > const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&)' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x16a7): undefined reference tomoveit::planning_interface::MoveGroupInterface::setPlanningTime(double)' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x16c0): undefined reference to moveit::planning_interface::MoveGroupInterface::plan(moveit::planning_interface::MoveGroupInterface::Plan&)' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x1a48): undefined reference tomoveit::planning_interface::MoveGroupInterface::clearPathConstraints()' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x1c11): undefined reference to moveit::planning_interface::MoveGroupInterface::computeCartesianPath(std::vector<geometry_msgs::msg::Pose_<std::allocator<void> >, std::allocator<geometry_msgs::msg::Pose_<std::allocator<void> > > > const&, double, double, moveit_msgs::msg::RobotTrajectory_<std::allocator<void> >&, bool, moveit_msgs::msg::MoveItErrorCodes_<std::allocator<void> >*)' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x1fc8): undefined reference tomoveit::planning_interface::MoveGroupInterface::getCurrentState(double) const' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x1fec): undefined reference to moveit::planning_interface::MoveGroupInterface::setStartState(moveit::core::RobotState const&)' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x20a3): undefined reference tomoveit::planning_interface::MoveGroupInterface::setPoseTarget(geometrymsgs::msg::Pose<std::allocator > const&, std::cxx11::basic_string<char, std::char_traits, std::allocator > const&)' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x20da): undefined reference to moveit::planning_interface::MoveGroupInterface::plan(moveit::planning_interface::MoveGroupInterface::Plan&)' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x2404): undefined reference tomoveit::planning_interface::MoveGroupInterface::getPlanningFrame[abi:cxx11]() const' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x2710): undefined reference to moveit::planning_interface::PlanningSceneInterface::addCollisionObjects(std::vector<moveit_msgs::msg::CollisionObject_<std::allocator<void> >, std::allocator<moveit_msgs::msg::CollisionObject_<std::allocator<void> > > > const&, std::vector<moveit_msgs::msg::ObjectColor_<std::allocator<void> >, std::allocator<moveit_msgs::msg::ObjectColor_<std::allocator<void> > > > const&) const' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x2822): undefined reference tomoveit::planning_interface::MoveGroupInterface::plan(moveit::planning_interface::MoveGroupInterface::Plan&)' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x2b60): undefined reference to moveit::planning_interface::MoveGroupInterface::getEndEffectorLink[abi:cxx11]() const' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x2c0d): undefined reference tomoveit::planning_interface::PlanningSceneInterface::applyCollisionObject(moveitmsgs::msg::CollisionObject<std::allocator > const&)' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x2e61): undefined reference to `moveit::planning_interface::MoveGroupInterface::attachObject(std::cxx11::basic_string<char, std::char_traits, std::allocator > const&, std::cxx11::basic_string<char, std::char_traits, std::allocator > const&, std::vector<std::cxx11::basic_string<char, std::char_traits, std::allocator >, std::allocator<std::__cxx11::basic_string<char, std::char_traits, std::allocator > > > const&)' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x2f78): undefined reference to moveit::planning_interface::MoveGroupInterface::setStartStateToCurrentState()' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x2f91): undefined reference tomoveit::planning_interface::MoveGroupInterface::plan(moveit::planning_interface::MoveGroupInterface::Plan&)' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x32e7): undefined reference to moveit::planning_interface::MoveGroupInterface::detachObject(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&)' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x356d): undefined reference tomoveit::planning_interface::PlanningSceneInterface::removeCollisionObjects(std::vector<std::cxx11::basic_string<char, std::char_traits, std::allocator >, std::allocator<std::cxx11::basic_string<char, std::char_traits, std::allocator > > > const&) const' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x37ff): undefined reference to moveit::planning_interface::PlanningSceneInterface::~PlanningSceneInterface()' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x380e): undefined reference tomoveit::planning_interface::MoveGroupInterface::~MoveGroupInterface()' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x4303): undefined reference to moveit::planning_interface::PlanningSceneInterface::~PlanningSceneInterface()' /usr/bin/ld: move_group_interface_tutorial.cpp:(.text+0x4312): undefined reference tomoveit::planning_interface::MoveGroupInterface::~MoveGroupInterface()' collect2: error: ld returned 1 exit status make[2]: [CMakeFiles/move_group_interface_tutorial.dir/build.make:431:move_group_interface_tutorial] 错误 1 make[1]: [CMakeFiles/Makefile2:78:CMakeFiles/move_group_interface_tutorial.dir/all] 错误 2 make: *** [Makefile:141:all] 错误 2

Failed <<< move_group_interface_tutorial [23.0s, exited with code 2]

Summary: 0 packages finished [23.1s] 1 package failed: move_group_interface_tutorial 1 package had stderr output: move_group_interface_tutorial

I am glad to see this problem has been solved, the problem is in the cmakelist.txt

afterI add some lines in it, it can be built. the crucial step is the line below.

ament_target_dependencies(move_group_interface_tutorial moveit_ros_planning_interface)

then the package can be successfully built. the full cmakelist.txt is uploaded CMakeLists.txt

However the robot arm still can't move and start at default position. the new log of the shell is also uolpaded 1_log.txt

RoboHack04 commented 2 years ago

@mengyin98 I am not sure if you are still looking for an answer, but for anyone who is facing similar issue.....the reason is with the initial_position xml used in ros2_control. This can be found in "panda.ros2_control.xacro" file of your panda_moveit_config package.

You have to change the xml format to -

<param name="initial_position">${initial_positions['panda_joint1']}</param>

Also check this link. Hopefully this solves your problem.