Hauptinhalt

chompCollisionOptions

Collision options for CHOMP trajectories

Since R2023a

    Description

    The chompCollisionOptions object stores collision options for Covariant Hamiltonian Optimization for Motion Planning (CHOMP) trajectories. Use this object to optimize a CHOMP trajectory to avoid collisions.

    Creation

    Description

    OPTS = chompCollisionOptions creates a collision options object OPTS that you can use to optimize a CHOMP trajectory to avoid collisions.

    OPTS = chompCollisionOptions(Name=Value) specifies properties using one or more name-value arguments.

    example

    Properties

    expand all

    Minimum distance to maintain from obstacles, specified as a positive numeric scalar.

    Body pairs to omit from self-collision costs, specified as either "parent" or "adjacent".

    • "parent" — Skip collision checking between child and parent bodies.

    • "adjacent" — Skip collision checking between bodies on adjacent indices.

    Data Types: char | string

    Weight on cost of ignoring self-collision avoidance, specified as a numeric scalar.

    Weight on the cost of collision, specified as a positive numeric scalar.

    Examples

    collapse all

    Load a robot model into the workspace, and create a CHOMP solver.

    robot = loadrobot("kinovaGen3",DataFormat="row");
    chomp = manipulatorCHOMP(robot);

    Create spheres to represent obstacles, and add them to the CHOMP solver.

    env = [0.20 0.2 -0.1 -0.1;   % sphere, radius 0.20 at (0.2,-0.1,-0.1)
           0.15 0.2  0.0  0.5]'; % sphere, radius 0.15 at (0.2,0.0,0.5)
    chomp.SphericalObstacles = env;

    To prioritize a collision-free trajectory, set the smoothness cost weight to a lower value than the collision cost weight. Then add the options to the CHOMP solver.

    chomp.SmoothnessOptions = chompSmoothnessOptions(SmoothnessCostWeight=1e-3);
    chomp.CollisionOptions = chompCollisionOptions(CollisionCostWeight=10);
    chomp.SolverOptions = chompSolverOptions(Verbosity="none",LearningRate=7.0);

    Initialize a trajectory, optimize it using the CHOMP solver, and show the waypoints in a figure.

    startconfig = homeConfiguration(robot);
    goalconfig = [0.5 1.75 -2.25 2.0 0.3 -1.65 -0.4];
    timepoints = [0 5];
    timestep = 0.1;
    trajtype = "minjerkpolytraj";
    [wptsamples,tsamples] = optimize(chomp, ...
        [startconfig; goalconfig], ...
        timepoints, ...
        timestep, ...
        InitialTrajectoryFitType=trajtype);
    show(chomp,wptsamples,NumSamples=10);
    zlim([-0.5 1.3])

    Figure contains an axes object. The axes object with xlabel X, ylabel Y contains 263 objects of type patch. These objects represent base_link, Shoulder_Link, HalfArm1_Link, HalfArm2_Link, ForeArm_Link, Wrist1_Link, Wrist2_Link, Bracelet_Link, EndEffector_Link, Shoulder_Link_mesh, HalfArm1_Link_mesh, HalfArm2_Link_mesh, ForeArm_Link_mesh, Wrist1_Link_mesh, Wrist2_Link_mesh, Bracelet_Link_mesh, base_link_mesh, Shoulder_Link_coll_mesh, HalfArm1_Link_coll_mesh, HalfArm2_Link_coll_mesh, ForeArm_Link_coll_mesh, Wrist1_Link_coll_mesh, Wrist2_Link_coll_mesh, Bracelet_Link_coll_mesh, base_link_coll_mesh.

    References

    [1] Ratliff, Nathan, Siddhartha Srinivasa, Matt Zucker, and Andrew Bagnell. “CHOMP: Gradient Optimization Techniques for Efficient Motion Planning.” In 2009 IEEE International Conference on Robotics and Automation, 489–94. Kobe, Japan: IEEE, 2009. https://doi.org/10.1109/ROBOT.2009.5152817.

    Extended Capabilities

    expand all

    C/C++ Code Generation
    Generate C and C++ code using MATLAB® Coder™.

    Version History

    Introduced in R2023a