MoveitGrasp的参数配置

参数配置

moveitgrasp分为两个配置文件,一个和机器人无关,一个与具体机器人配置有关。

config_robot配置文件需要注意,选择对的base_link,这个需要具体问题具体分析,如果选择不对,规划出来的抓取姿态和目标不在一起,通常,机械臂和定位传感器建立了一个坐标转换关系,而grasp会把规划出来的姿态以base_link为坐标系发出去并控制机械臂。

config_robot.yaml:

# 选择正确的基座

base_link: 'link_chassis'

# =====================================================

# Note: these parameters are copied from Robotiq gripper without tweaking

griper:

    end_effector_name: 'griper'  # ee group name,手爪的moveit group

    end_effector_type: 'finger'  # 'finger' or 'suction',手爪类型



    # x/y translation and angle orientation grasp resolution parameters used for sampling grasp candidates

    grasp_resolution : 0.03  # meter

    angle_resolution : 30    # degrees



    # min/max values of the grasp depth range in meter.

    # This should fit to the distance from finger tip to inner palm or the suction cup stroke

    grasp_max_depth : 0.035

    grasp_min_depth : 0.01

    # grasp_depth_resolution is the discretization distance in meter used for sampling the grasp depth value.

    # Idealy this should be a small fraction of the depth range (i.e. 0.005).

    # If the value exceeds the depth distance range grasp_max_depth is used by default.

    grasp_depth_resolution : 0.05



    # A grasp motion is composed of three linear paths: approach, retreat, lift

    # The values below define the desired distances of each path.

    # Length of approach path (this is in addition to the grasp_max_depth)

    approach_distance_desired: 0.1  # approach path (in addition to grasp_max_depth)

    retreat_distance_desired: 0.05   # retreat path (in addition to grasp_max_depth)

    lift_distance_desired: 0.05      # lift path (used as MINIMUM safety distance from surface)



    # minimum padding on each side of the object on approach

    grasp_padding_on_approach: 0.005  # meter



    # Distance from the eef mount to the palm of end effector [x, y, z, r, p, y]

    # z-axis pointing toward object to grasp

    # x-axis perp. to movement of grippers

    # y-axis parallel to movement of grippers

    tcp_to_eef_mount_transform :  [0, 0, -0.172, 0, 0, 0] # NOTE: Imaginary point in the middle



    # Joint names and state values for the end effector.

    # The names should match the values of pregrasp_posture and grasp_posture.

    # These values can be left empty if end_effector_type is 'suction'

    joints : ['drive_joint']

    pregrasp_posture : [0.0]  # open position

    grasp_posture : [0.85]      # close position



    # Target durations in seconds for reaching pregrasp and grasp positions in end effector motions

    pregrasp_time_from_start : 0.5

    grasp_time_from_start : 0.5



    ##############################

    ##  Finger gripper parameters

    ##############################

    # Distances between fingers matching to pregrasp_posture and grasp_posture, in meters

    max_finger_width: 0.085

    min_finger_width: 0.06



    # Maximum allowed finger width for a grasp.

    # This value should be considerably smaller than max_finger_width

    # to allow padded collision checks

    max_grasp_width: 0.08



    # width of gripper fingers to ensure the finger tips fully overlap the object

    gripper_finger_width : 0.015



    ##############################

    ## Suction gripper parameters

    ##############################

    # The width of the suction griper along the specified axes. (Assumes that Z points in the direction of the suction cups)

    # active_suction_range_x : 0.25

    # active_suction_range_y : 0.10



    # Some suction grippers can selectively enable and disable regions of suction. If you have more than one

    # region that can be selectively activated or de-activated, set those values here and moveit_grasps

    # will prioritize grasp candidates which use full suction regions rather than partial regions.

    # it will also set the suction_regions_in_contact_ variable in the grasp candidates so that you are able

    # to only enable suction on regions that are in contact with the grasp target.

    # Note that this metric assumes that suction regions are equally sized

    # ie. width = active_suction_range_x / suction_regions_x

    #

    # suction_rows_count: 1

    # suction_cols_count: 1

moveit_grasps.yaml:

moveit_grasps:

  ####################################

  # These settings are used by the grasp generator which generates GraspCandidates

   

  ####################################

  generator:

    # Other verbose stuff

    verbose: true



    # Show hand of generated grasps,是否展示每个采样抓取姿态的手爪模型(urdf),可以用rviz动画般的显示效果,注意:打开后极大的影响处理效率,研究阶段建议打开,其他建议关闭

    show_prefiltered_grasps: false

    show_prefiltered_grasps_speed: 0.01



    # --------------------------------

    # Suction gripper specific settings,吸泵设置,未探索

    # --------------------------------

    # Visual debug options

    debug_top_grasps: false

    # Show suction gripper overhang

    show_grasp_overhang: false



  ####################################

  # The grasp filter filters out unreachable GraspCandidates and populates valid GraspCandidates' pregrasp_ik_solution_ and grasp_ik_solution_'s

  # 上一节负责把手爪构型的所有抓取姿态规划出来,这一节主要是根据机械臂的运动学参数进行过滤选择,跳出机械臂能够到达的姿态

  ####################################

  filter:

    # Show summary statistics

    statistics_verbose: true

    # Visualize the planes used by the filter

    show_cutting_planes: true

    # Collision checking in verbose

    collision_verbose: true

    collision_verbose_speed: 0.01

    # Collision checking in verbose on second pass (after all failed)

    show_grasp_filter_collision_if_failed: true

    # Show post-filter arrows

    show_filtered_grasps: true

    # Show pose-filter arm ik solutions

    show_filtered_arm_solutions: true

    show_filtered_arm_solutions_pregrasp_speed: 0.01

    show_filtered_arm_solutions_speed: 0.01



  ####################################

  # The GraspPlanner generates approach, lift and retreat paths for a GraspCandidate.

  # If the GraspPlanner is unable to plan 100% of the approach path and at least ~90% of the lift and retreat paths, then it considers the GraspCandidate to be infeasible

  # 进行规划,应该说,上一节滤波即使根据机械臂选择了一些可以达到的姿态,但是,没有考虑碰撞检测等特殊情况,这部分则通过机械臂规划尝试选择出最佳的姿态

  ####################################

  planner:

    # Cartesian planning

    statistics_verbose: true

    verbose_cartesian_filtering: false

    show_cartesian_waypoints: true

    collision_checking_verbose: false

  • 0
    点赞
  • 0
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值