[neotic-moveit] 子坐标系框架 Subframes

Subframes — moveit_tutorials Noetic documentation (ros-planning.github.io)https://ros-planning.github.io/moveit_tutorials/doc/subframes/subframes_tutorial.html

子框架是在 CollisionObjects 上定义的框架坐标系。 它们可用于定义放置在场景中的对象上的兴趣点,例如瓶子的开口、螺丝刀的尖端或螺丝头。 它们可用于规划和编写机器人指令,例如“拿起瓶子,然后移动水龙头出水口下方的开口”,或“拿起螺丝刀,然后将其放在螺丝头上方”。、

编写专注于机器人操作对象的代码不仅更具可读性,而且在机器人之间更健壮和可移植。 本教程向您展示如何在碰撞对象上定义子帧,将它们发布到规划场景并使用它们来规划运动,因此您可以执行以下操作:

../../_images/subframes_tutorial_cylinder_demo.gif

// ROS
#include <ros/ros.h>

// MoveIt
#include <moveit/planning_scene_interface/planning_scene_interface.h>
#include <moveit/planning_scene_monitor/planning_scene_monitor.h>
#include <moveit/move_group_interface/move_group_interface.h>

// TF2
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <tf2_eigen/tf2_eigen.h>

// 圆常数 tau = 2*pi。 一 tau 是一圈弧度。
const double tau = 2 * M_PI;

// BEGIN_SUB_TUTORIAL plan1
//
// Creating the planning request
// ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
// 在本教程中,我们使用一个小的辅助函数来创建我们的规划请求并移动机器人。
bool moveToCartPose(const geometry_msgs::PoseStamped& pose, moveit::planning_interface::MoveGroupInterface& group,
                    const std::string& end_effector_link)
{
  // 要在规划中使用附加到机器人的对象的子框架,您需要将您的 move_group 的末端执行器设置为对象的子框架。 
  //格式必须是“object_name/subframe_name”,如“*Example 1*”行所示。
  // 不要忘记在分离对象时将 end_effector_link 重置为机器人连杆,并且子框架不再是机器人的一部分!
  group.clearPoseTargets();  //规划组清空位姿目标
  group.setEndEffectorLink(end_effector_link); //设置末端执行器连杆
  /*
  group.setEndEffectorLink("cylinder/tip");    // Example 1
  group.setEndEffectorLink("panda_hand");      // Example 2
  */
  group.setStartStateToCurrentState(); //设置起始状态为当前状态
  group.setPoseTarget(pose);//设置目标位姿

  // The rest of the planning is done as usual. Naturally, you can also use the ``go()`` command instead of
  // ``plan()`` and ``execute()``.其余的规划照常完成。 当然,您也可以使用“go()”命令代替“plan()”和“execute()”。 
  ROS_INFO_STREAM("Planning motion to pose:"); //规划到一个位姿的运动
  ROS_INFO_STREAM(pose.pose.position.x << ", " << pose.pose.position.y << ", " << pose.pose.position.z);//输出目标位置
  moveit::planning_interface::MoveGroupInterface::Plan myplan; //规划结果
  if (group.plan(myplan) && group.execute(myplan)) //规划并执行
    return true;

  ROS_WARN("Failed to perform motion.");//警告:执行运动失败
  return false;
}
// END_SUB_TUTORIAL

// BEGIN_SUB_TUTORIAL object1
//
// Defining two CollisionObjects with subframes用子框架定义两个 CollisionObjects
// ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
//这个辅助函数创建两个对象并将它们发布到 PlanningScene:一个盒子和一个圆柱体。
// 盒子在抓手的前面生成,在抓手尖端的圆柱体,就好像它被抓住了一样。

void spawnCollisionObjects(moveit::planning_interface::PlanningSceneInterface& planning_scene_interface)
{
  double z_offset_box = .25;  // The z-axis points away from the gripper
  double z_offset_cylinder = .1;

  // 首先,我们开始像往常一样定义 `CollisionObject <http://docs.ros.org/api/moveit_msgs/html/msg/CollisionObject.html>`_。
  moveit_msgs::CollisionObject box;
  box.id = "box"; 
  box.header.frame_id = "panda_hand";
  box.primitives.resize(1);//图元数量1个
  box.primitive_poses.resize(1);//图元位姿1个
  box.primitives[0].type = box.primitives[0].BOX;
  box.primitives[0].dimensions.resize(3);//尺度 x,y,z
  box.primitives[0].dimensions[0] = 0.05;
  box.primitives[0].dimensions[1] = 0.1;
  box.primitives[0].dimensions[2] = 0.02;
  box.primitive_poses[0].position.z = z_offset_box;

  // 然后,我们定义 CollisionObject 的子框架。 子框架在“frame_id”坐标系中定义,就像构成对象的形状一样。 每个子框架由名称和位姿组成。
   // 在本教程中,我们设置子框架的方向,使子框架的 z 轴指向远离对象的方向。
   // 这不是绝对必要的,但是遵循惯例会很有帮助,并且可以避免稍后在设置目标位姿的方向时出现混淆。 
  box.subframe_names.resize(5);//此函数将 %vector 的大小调整为指定数量的元素。 如果数字小于 %vector 的当前大小,则 %vector 被截断,否则附加默认构造元素。 
  box.subframe_poses.resize(5);//5个子框架
  //第一个子框架
  box.subframe_names[0] = "bottom";
  box.subframe_poses[0].position.y = -.05;
  box.subframe_poses[0].position.z = 0.0 + z_offset_box;

  tf2::Quaternion orientation;
  orientation.setRPY(tau / 4, 0, 0);  // 绕 x 轴旋转四分之一圈
  box.subframe_poses[0].orientation = tf2::toMsg(orientation);
  // END_SUB_TUTORIAL
  //第二个子框架
  box.subframe_names[1] = "top";
  box.subframe_poses[1].position.y = .05;
  box.subframe_poses[1].position.z = 0.0 + z_offset_box;
  orientation.setRPY(-tau / 4, 0, 0);
  box.subframe_poses[1].orientation = tf2::toMsg(orientation);
  //第三个子框架
  box.subframe_names[2] = "corner_1";
  box.subframe_poses[2].position.x = -.025;
  box.subframe_poses[2].position.y = -.05;
  box.subframe_poses[2].position.z = -.01 + z_offset_box;
  orientation.setRPY(tau / 4, 0, 0);
  box.subframe_poses[2].orientation = tf2::toMsg(orientation);
  //第4个子框架
  box.subframe_names[3] = "corner_2";
  box.subframe_poses[3].position.x = .025;
  box.subframe_poses[3].position.y = -.05;
  box.subframe_poses[3].position.z = -.01 + z_offset_box;
  orientation.setRPY(tau / 4, 0, 0);
  box.subframe_poses[3].orientation = tf2::toMsg(orientation);
  //第5个子框架
  box.subframe_names[4] = "side";
  box.subframe_poses[4].position.x = .0;
  box.subframe_poses[4].position.y = .0;
  box.subframe_poses[4].position.z = -.01 + z_offset_box;
  orientation.setRPY(0, tau / 2, 0);
  box.subframe_poses[4].orientation = tf2::toMsg(orientation);//geometry_msgs::Quaternion

  //接下来,定义圆柱体
  moveit_msgs::CollisionObject cylinder;
  cylinder.id = "cylinder";
  cylinder.header.frame_id = "panda_hand";
  cylinder.primitives.resize(1);//图元数量1个
  cylinder.primitive_poses.resize(1);//图元位姿1个
  cylinder.primitives[0].type = box.primitives[0].CYLINDER;
  cylinder.primitives[0].dimensions.resize(2);//尺度:高度,半径
  cylinder.primitives[0].dimensions[0] = 0.06;   // height (along x)
  cylinder.primitives[0].dimensions[1] = 0.005;  // radius
  cylinder.primitive_poses[0].position.x = 0.0;
  cylinder.primitive_poses[0].position.y = 0.0;
  cylinder.primitive_poses[0].position.z = 0.0 + z_offset_cylinder;
  orientation.setRPY(0, tau / 4, 0);
  cylinder.primitive_poses[0].orientation = tf2::toMsg(orientation);
  //圆柱体的子框架
  cylinder.subframe_poses.resize(1);//1个
  cylinder.subframe_names.resize(1);
  cylinder.subframe_names[0] = "tip";//名称tip
  cylinder.subframe_poses[0].position.x = 0.03;
  cylinder.subframe_poses[0].position.y = 0.0;
  cylinder.subframe_poses[0].position.z = 0.0 + z_offset_cylinder;
  orientation.setRPY(0, tau / 4, 0);
  cylinder.subframe_poses[0].orientation = tf2::toMsg(orientation);

  // BEGIN_SUB_TUTORIAL object2
  // 最后,对象被发布到 PlanningScene。 在本教程中,我们发布了一个盒子和一个圆柱体。
  box.operation = moveit_msgs::CollisionObject::ADD; //碰撞对象操作模式ADD
  cylinder.operation = moveit_msgs::CollisionObject::ADD;
  planning_scene_interface.applyCollisionObjects({ box, cylinder });//应用碰撞对象
}
// END_SUB_TUTORIAL
//创建箭头标记
void createArrowMarker(visualization_msgs::Marker& marker, const geometry_msgs::Pose& pose, const Eigen::Vector3d& dir,
                       int id, double scale = 0.1)
{
  marker.action = visualization_msgs::Marker::ADD;//添加操作
  marker.type = visualization_msgs::Marker::CYLINDER;//类型:圆柱
  marker.id = id;
  marker.scale.x = 0.1 * scale;
  marker.scale.y = 0.1 * scale;
  marker.scale.z = scale;
  //标记位姿
  Eigen::Isometry3d pose_eigen;
  tf2::fromMsg(pose, pose_eigen);
  marker.pose = tf2::toMsg(pose_eigen * Eigen::Translation3d(dir * (0.5 * scale)) *
                           Eigen::Quaterniond::FromTwoVectors(Eigen::Vector3d::UnitZ(), dir));
  //标记颜色
  marker.color.r = 0.0;
  marker.color.g = 0.0;
  marker.color.b = 0.0;
  marker.color.a = 1.0;
}
//创建坐标系框架标记
void createFrameMarkers(visualization_msgs::MarkerArray& markers, const geometry_msgs::PoseStamped& target,
                        const std::string& ns, bool locked = false)
{
  int id = markers.markers.size();//标记数量   X,Y,Z轴箭头标记
  visualization_msgs::Marker m;//定义标记
  m.header.frame_id = target.header.frame_id;//目标位姿的父框架
  m.ns = ns;//标记的命名
  m.frame_locked = locked; 
  //创建箭头标记X轴
  createArrowMarker(m, target.pose, Eigen::Vector3d::UnitX(), ++id);
  m.color.r = 1.0;
  markers.markers.push_back(m);
  //创建Y轴
  createArrowMarker(m, target.pose, Eigen::Vector3d::UnitY(), ++id);
  m.color.g = 1.0;
  markers.markers.push_back(m);
  //创建Z轴
  createArrowMarker(m, target.pose, Eigen::Vector3d::UnitZ(), ++id);
  m.color.b = 1.0;
  markers.markers.push_back(m);
}

int main(int argc, char** argv)
{
  ros::init(argc, argv, "panda_arm_subframes");//节点初始化
  ros::NodeHandle nh;//节点句柄
  ros::AsyncSpinner spinner(1);//AsyncSpinner 是一个不符合抽象 Spinner 接口的微调器。 相反,它在您调用 start() 时异步旋转,
  //并在您调用 stop()、ros::shutdown() 或调用其析构函数时停止
  //AsyncSpinner 是内部引用计数,因此如果您复制一个,它将继续旋转,直到所有副本都已销毁(或在其中一个副本上调用了 stop()) 
  spinner.start();

  moveit::planning_interface::PlanningSceneInterface planning_scene_interface;//规划场景接口
  moveit::planning_interface::MoveGroupInterface group("panda_arm");//运动规划组接口
  group.setPlanningTime(10.0);//规划时间设置

  // BEGIN_SUB_TUTORIAL sceneprep
  // 准备场景
  // ^^^^^^^^^^^^^^^^^^^
  //在主函数中,我们首先在规划场景中生成对象,然后将圆柱体附加到机器人上。
   // 附着圆柱体在 Rviz 中将其变为紫色。
  spawnCollisionObjects(planning_scene_interface); //在规划场景中产生碰撞对象
  moveit_msgs::AttachedCollisionObject att_coll_object; //附着碰撞对象 消息
  att_coll_object.object.id = "cylinder";//附着碰撞对象id: 圆柱体 
  att_coll_object.link_name = "panda_hand";//附着碰撞对象的连杆名:panda_hand
  att_coll_object.object.operation = att_coll_object.object.ADD;//附着碰撞对象的操作方式:ADD
  ROS_INFO_STREAM("Attaching cylinder to robot.");//附着圆柱体到机器人……
  planning_scene_interface.applyAttachedCollisionObject(att_coll_object);//应用附着碰撞对象
  // END_SUB_TUTORIAL

  // 获取当前规划场景状态一次
  auto planning_scene_monitor = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>("robot_description");//规划场景监视器共享指针
  planning_scene_monitor->requestPlanningSceneState();//规划场景监视器->请求规划场景状态
  //这是一个方便的类,用于获取对锁定的 PlanningScene 实例的访问权限。
  //由于类型转换运算符和“operator->”函数,此类的实例几乎可以像 PlanningScenePtr 的实例一样使用。 因此你会经常看到这样的代码:
  // *   planning_scene_monitor::LockedPlanningSceneRO ls(planning_scene_monitor);
  //*   moveit::core::RobotModelConstPtr model = ls->getRobotModel();
  planning_scene_monitor::LockedPlanningSceneRO planning_scene(planning_scene_monitor);

  // 将框架可视化为 rviz 标记
  /*广播主题,简单版
  此调用连接到主节点以广播该节点将在给定主题上发布消息。 此方法返回一个发布者,允许您发布有关此主题的消息。
  这个版本的广播是一个模板化的便利功能,可以像这样使用
   ros::Publisher pub = handle.advertise<std_msgs::Empty>("my_topic", 1);*/
  ros::Publisher marker_publisher = nh.advertise<visualization_msgs::MarkerArray>("visualization_marker_array", 10);
  //
  auto showFrames = [&](geometry_msgs::PoseStamped target, const std::string& eef) {
    visualization_msgs::MarkerArray markers;//标记数组
    // 将目标位姿转换为规划框架
    Eigen::Isometry3d tf;//target.pose为相对父坐标系的位姿
    tf2::fromMsg(target.pose, tf);//将姿势消息变换类型转换为Eigen Isometry3d。 此函数是 tf2/convert.h 中定义的 toMsg 模板的特化。
    target.pose = tf2::toMsg(planning_scene->getFrameTransform(target.header.frame_id) * tf);//转换为相对world的位姿
    target.header.frame_id = planning_scene->getPlanningFrame();//获取执行规划的框架坐标系
    createFrameMarkers(markers, target, "target");//创建标记

    // convert eef in pose relative to panda_hand将 eef 转换为相对于 panda_hand 的位姿
    target.header.frame_id = "panda_hand";//父框架设置为panda_hand
    target.pose = tf2::toMsg(planning_scene->getFrameTransform(target.header.frame_id).inverse() *
                             planning_scene->getFrameTransform(eef));//计算eef坐标框架相对panda_hand坐标框架的位姿矩阵
    createFrameMarkers(markers, target, "eef", true);//创建eef标记

    marker_publisher.publish(markers);//发布标记数组
  };

  // 在机器人底座中定义一个位姿。
  tf2::Quaternion target_orientation;//目标四元数
  geometry_msgs::PoseStamped fixed_pose, target_pose;//位姿消息:固定位姿,目标位姿
  fixed_pose.header.frame_id = "panda_link0"; //父坐标系panda_link0
  fixed_pose.pose.position.y = -.4;
  fixed_pose.pose.position.z = .3;
  target_orientation.setRPY(0, (-20.0 / 360.0 * tau), 0);
  fixed_pose.pose.orientation = tf2::toMsg(target_orientation);

  // 设置一个小的命令行界面以使教程具有交互性。
  int character_input;
  while (ros::ok())
  {
    ROS_INFO("==========================\n"
             "Press a key and hit Enter to execute an action. \n0 to exit"
             "\n1 to move cylinder tip to box bottom \n2 to move cylinder tip to box top"
             "\n3 to move cylinder tip to box corner 1 \n4 to move cylinder tip to box corner 2"
             "\n5 to move cylinder tip to side of box"
             "\n6 to return the robot to the start pose"
             "\n7 to move the robot's wrist to a cartesian pose"
             "\n8 to move cylinder/tip to the same cartesian pose"
             "\n----------"
             "\n10 to remove box and cylinder from the scene"
             "\n11 to spawn box and cylinder"
             "\n12 to attach the cylinder to the gripper\n");
    std::cin >> character_input;
    if (character_input == 0)
    {
      return 0;
    }
    else if (character_input == 1)
    {
      ROS_INFO_STREAM("Moving to bottom of box with cylinder tip");

      // BEGIN_SUB_TUTORIAL orientation
      // Setting the orientation
      // ^^^^^^^^^^^^^^^^^^^^^^^
      // The target pose is given relative to a box subframe:
      target_pose.header.frame_id = "box/bottom"; //目标位姿 父坐标系:盒子底部子框架
      // The orientation is determined by RPY angles to align the cylinder and box subframes:
      //方向由 RPY 角度确定,以对齐圆柱 和 盒子子框架:
      target_orientation.setRPY(0, tau / 2, tau / 4);
      target_pose.pose.orientation = tf2::toMsg(target_orientation);
      // 为了与盒子保持一定的距离,我们使用了一个小的偏移量:
      target_pose.pose.position.z = 0.01;
      showFrames(target_pose, "cylinder/tip");
      moveToCartPose(target_pose, group, "cylinder/tip");
      // END_SUB_TUTORIAL
    }
    // BEGIN_SUB_TUTORIAL move_example
    // The command "2" moves the cylinder tip to the top of the box (the right side in the top animation).
    //命令“2”将圆柱体tip移动到box的顶部(顶部动画中的右侧)。
    else if (character_input == 2)
    {
      ROS_INFO_STREAM("Moving to top of box with cylinder tip");
      target_pose.header.frame_id = "box/top";
      target_orientation.setRPY(tau / 2, 0, tau / 4);
      target_pose.pose.orientation = tf2::toMsg(target_orientation);
      target_pose.pose.position.z = 0.01;
      showFrames(target_pose, "cylinder/tip");
      moveToCartPose(target_pose, group, "cylinder/tip");
    }
    // END_SUB_TUTORIAL
    else if (character_input == 3)
    {
      ROS_INFO_STREAM("Moving to corner1 of box with cylinder tip");
      target_pose.header.frame_id = "box/corner_1";
      target_orientation.setRPY(0, tau / 2, tau / 4);
      target_pose.pose.orientation = tf2::toMsg(target_orientation);
      target_pose.pose.position.z = 0.01;
      showFrames(target_pose, "cylinder/tip");
      moveToCartPose(target_pose, group, "cylinder/tip");
    }
    else if (character_input == 4)
    {
      target_pose.header.frame_id = "box/corner_2";
      target_orientation.setRPY(0, tau / 2, tau / 4);
      target_pose.pose.orientation = tf2::toMsg(target_orientation);
      target_pose.pose.position.z = 0.01;
      showFrames(target_pose, "cylinder/tip");
      moveToCartPose(target_pose, group, "cylinder/tip");
    }
    else if (character_input == 5)
    {
      target_pose.header.frame_id = "box/side";
      target_orientation.setRPY(0, tau / 2, tau / 4);
      target_pose.pose.orientation = tf2::toMsg(target_orientation);
      target_pose.pose.position.z = 0.01;
      showFrames(target_pose, "cylinder/tip");
      moveToCartPose(target_pose, group, "cylinder/tip");
    }
    else if (character_input == 6)
    {
      // Go to neutral home pose
      group.clearPoseTargets();
      group.setNamedTarget("ready");
      group.move();
    }
    else if (character_input == 7)
    {
      ROS_INFO_STREAM("Moving to a pose with robot wrist");
      showFrames(fixed_pose, "panda_hand");
      moveToCartPose(fixed_pose, group, "panda_hand");
    }
    else if (character_input == 8)
    {
      ROS_INFO_STREAM("Moving to a pose with cylinder tip");
      showFrames(fixed_pose, "cylinder/tip");
      moveToCartPose(fixed_pose, group, "cylinder/tip");
    }
    else if (character_input == 10)
    {
      try
      {
        ROS_INFO_STREAM("Removing box and cylinder.");
        moveit_msgs::AttachedCollisionObject att_coll_object;
        att_coll_object.object.id = "box";
        att_coll_object.object.operation = att_coll_object.object.REMOVE;
        planning_scene_interface.applyAttachedCollisionObject(att_coll_object);

        att_coll_object.object.id = "cylinder";
        att_coll_object.object.operation = att_coll_object.object.REMOVE;
        planning_scene_interface.applyAttachedCollisionObject(att_coll_object);

        moveit_msgs::CollisionObject co1, co2;
        co1.id = "box";
        co1.operation = moveit_msgs::CollisionObject::REMOVE;
        co2.id = "cylinder";
        co2.operation = moveit_msgs::CollisionObject::REMOVE;
        planning_scene_interface.applyCollisionObjects({ co1, co2 });
      }
      catch (const std::exception& exc)
      {
        ROS_WARN_STREAM(exc.what());
      }
    }
    else if (character_input == 11)
    {
      ROS_INFO_STREAM("Respawning test box and cylinder.");
      spawnCollisionObjects(planning_scene_interface);
    }
    else if (character_input == 12)
    {
      moveit_msgs::AttachedCollisionObject att_coll_object;
      att_coll_object.object.id = "cylinder";
      att_coll_object.link_name = "panda_hand";
      att_coll_object.object.operation = att_coll_object.object.ADD;
      ROS_INFO_STREAM("Attaching cylinder to robot.");
      planning_scene_interface.applyAttachedCollisionObject(att_coll_object);
    }
    else
    {
      ROS_INFO("Could not read input. Quitting.");
      break;
    }
  }

  ros::waitForShutdown();
  return 0;
}

