RobWorkProject  23.9.11-
Static Public Member Functions | List of all members
Z3Planner Class Reference

Z3 based planners. More...

#include <Z3Planner.hpp>

Static Public Member Functions

static rw::pathplanning::QToQPlanner::Ptr makeQToQPlanner (rw::core::Ptr< rw::pathplanning::QSampler > sampler, rw::pathplanning::QToQPlanner::Ptr localPlanner, int nodeCnt=-1, int repeatCnt=-1)
 Z3 based point-to-point planner. More...
 
static rw::pathplanning::QToQPlanner::Ptr makeQToQPlanner (const rw::pathplanning::PlannerConstraint &constraint, rw::core::Ptr< rw::models::Device > device)
 Z3 based point-to-point planner. More...
 
static rw::pathplanning::QToQPlanner::Ptr makeSlidingQToQPlanner (const rw::pathplanning::PlannerConstraint &constraint, rw::core::Ptr< rw::pathplanning::QSampler > directionSampler, rw::core::Ptr< rw::pathplanning::QConstraint > boundsConstraint, rw::math::QMetric::Ptr metric, double extend, double slideImprovement=-1)
 Sliding local planner. More...
 
static rw::pathplanning::QToQPlanner::Ptr makeSlidingQToQPlanner (const rw::pathplanning::PlannerConstraint &constraint, rw::core::Ptr< rw::models::Device > device, rw::math::QMetric::Ptr metric=0, double extend=-1, double slideImprovement=-1)
 Sliding local planner. More...
 

Detailed Description

Z3 based planners.

See "The Z3-Method for Fast Path Planning in Dynamic Environments", Boris Baginski, 1996.

Member Function Documentation

◆ makeQToQPlanner() [1/2]

static rw::pathplanning::QToQPlanner::Ptr makeQToQPlanner ( const rw::pathplanning::PlannerConstraint constraint,
rw::core::Ptr< rw::models::Device device 
)
static

Z3 based point-to-point planner.

A default configuration space sampler (rw::pathplanning::QSampler) and local planning is chosen for device using constraint for collision checking.

Parameters
constraint[in] Constraint for configurations and edges.
device[in] Device for which the path is planned.

◆ makeQToQPlanner() [2/2]

static rw::pathplanning::QToQPlanner::Ptr makeQToQPlanner ( rw::core::Ptr< rw::pathplanning::QSampler sampler,
rw::pathplanning::QToQPlanner::Ptr  localPlanner,
int  nodeCnt = -1,
int  repeatCnt = -1 
)
static

Z3 based point-to-point planner.

Parameters
sampler[in] Sampler of the configuration space.
localPlanner[in] Local planner for connecting the configurations.
nodeCnt[in] Number of supporting configurations to insert. If nodeCnt is negative, a default value is chosen.
repeatCnt[in] Number of times to repeat the attempt. If repeatCnt is negative (the default), the attempts are repeated until the stop criteria returns true.

◆ makeSlidingQToQPlanner() [1/2]

static rw::pathplanning::QToQPlanner::Ptr makeSlidingQToQPlanner ( const rw::pathplanning::PlannerConstraint constraint,
rw::core::Ptr< rw::models::Device device,
rw::math::QMetric::Ptr  metric = 0,
double  extend = -1,
double  slideImprovement = -1 
)
static

Sliding local planner.

A default direction sampler and bounds checker is chosen for device.

Parameters
constraint[in] Path planning constraint.
device[in] Device for which the planning is done.
metric[in] Configuration space distance measure. If no metric is given, a default metric for device is chosen. In this case extend and slideImprovement should be negative, and default values for these will be chosen.
extend[in] The length of each sliding step as measured by metric.
slideImprovement[in] The minimum decrease in distance to the goal that should be acheived for every valid slide step. If slideImprovement is negative, a default value for slideImprovement is chosen based on the value of extend.

◆ makeSlidingQToQPlanner() [2/2]

static rw::pathplanning::QToQPlanner::Ptr makeSlidingQToQPlanner ( const rw::pathplanning::PlannerConstraint constraint,
rw::core::Ptr< rw::pathplanning::QSampler directionSampler,
rw::core::Ptr< rw::pathplanning::QConstraint boundsConstraint,
rw::math::QMetric::Ptr  metric,
double  extend,
double  slideImprovement = -1 
)
static

Sliding local planner.

This is a variation of the sliding local planner described in the Z3 paper.

This is the default local planner used for instantiation of the Z3 based planners.

Parameters
constraint[in] Path planning constraint.
directionSampler[in] Sampler of direction vectors in the configuration space.
boundsConstraint[in] Constraint checking for the bounds of the configuration space.
metric[in] Configuration space distance measure.
extend[in] The length of each sliding step as measured by metric.
slideImprovement[in] The minimum decrease in distance to the goal that should be acheived for every valid slide step. If slideImprovement is negative, a default value for slideImprovement is chosen based on the value of extend.

The documentation for this class was generated from the following file: