美文网首页
MoveIt教程9 - moveit::planning_int

MoveIt教程9 - moveit::planning_int

作者: Danny_a44d | 来源:发表于2019-07-16 13:53 被阅读0次

    moveit::planning_interface::MoveGroupInterface是一个client类,对move_group的接口进行了封装。在MoveIt!编程中,通过创建该类client对象,调用接口函数对机器人进行控制。

    头文件:#include <moveit/planning_interface/move_group_interface.h>


    类成员

    内部类

    类名&介绍
    class MoveGroupInterfaceImpl
    MoveGroupInterface接口的具体实现
    struct Options
    构建对象时可选择传入Options More... 详见对应的构造函数
    struct Plan
    构造对象时可以给定一个plan More... 详见对应的构造函数

    公有函数

    返回值 函数&介绍
    const std::vector< std::string > & getActiveJoints () const
    获取move_group(规划组)中的主动关节(可以主动控制的关节)More...
    std::string getDefaultPlannerId (const std::string &group="") const
    获取当前规划组的planner,如果没有指定过,那返回的是global默认的planner More...
    double getGoalJointTolerance () const
    获取到达一个关节目标的允许的误差 More...
    double getGoalOrientationTolerance () const
    获取达到目标的orientation误差,针对roll,pitch,yaw,返回的是弧度 More...
    double getGoalPositionTolerance () const
    获取到达目标的position误差,返回double半径值,末端执行器所需到达的该半径的圆球内 More...
    bool getInterfaceDescription (moveit_msgs::PlannerInterfaceDescription &desc)
    获取action sever加载的规划插件的描述 More...
    const std::vector< std::string > & getJointNames ()
    获取当前规划组内的关节名称 More...
    const std::vector< std::string > & getJoints () const
    获取当前规划组内的关节 (包括fixed joints) More...
    const std::vector< std::string > & getLinkNames ()
    获取规当前划组内的链接名称 More...
    const std::string & getName () const
    获取当前规划组名称 More...
    const std::vector< std::string > getNamedTargets ()
    获取已命名的机器人目标状态,包括SRDF文件中定义的和程序中保存的 More...
    std::map< std::string, double > getNamedTargetValues (const std::string &name)
    获取某个命名的机器人目标状态的关节角度 More...
    const ros::NodeHandle & getNodeHandle () const
    获取ROS节点handle More...
    const std::string & getPlannerId () const
    获取当前planner ID More...
    std::map< std::string, std::string > getPlannerParams (const std::string &planner_id, const std::string &group="")
    获取planner参数 More...
    const std::string & getPlanningFrame () const
    获取当前规划基于的坐标系frame More...
    double getPlanningTime () const
    获取setPlanningTime() 设置的规划时间(秒) More...
    robot_model::RobotModelConstPtr getRobotModel () const
    获取RobotModel对象 More...
    unsigned int getVariableCount () const
    获取描述规划组状态的变量个数,大于等于自由度DOF More...
    MoveGroupInterface (const Options &opt, const boost::shared_ptr< tf::Transformer > &tf=boost::shared_ptr< tf::Transformer >(), const ros::WallDuration &wait_for_servers=ros::WallDuration())
    构造函数 More...
    MOVEIT_DEPRECATED MoveGroupInterface (const Options &opt, const boost::shared_ptr< tf::Transformer > &tf, const ros::Duration &wait_for_servers)
    构造函数 不建议使用
    MoveGroupInterface (const std::string &group, const boost::shared_ptr< tf::Transformer > &tf=boost::shared_ptr< tf::Transformer >(), const ros::WallDuration &wait_for_servers=ros::WallDuration())
    构造函数 More...
    MOVEIT_DEPRECATED MoveGroupInterface (const std::string &group, const boost::shared_ptr< tf::Transformer > &tf, const ros::Duration &wait_for_servers)
    构造函数 不建议使用
    MoveGroupInterface (const MoveGroupInterface &)=delete
    禁止使用编译器默认生成的拷贝构造函数
    MoveGroupInterface (MoveGroupInterface &&other)
    默认移动构造函数
    MOVEIT_STRUCT_FORWARD (Plan)
    详见链接
    MoveGroupInterface & operator= (const MoveGroupInterface &)=delete
    禁止使用编译器默认生成的赋值函数
    MoveGroupInterface & operator= (MoveGroupInterface &&other)
    默认拷贝函数
    void setGoalJointTolerance (double tolerance)
    设置到目标时允许的关节角度偏差 More...
    void setGoalOrientationTolerance (double tolerance)
    设置到目标姿态时允许的方向orientation偏差 More...
    void setGoalPositionTolerance (double tolerance)
    设置到目标姿态时允许的位置position偏差 More...
    void setGoalTolerance (double tolerance)
    设置到达目标允许的偏差。对于joint state goal, 为关节角度(弧度)或距离(m)偏差(根据关节的种类而定);对于pose goal,为末端执行器需到达的圆球范围的半径(m)。 内部调用了 setGoalPositionTolerance(), setGoalOrientationTolerance()setGoalJointTolerance(). More...
    void setMaxAccelerationScalingFactor (double max_acceleration_scaling_factor)
    可选)设置一个比例参数(0, 1]减小关节最大加速度。在URDF和SRDF中定义的阈值会乘以这个比例。如果传入的值超出范围(包括0.0),则内部会默认设置为1.0 More...
    void setMaxVelocityScalingFactor (double max_velocity_scaling_factor)
    可选)设置一个比例参数(0, 1]减小关节最大速度。在URDF和SRDF中定义的阈值会乘以这个比例。如果传入的值超出范围(包括0.0),则内部会默认设置为1.0 More...
    void setNumPlanningAttempts (unsigned int num_planning_attempts)
    设置规划求解次数,达到这个次数后返回最优解。默认1 More...
    void setPlannerId (const std::string &planner_id)
    设置planner More...
    void setPlannerParams (const std::string &planner_id, const std::string &group, const std::map< std::string, std::string > &params, bool bReplace=false)
    设置planner参数 More...
    void setPlanningTime (double seconds)
    设置规划最大时间 More...
    void setStartState (const moveit_msgs::RobotState &start_state)
    设置初始状态 (如需要) More...
    void setStartState (const robot_state::RobotState &start_state)
    设置初始状态 (如需要) More...
    void setStartStateToCurrentState ()
    设置初始状态(如需要),并且发布到joint state More...
    void setSupportSurfaceName (const std::string &name)
    对于pick/place操作,设置support surface name允许指定的表面与绑定attach物体接触 More...
    void setWorkspace (double minx, double miny, double minz, double maxx, double maxy, double maxz)
    设置workspace边界范围 (相对于根链接的初始位置) More...
    ~MoveGroupInterface ()
    默认析构函数

    有两种设置目标(goal)的方式

    • JointValueTarget (即JointStateTarget),指定每个关节的绝对数值(旋转关节为角度值,移动关节为位置值)。
    • PoseTarget (位置方向姿态), 指定末端执行器的目标状态 (各关节可以是任何符合的状态)。
    设置joint state目标(goal)
    返回值 函数&介绍
    bool setJointValueTarget (const std::vector< double > &group_variable_values)
    设置JointValueTarget More...
    bool setJointValueTarget (const std::map< std::string, double > &variable_values)
    设置JointValueTarget More...
    bool setJointValueTarget (const robot_state::RobotState &robot_state)
    设置JointValueTarget More...
    bool setJointValueTarget (const std::string &joint_name, const std::vector< double > &values)
    设置JointValueTarget More...
    bool setJointValueTarget (const std::string &joint_name, double value)
    设置JointValueTarget More...
    bool setJointValueTarget (const sensor_msgs::JointState &state)
    设置JointValueTarget More...
    bool setJointValueTarget (const geometry_msgs::Pose &eef_pose, const std::string &end_effector_link="")
    为指定关节设置JointValueTarget More...
    bool setJointValueTarget (const geometry_msgs::PoseStamped &eef_pose, const std::string &end_effector_link="")
    为指定关节设置JointValueTarget More...
    bool setJointValueTarget (const Eigen::Affine3d &eef_pose, const std::string &end_effector_link="")
    为指定关节设置JointValueTarget More...
    bool setApproximateJointValueTarget (const geometry_msgs::Pose &eef_pose, const std::string &end_effector_link="")
    为指定关节设置JointValueTarget More...
    bool setApproximateJointValueTarget (const geometry_msgs::PoseStamped &eef_pose, const std::string &end_effector_link="")
    为指定关节设置JointValueTarget More...
    bool setApproximateJointValueTarget (const Eigen::Affine3d &eef_pose, const std::string &end_effector_link="")
    为指定关节设置JointValueTarget More...
    void setRandomTarget ()
    随机设置JointValueTarget More...
    bool setNamedTarget (const std::string &name)
    设置一个已知名称的目标,从通过 rememberJointValues()添加的状态中搜索,如果找过到,会从SRDF中搜索 More...
    const robot_state::RobotState & getJointValueTarget () const
    获取当前的JointValueTarget More...
    设置pose目标(goal)
    返回值 函数&介绍
    bool setPositionTarget (double x, double y, double z, const std::string &end_effector_link="")
    设置end-effector end_effector_link 目标位置 (x, y, z). More...
    bool setRPYTarget (double roll, double pitch, double yaw, const std::string &end_effector_link="")
    设置 end-effector end_effector_link 目标方向 (roll,pitch,yaw) 弧度 More...
    bool setOrientationTarget (double x, double y, double z, double w, const std::string &end_effector_link="")
    设置 end-effector end_effector_link 目标方向 (x,y,z,w) 四元组 More...
    bool setPoseTarget (const Eigen::Affine3d &end_effector_pose, const std::string &end_effector_link="")
    设置 end-effector end_effector_link 目标姿态 pose More...
    bool setPoseTarget (const geometry_msgs::Pose &target, const std::string &end_effector_link="")
    设置 end-effector end_effector_link 目标姿态 pose More...
    bool setPoseTarget (const geometry_msgs::PoseStamped &target, const std::string &end_effector_link="")
    设置 end-effector end_effector_link 目标姿态 pose More...
    bool setPoseTargets (const EigenSTL::vector_Affine3d &end_effector_pose, const std::string &end_effector_link="")
    设置 end_effector_link 目标姿态 (多个) More...
    bool setPoseTargets (const std::vector< geometry_msgs::Pose > &target, const std::string &end_effector_link="")
    设置 end_effector_link 目标姿态 (多个) More...
    bool setPoseTargets (const std::vector< geometry_msgs::PoseStamped > &target, const std::string &end_effector_link="")
    设置 end_effector_link 目标姿态 (多个) More...
    void setPoseReferenceFrame (const std::string &pose_reference_frame)
    设置姿态目标基准坐标系 More...
    bool setEndEffectorLink (const std::string &end_effector_link)
    设置 end-effector 父链接,如果没有另外指定,会用此链接作为 end_effector_link More...
    bool setEndEffector (const std::string &eef_name)
    指定末端执行器名称。 同时会把改末端执行器的父链接设置为 end_effector_link More...
    void clearPoseTarget (const std::string &end_effector_link="")
    清楚指定 end_effector_link 的目标 More...
    void clearPoseTargets ()
    清楚所有目标 More...
    const geometry_msgs::PoseStamped & getPoseTarget (const std::string &end_effector_link="") const
    const std::vector< geometry_msgs::PoseStamped > & getPoseTargets (const std::string &end_effector_link="") const
    const std::string & getEndEffectorLink () const
    获取当前 end-effector lin,由setEndEffectorLink() 设置 (或直接由 setEndEffector() 设置)。如果 setEndEffectorLink() 没有调用过,返回 end-effector 的父链接,如果有多个 end-effector, 只返回其中一个的父链接。如果没有,返回空字符串。 More...
    const std::string & getEndEffector () const
    获取当前 end-effector 名称,由 setEndEffector() 设置,(或直接由 setEndEffectorLink() 设置)。如果 setEndEffector() 没有被调用过,返回 SRDF中定义的 end-effector,如果有多个,值返回其中一个。如果没有,返回空字符串。 More...
    const std::string & getPoseReferenceFrame () const
    获取参考坐标系,由 setPoseReferenceFrame() 设置。默认为robot model的参考系。 More...
    规划和执行
    返回值 函数&介绍
    MoveItErrorCode asyncMove ()
    规划并执行一个路径。(异步执行) 不会等待执行完成。More...
    actionlib::SimpleActionClient< moveit_msgs::MoveGroupAction > & getMoveGroupClient () const
    获取 move_group action client。在异步执行运动时,可以通过client对象查询当前执行状态或终止执行。More...
    MoveItErrorCode move ()
    规划并执行一个路径。(同步执行) 阻塞等待执行完成。前提要启动 asynchronous spinner More...
    MoveItErrorCode plan (Plan &plan)
    规划一个路径,结果保存到 plan More...
    MoveItErrorCode asyncExecute (const Plan &plan)
    执行一个指定的规划 (异步)More...
    MoveItErrorCode execute (const Plan &plan)
    执行一个指定的规划 (同步) More...
    double computeCartesianPath (const std::vector< geometry_msgs::Pose > &waypoints, double eef_step, double jump_threshold, moveit_msgs::RobotTrajectory &trajectory, bool avoid_collisions=true, moveit_msgs::MoveItErrorCodes *error_code=NULL)
    通过插补规划一个Cartesian 路径,基于指定的一组路径点 waypoints, 插补步长由 eef_step 指定,结果保存到 trajectory 中, 参考系由 setPoseReferenceFrame() 设置; jump_threshold 设置跳跃阈值,防止IK逆运动求解中的 jumpavoid_collisions 设为 true 禁止碰撞;返回值为 0.0 到 1.0 的一个值表示成功规划得到的路径占全部路径的比例。 错误返回 -1.0 More...
    double computeCartesianPath (const std::vector< geometry_msgs::Pose > &waypoints, double eef_step, double jump_threshold, moveit_msgs::RobotTrajectory &trajectory, const moveit_msgs::Constraints &path_constraints, bool avoid_collisions=true, moveit_msgs::MoveItErrorCodes *error_code=NULL)
    通过插补规划一个Cartesian 路径,基于指定的一组路径点 waypoints, 插补步长由 eef_step 指定,结果保存到 trajectory 中, 参考系由 setPoseReferenceFrame() 设置; jump_threshold 设置跳跃阈值,防止IK逆运动求解中的 jumppath_constraints 指定约束条件,如果约束无法满足,返回部分解; avoid_collisions 设为 true 禁止碰撞;返回值为 0.0 到 1.0 的一个值表示成功规划得到的路径占全部路径的比例。 错误返回 -1.0 More...
    void stop ()
    终止正在执行的规划 More...
    void allowLooking (bool flag)
    设置是否允许机器人观察周围来确定是否可以执行规划 (默认true)More...
    void allowReplanning (bool flag)
    设置是否允许机器人在检测到环境变化后重新规划 More...
    void constructMotionPlanRequest (moveit_msgs::MotionPlanRequest &request)
    创建请求 MotionPlanRequest 发送到 move_grouprequest 为plan()或move() More...
    高级动作:触发一些列plans 和 actions
    返回值 函数&介绍
    MoveItErrorCode pick (const std::string &object, bool plan_only=false)
    抓取物体 More...
    MoveItErrorCode pick (const std::string &object, const moveit_msgs::Grasp &grasp, bool plan_only=false)
    抓取物体 (指定抓取姿态) More...
    MoveItErrorCode pick (const std::string &object, const std::vector< moveit_msgs::Grasp > &grasps, bool plan_only=false)
    抓取物体 (给定可选抓取姿态) More...
    MoveItErrorCode planGraspsAndPick (const std::string &object="", bool plan_only=false)
    抓取物体 More...
    MoveItErrorCode planGraspsAndPick (const moveit_msgs::CollisionObject &object, bool plan_only=false)
    抓取物体 More...
    MoveItErrorCode place (const std::string &object, bool plan_only=false)
    放置物体到world中某个安全区域 (自动检测寻找一个安全位置) More...
    MoveItErrorCode place (const std::string &object, const std::vector< moveit_msgs::PlaceLocation > &locations, bool plan_only=false)
    放置物体到可选位置之一 More...
    MoveItErrorCode place (const std::string &object, const std::vector< geometry_msgs::PoseStamped > &poses, bool plan_only=false)
    放置物体到可选位置之一 More...
    MoveItErrorCode place (const std::string &object, const geometry_msgs::PoseStamped &pose, bool plan_only=false)
    放置物体到可选位置之一 More...
    bool attachObject (const std::string &object, const std::string &link="")
    将指定物体绑定到指定link。如果没有指定link,默认绑定到end-effector;如果没有end-effector,绑定到第一个link。如果不存在指定物体,报错会在 move_group 生成,该接口调用的请求依旧会成功。More...
    bool attachObject (const std::string &object, const std::string &link, const std::vector< std::string > &touch_links)
    将指定物体绑定到指定link。touch_links设置允许忽略碰撞而接触的link;如果没有指定link,默认绑定到end-effector;如果没有end-effector,绑定到第一个link。如果不存在指定物体,报错会在 move_group 生成,该接口调用的请求依旧会成功。 More...
    bool detachObject (const std::string &name="")
    接触物体绑定。 name 指定已绑定的物体名称或物体所绑定的link名称;如果没有指定名称并且只有一个绑定物体,则解绑该物体;如果无法识别,则报错。 More...
    访问当前状态
    返回值 函数&介绍
    bool startStateMonitor (double wait=1.0)
    任何访问机器人当前状态的函数被调用都会自动构造CurrentStateMonitor 对象(若尚未存在)。可以手动调用该函数创建,以此减少之后查看状态需要的时间。 More...
    std::vector< double > getCurrentJointValues ()
    获取当前关节状态 (见 getJoints()) More...
    robot_state::RobotStatePtr getCurrentState (double wait=1)
    获取当前状态 (超时 wait) More...
    geometry_msgs::PoseStamped getCurrentPose (const std::string &end_effector_link="")
    获取 end-effector end_effector_link 的姿态。如果没有设置默认的 end_effector_link 则为 getEndEffectorLink() 得到的 end-effector More...
    std::vector< double > getCurrentRPY (const std::string &end_effector_link="")
    获取 end-effector end_effector_link 的 roll-pitch-yaw (XYZ)。如果没有设置默认的 end_effector_link 则为 getEndEffectorLink() 得到的 end-effector More...
    std::vector< double > getRandomJointValues ()
    获取随机的关节状态 (见 getJoints()) More...
    geometry_msgs::PoseStamped getRandomPose (const std::string &end_effector_link="")
    获取随机的 end-effector end_effector_link 的姿态。如果没有设置默认的 end_effector_link 则为 getEndEffectorLink() 得到的 end-effector More...
    管理关节状态
    返回值 函数&介绍
    void rememberJointValues (const std::string &name)
    name 保存当前关节状态。 数据局部存在于client中,其他clinet无法访问。 More...
    void rememberJointValues (const std::string &name, const std::vector< double > &values)
    name 保存指定关节的状态。 数据局部存在于client中,其他clinet无法访问。 More...
    const std::map< std::string, std::vector< double > > & getRememberedJointValues () const
    获取以保存的关节状态,返回 std::map More...
    void forgetJointValues (const std::string &name)
    忘记保存为 name 的状态数据 More...
    管理规划约束条件
    返回值 函数&介绍
    void setConstraintsDatabase (const std::string &host, unsigned int port)
    设置数据库服务器, 约束条件的数据所在位置 More...
    std::vector< std::string > getKnownConstraints () const
    获取一直约束条件数据 (前提已经与 Mongo 数据库建立连接)More...
    moveit_msgs::Constraints getPathConstraints () const
    获取当前 MoveGroupInterface 使用中的约束条件数据 More...
    bool setPathConstraints (const std::string &constraint)
    设置约束条件。通过制定名称从 Mongo 数据库查找。覆盖之前通过 setPathConstraints() 设置的约束条件 More...
    void setPathConstraints (const moveit_msgs::Constraints &constraint)
    设置约束调节。直接传入 moveit_msgs::Constraints 对象。 覆盖之前通过 setPathConstraints() 设置的约束条件 More...
    void clearPathConstraints ()
    清楚约束条件 More...
    moveit_msgs::TrajectoryConstraints getTrajectoryConstraints () const
    void setTrajectoryConstraints (const moveit_msgs::TrajectoryConstraints &constraint)
    void clearTrajectoryConstraints ()

    相关文章

      网友评论

          本文标题:MoveIt教程9 - moveit::planning_int

          本文链接:https://www.haomeiwen.com/subject/nejnkctx.html