// BEGIN_TUTORIAL
// CALL_SUB_TUTORIAL object1
// CALL_SUB_TUTORIAL object2
// CALL_SUB_TUTORIAL plan1
//
// CALL_SUB_TUTORIAL sceneprep
// 交互式测试机器人
// ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
// 我们设置了一个小的命令行界面,以便您可以与模拟交互并查看它如何响应某些
// 命令。 当您移除盒子和圆柱体,重生时,您可以使用它来试验机器人的行为
// 并重新附加它们,或创建新的计划请求。 尝试将机器人移动到新位置并重新生成盒子
// 和圆柱体(它们是相对于机器人手腕产生的)。
// 或者尝试命令 7 和 8 将不同的帧移动到空间中的相同位置。
// CALL_SUB_TUTORIAL move_example
//
// CALL_SUB_TUTORIAL orientation
//
// END_TUTORIAL

Running The Demo

完成入门中的步骤后,打开两个终端。 在第一个终端中,执行此命令加载一个panda,并等待一切完成加载:

roslaunch panda_moveit_config demo.launch

<launch>

  <!-- 默认情况下,我们不启动数据库(它可以很大) -->
  <arg name="db" default="false" />
  <!--允许用户指定数据库位置 -->
  <arg name="db_path" default="$(find panda_moveit_config)/default_warehouse_mongo_db" />

  <!-- 默认情况下,我们不处于调试模式 -->
  <arg name="debug" default="false" />
  <arg name="pipeline" default="ompl" />

  <!--
