鱼香ROS社区
    • 版块
    • 最新
    • 未解决
    • 已解决
    • 群组
    • 注册
    • 登录
    紧急通知:禁止一切关于政治&VPN翻墙等话题,发现相关帖子会立马删除封号
    提问前必看的发帖注意事项: 社区问答规则(小鱼个人)更新 | 高质量帖子发布指南

    ros2通过moveit2控制双臂机器人

    已定时 已固定 已锁定 已移动
    ROS 2相关问题
    ros2 control moveit2
    3
    5
    707
    正在加载更多帖子
    • 从旧到新
    • 从新到旧
    • 最多赞同
    回复
    • 在新帖中回复
    登录后回复
    此主题已被删除。只有拥有主题管理权限的用户可以查看。
    • Z
      zhang_bo7
      最后由 编辑

      已经按照鱼哥教程安装好了moveit2,如图所示设置了规划组。通过程序控制both_arm规划组控制双臂运行出现规划失败情况。
      c52241f3-90d9-4800-afde-54ec277ec131-image.png
      这是我的c++程序

      #include <rclcpp/rclcpp.hpp>
      #include <moveit/moveit_cpp/moveit_cpp.h>
      #include <moveit/moveit_cpp/planning_component.h>
      #include <moveit/move_group_interface/move_group_interface.h>
      #include <geometry_msgs/msg/pose.h>
      #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
      #include <iostream>
      
      tf2::Quaternion getQuat(geometry_msgs::msg::Pose target_pose)
      {
          tf2::Quaternion targetQ;
          targetQ[0] = target_pose.orientation.x;
          targetQ[1] = target_pose.orientation.y;
          targetQ[2] = target_pose.orientation.z;
          targetQ[3] = target_pose.orientation.w;
          return targetQ;
      }
      
      
      geometry_msgs::msg::Pose pose_specify(float Xx, float Yy, float Zz, float R, float P, float Y)
      {
          geometry_msgs::msg::Pose target_pose;
          tf2::Quaternion targetQ;
      
          target_pose.position.x = Xx;
          target_pose.position.y = Yy;
          target_pose.position.z = Zz;
      
          targetQ.setRPY(R, P, Y);
          target_pose.orientation.x = targetQ.x();
          target_pose.orientation.y = targetQ.y();
          target_pose.orientation.z = targetQ.z();
          target_pose.orientation.w = targetQ.w();
      
          return target_pose;
      }
      
      bool both_arm_motion(moveit::planning_interface::MoveGroupInterface& move_group_l, moveit::planning_interface::MoveGroupInterface& move_group_r,geometry_msgs::msg::Pose& left_target_pose, geometry_msgs::msg::Pose& right_target_pose)
      {
          // Create planning component for both arms
          moveit::planning_interface::MoveGroupInterface::Plan plan_l;
          moveit::planning_interface::MoveGroupInterface::Plan plan_r;
          bool success;
          move_group_l.setStartStateToCurrentState();
          move_group_r.setStartStateToCurrentState();
          RCLCPP_INFO(rclcpp::get_logger("moveit_cpp_tutorial"), "The pose reference frame is: %s", move_group_l.getPlanningFrame().c_str());
          RCLCPP_INFO(rclcpp::get_logger("moveit_cpp_tutorial"), "The pose reference frame is: %s", move_group_r.getPlanningFrame().c_str());
          // Set the target poses
          move_group_l.setPoseTarget(left_target_pose, "er3a_end_frame");
          move_group_r.setPoseTarget(right_target_pose, "linkhou_end_frame");
      
          // Plan and execute
          do
          {
              success = ((move_group_l.plan(plan_l)&&move_group_r.plan(plan_r))== moveit::planning_interface::MoveItErrorCode::SUCCESS);
          } while (!success);
      
          move_group_l.execute(plan_l);
          move_group_r.execute(plan_r);
          return true;
      }
      
      
      bool both_arm_motion2(moveit::planning_interface::MoveGroupInterface& move_group,geometry_msgs::msg::Pose& left_target_pose, geometry_msgs::msg::Pose& right_target_pose)
      {
          // Create planning component for both arms
          moveit::planning_interface::MoveGroupInterface::Plan dual_plan;
      
          bool success;
          move_group.setStartStateToCurrentState();
      
          RCLCPP_INFO(rclcpp::get_logger("moveit_cpp_tutorial"), "The pose reference frame is: %s", move_group.getPlanningFrame().c_str());
      
          // Set the target poses
          move_group.setPoseTarget(left_target_pose, "er3a_end_frame");
          move_group.setPoseTarget(right_target_pose, "linkhou_end_frame");
      
          // Plan and execute
          do
          {
              success = (move_group.plan(dual_plan) == moveit::planning_interface::MoveItErrorCode::SUCCESS);
      
          } while (!success);
          RCLCPP_INFO(rclcpp::get_logger("moveit_cpp_tutorial"), "fuck fuck fuck fuck fuck");
          move_group.execute(dual_plan);
          return true;
      }
      
      int main(int argc, char* argv[])
      {
          // Initialize ROS
          rclcpp::init(argc, argv);
      
          // Initialize MoveIt
          auto node = std::make_shared<rclcpp::Node>("hello_moveit", rclcpp::NodeOptions().automatically_declare_parameters_from_overrides(true));
      
          rclcpp::executors::MultiThreadedExecutor executor;
          executor.add_node(node);
          //const std::string both_arm = "both_arm";
          auto move_group = moveit::planning_interface::MoveGroupInterface(node, "both_arm");
          auto move_group_l = moveit::planning_interface::MoveGroupInterface(node, "left_arm");
          auto move_group_r = moveit::planning_interface::MoveGroupInterface(node, "right_arm");
          
          move_group.allowReplanning(true);
          move_group.setNumPlanningAttempts(10);
          move_group.setMaxVelocityScalingFactor(0.8);
          move_group.setMaxAccelerationScalingFactor(0.8);
          move_group.setPoseReferenceFrame("Link_foot");
          move_group_l.setPlanningTime(5.0);  // Set planning time to 5 seconds
          move_group_r.setPlanningTime(5.0);
          move_group.setPlanningTime(5.0);
      
          move_group_l.allowReplanning(true);
          move_group_l.setNumPlanningAttempts(10);
          move_group_l.setPoseReferenceFrame("Link_foot");
      
          move_group_r.allowReplanning(true);
          move_group_r.setNumPlanningAttempts(10);
          move_group_r.setPoseReferenceFrame("Link_foot");
         // moveit::planning_interface::PlanningSceneInterface planning_scene_interface; // 添加此行
      
          // Call the both_arm_motion function
          geometry_msgs::msg::Pose left_target_pose;
          geometry_msgs::msg::Pose right_target_pose;
          geometry_msgs::msg::PoseStamped current_pose_l = move_group_l.getCurrentPose();
          geometry_msgs::msg::PoseStamped current_pose_r = move_group_r.getCurrentPose();
          RCLCPP_INFO(rclcpp::get_logger("moveit_cpp_tutorial"),"left current Pose : [%f, %f, %f, %f, %f, %f, %f]" ,
          current_pose_l.pose.position.x, current_pose_l.pose.position.y, current_pose_l.pose.position.z,
          current_pose_l.pose.orientation.x, current_pose_l.pose.orientation.y, current_pose_l.pose.orientation.z,
          current_pose_l.pose.orientation.w);
      
          RCLCPP_INFO(rclcpp::get_logger("moveit_cpp_tutorial"),"right current Pose : [%f, %f, %f, %f, %f, %f, %f]" ,
          current_pose_r.pose.position.x, current_pose_r.pose.position.y, current_pose_r.pose.position.z,
          current_pose_r.pose.orientation.x, current_pose_r.pose.orientation.y, current_pose_r.pose.orientation.z,
          current_pose_r.pose.orientation.w);
      
                                                 
          
          
          tf2::Quaternion left_rotate,right_rotate,q_rot,q_rots45,q_rotn45;
          right_target_pose = pose_specify(0.35,0.5,0.02+0.05,0,M_PI,M_PI/2);
          left_target_pose = pose_specify(0.35,0.7,0.02+0.05,0,0,-M_PI/2);
          left_rotate = getQuat(left_target_pose);
          q_rot.setRPY(-M_PI/4, 0, 0);
          left_rotate = q_rot*left_rotate;  // Calculate the new orientation
          left_rotate.normalize();
          right_rotate = getQuat(right_target_pose);
          q_rot.setRPY(M_PI/4, 0, 0);
          right_rotate = q_rot*right_rotate;  // Calculate the new orientation
          right_rotate.normalize();
          left_target_pose.orientation.x = left_rotate[0];//.70739;
          left_target_pose.orientation.y = left_rotate[1];//.70683;
          left_target_pose.orientation.z = left_rotate[2];
          left_target_pose.orientation.w = left_rotate[3];
          right_target_pose.orientation.x = right_rotate[0];//.70739;
          right_target_pose.orientation.y = right_rotate[1];//.70683;
          right_target_pose.orientation.z = right_rotate[2];
          right_target_pose.orientation.w = right_rotate[3];
      
          //both_arm_motion(move_group_l, move_group_r, left_target_pose, right_target_pose);
          both_arm_motion2(move_group, left_target_pose, right_target_pose);
          // Shutdown ROS
          rclcpp::shutdown();
      
          return 0;
      }
      
      

      目标点确定是可行的,因为我通过使用dual_arm_motion测试,即使用move_group_l和move_group_r分别控制两机械臂可以运动到设定点,但使用dual_arm_motion2,即使用move_group就会规划失败c++程序报错:

      [INFO] [1702386328.396770338] [move_group_interface]: MoveGroup action client/server ready
      [INFO] [1702386328.397073422] [move_group_interface]: Planning request accepted
      [INFO] [1702386329.511238255] [move_group_interface]: Planning request aborted
      [ERROR] [1702386329.512311632] [move_group_interface]: MoveGroupInterface::plan() failed or timeout reached
      [INFO] [1702386329.512426744] [move_group_interface]: MoveGroup action client/server ready
      [INFO] [1702386329.512875038] [move_group_interface]: Planning request accepted
      [INFO] [1702386330.642550132] [move_group_interface]: Planning request aborted
      [ERROR] [1702386330.642602329] [move_group_interface]: MoveGroupInterface::plan() failed or timeout reached
      

      另外启动的demo.launch终端报错:

      [move_group-2] [ERROR] [1702386331.682317993] [ompl]: ./src/ompl/geometric/planners/rrt/src/RRTConnect.cpp:213 - both_arm/both_arm: Insufficient states in sampleable goal region
      [move_group-2] [ERROR] [1702386331.682397145] [ompl]: ./src/ompl/geometric/planners/rrt/src/RRTConnect.cpp:213 - both_arm/both_arm: Insufficient states in sampleable goal region
      [move_group-2] [WARN] [1702386331.682453413] [ompl]: ./src/ompl/tools/multiplan/src/ParallelPlan.cpp:138 - ParallelPlan::solve(): Unable to find solution by any of the threads in 0.000423 seconds
      [move_group-2] [ERROR] [1702386331.682554129] [ompl]: ./src/ompl/geometric/planners/rrt/src/RRTConnect.cpp:213 - both_arm/both_arm: Insufficient states in sampleable goal region
      [move_group-2] [ERROR] [1702386331.682620236] [ompl]: ./src/ompl/geometric/planners/rrt/src/RRTConnect.cpp:213 - both_arm/both_arm: Insufficient states in sampleable goal region
      [move_group-2] [WARN] [1702386331.682670208] [ompl]: ./src/ompl/tools/multiplan/src/ParallelPlan.cpp:138 - ParallelPlan::solve(): Unable to find solution by any of the threads in 0.000185 seconds
      [move_group-2] [INFO] [1702386331.754546175] [moveit.ompl_planning.model_based_planning_context]: Unable to solve the planning problem
      [move_group-2] [WARN] [1702386331.754646109] [moveit.ros_planning.planning_pipeline]: More than one constraint is set. If your move_group does not have multiple end effectors/arms, this is unusual. Are you using a move_group_interface and forgetting to call clearPoseTargets() or equivalent?
      [move_group-2] [INFO] [1702386331.754712714] [moveit_move_group_default_capabilities.move_action_capability]: Catastrophic failure
      
      H Z 2 条回复 最后回复 回复 引用 0
      • H
        h18332138157 @zhang_bo7
        最后由 编辑

        @zhang_bo7 你会出现两个单臂可以规划和执行,但是双臂执行的时候就会出错吗

        1 条回复 最后回复 回复 引用 0
        • Z
          zjs1006
          最后由 编辑

          请问这个问题有解决吗?

          1 条回复 最后回复 回复 引用 0
          • Z
            zjs1006 @zhang_bo7
            最后由 编辑

            @zhang_bo7 我和你一样的情况

            1 条回复 最后回复 回复 引用 0
            • Z
              zjs1006
              最后由 编辑

              这个问题我解决了,规划失败的原因可能是设置复合规划组的目标点不能采用这种方式: move_group.setPoseTarget(left_target_pose, "er3a_end_frame");
              move_group.setPoseTarget(right_target_pose, "linkhou_end_frame");(这种应该是moveit1的设置方式)
              而是要采用下面这种方式:
              //1.构建双机械臂父规划组的控制接口
              MoveitControl panda_dual_arms_control(node,"dual_arms","world");//此时传入的规划组就是包含两个机械臂的父规划组
              //2.获取机器人模型
              moveit::core::RobotModelConstPtr robot_model = panda_dual_arms_control.move_group_->getRobotModel();
              //获取左右臂的关节组信息
              const moveit::core::JointModelGroup* right_arm_jmg = robot_model->getJointModelGroup("right_arm");
              const moveit::core::JointModelGroup* left_arm_jmg = robot_model->getJointModelGroup("left_arm");

              //3.设置左右臂的目标关节值
              std::vector<double> panda_left_arm_pos1_joint = {0.0,1.2953,1.5527,0.0175,-0.08,-0.0085,0.6243};
              std::vector<double> panda_right_arm_pos1_joint = {0.048,1.3343,1.5847,-0.2556,0.1121,0.0,0.0};

              //4.创建目标状态
              moveit::core::RobotStatePtr goal_state = std::make_sharedmoveit::core::RobotState(robot_model);
              //设置左右臂的目标关节值
              goal_state->setJointGroupPositions(right_arm_jmg, panda_right_arm_pos1_joint);
              goal_state->setJointGroupPositions(left_arm_jmg, panda_left_arm_pos1_joint);
              //5.设置目标状态并规划
              panda_dual_arms_control.move_group_->setJointValueTarget(*goal_state);
              bool success = (panda_dual_arms_control.move_group_->plan(panda_dual_arms_control.plan_path) == moveit::core::MoveItErrorCode::SUCCESS);
              //6.执行规划
              if (success)
              {
              RCLCPP_INFO(node->get_logger(), "Planning successful! Executing trajectory.");
              panda_dual_arms_control.move_group_->execute(panda_dual_arms_control.plan_path);
              }
              else
              {
              RCLCPP_ERROR(node->get_logger(), "Planning failed!");
              }
              上面是我写的代码,我通过这种方式设置目标点,就可以正常的规划出来复合规划组的路径了。

              1 条回复 最后回复 回复 引用 0
              • 第一个帖子
                最后一个帖子
              皖ICP备16016415号-7
              Powered by NodeBB | 鱼香ROS