默认情况下,隐藏joint_state_publisher 的GUI
   MoveIt! 的“demo”模式用joint_state_publisher 替换了真正的机器人驱动程序。
   后者维护并发布模拟机器人的当前关节配置。
   它还提供了一个 GUI 来“手动”移动模拟机器人。
   这对应于在不使用 MoveIt 的情况下在真实机器人周围移动。  -->
  <arg name="rviz_tutorial" default="false" />
  <arg name="use_gui" default="false" />

  <!--在参数服务器上加载URDF、SRDF等.yaml配置文件-->
  <include file="$(find panda_moveit_config)/launch/planning_context.launch">
    <arg name="load_robot_description" value="true"/>
  </include>

  <!-- 如果需要,为机器人 robot 广播静态 tf -->
  <node pkg="tf2_ros" type="static_transform_publisher" name="virtual_joint_broadcaster_1" args="0 0 0 0 0 0 world panda_link0" />

  <!-- 我们没有连接机器人,所以发布假关节状态 -->
  <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
    <param name="/use_gui" value="$(arg use_gui)"/>
    <rosparam param="/source_list">[/move_group/fake_controller_joint_states]</rosparam>
  </node>
  <node name="joint_state_desired_publisher" pkg="topic_tools" type="relay" args="joint_states joint_states_desired" />

  <!-- 给定已发布的关节状态,为机器人连杆发布 tf -->
  <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="true" output="screen" />

  <!--在不执行轨迹的情况下运行主要的 MoveIt 可执行文件(默认情况下我们没有配置控制器) -->
  <include file="$(find panda_moveit_config)/launch/move_group.launch">
    <arg name="allow_trajectory_execution" value="true"/>
    <arg name="fake_execution" value="true"/>
    <arg name="info" value="true"/>
    <arg name="debug" value="$(arg debug)"/>
    <arg name="pipeline" value="$(arg pipeline)"  />
  </include>

  <!-- Run Rviz -->
  <include file="$(find panda_moveit_config)/launch/moveit_rviz.launch">
    <arg name="rviz_tutorial" value="$(arg rviz_tutorial)"/>
    <arg name="debug" value="$(arg debug)"/>
  </include>

  <!-- 如果启用了数据库加载,也启动 mongodb -->
  <include file="$(find panda_moveit_config)/launch/default_warehouse_db.launch" if="$(arg db)">
    <arg name="moveit_warehouse_database_path" value="$(arg db_path)"/>
  </include>

</launch>

在第二个终端中运行教程:

rosrun moveit_tutorials subframes_tutorial

<launch>
  <node name="subframes_tutorial" pkg="moveit_tutorials" type="subframes_tutorial" respawn="false" output="screen">
  </node>
</launch>

在此终端中,您应该能够输入 1-12 之间的数字来发送命令,并查看机器人和场景的反应。

 

Guess you like

Origin blog.csdn.net/cxyhjl/article/details/121381295