Public Member Functions | Private Member Functions | List of all members
pilz::TrajectoryGeneratorCIRC Class Reference

This class implements a trajectory generator of arcs in Cartesian space. The arc is specified by a start pose, a goal pose and a interim point on the arc, or a point as the center of the circle which forms the arc. Complete circle is not covered by this generator. More...

#include <trajectory_generator_circ.h>

Inheritance diagram for pilz::TrajectoryGeneratorCIRC:
Inheritance graph
[legend]

Public Member Functions

 TrajectoryGeneratorCIRC (const robot_model::RobotModelConstPtr &robot_model, const pilz::LimitsContainer &planner_limits)
 Constructor of CIRC Trajectory Generator. More...
 
virtual ~TrajectoryGeneratorCIRC ()=default
 
- Public Member Functions inherited from pilz::TrajectoryGenerator
bool generate (const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res, double sampling_time=0.1)
 generate robot trajectory with given sampling time More...
 
 TrajectoryGenerator (const robot_model::RobotModelConstPtr &robot_model, const pilz::LimitsContainer &planner_limits)
 
virtual ~TrajectoryGenerator ()=default
 

Private Member Functions

virtual void cmdSpecificRequestValidation (const planning_interface::MotionPlanRequest &req) const override
 
virtual void extractMotionPlanInfo (const planning_interface::MotionPlanRequest &req, MotionPlanInfo &info) const finaloverride
 Extract needed information from a motion plan request in order to simplify further usages. More...
 
virtual void plan (const planning_interface::MotionPlanRequest &req, const MotionPlanInfo &plan_info, const double &sampling_time, trajectory_msgs::JointTrajectory &joint_trajectory) override
 
std::unique_ptr< KDL::PathsetPathCIRC (const MotionPlanInfo &info) const
 Construct a KDL::Path object for a Cartesian path of an arc. More...
 

Additional Inherited Members

- Protected Member Functions inherited from pilz::TrajectoryGenerator
std::unique_ptr< KDL::VelocityProfilecartesianTrapVelocityProfile (const double &max_velocity_scaling_factor, const double &max_acceleration_scaling_factor, const std::unique_ptr< KDL::Path > &path) const
 build cartesian velocity profile for the path More...
 
- Protected Attributes inherited from pilz::TrajectoryGenerator
const pilz::LimitsContainer planner_limits_
 
const robot_model::RobotModelConstPtr robot_model_
 
- Static Protected Attributes inherited from pilz::TrajectoryGenerator
static constexpr double MAX_SCALING_FACTOR {1.}
 
static constexpr double MIN_SCALING_FACTOR {0.0001}
 
static constexpr double VELOCITY_TOLERANCE {1e-8}
 

Detailed Description

This class implements a trajectory generator of arcs in Cartesian space. The arc is specified by a start pose, a goal pose and a interim point on the arc, or a point as the center of the circle which forms the arc. Complete circle is not covered by this generator.

Definition at line 51 of file trajectory_generator_circ.h.

Constructor & Destructor Documentation

pilz::TrajectoryGeneratorCIRC::TrajectoryGeneratorCIRC ( const robot_model::RobotModelConstPtr &  robot_model,
const pilz::LimitsContainer planner_limits 
)

Constructor of CIRC Trajectory Generator.

Parameters
planner_limitsLimits in joint and Cartesian spaces
Exceptions
TrajectoryGeneratorInvalidLimitsException

Definition at line 37 of file trajectory_generator_circ.cpp.

virtual pilz::TrajectoryGeneratorCIRC::~TrajectoryGeneratorCIRC ( )
virtualdefault

Member Function Documentation

void pilz::TrajectoryGeneratorCIRC::cmdSpecificRequestValidation ( const planning_interface::MotionPlanRequest req) const
overrideprivatevirtual

Reimplemented from pilz::TrajectoryGenerator.

Definition at line 47 of file trajectory_generator_circ.cpp.

void pilz::TrajectoryGeneratorCIRC::extractMotionPlanInfo ( const planning_interface::MotionPlanRequest req,
MotionPlanInfo info 
) const
finaloverrideprivatevirtual

Extract needed information from a motion plan request in order to simplify further usages.

Parameters
reqmotion plan request
infoinformation extracted from motion plan request which is necessary for the planning

Implements pilz::TrajectoryGenerator.

Definition at line 68 of file trajectory_generator_circ.cpp.

void pilz::TrajectoryGeneratorCIRC::plan ( const planning_interface::MotionPlanRequest req,
const MotionPlanInfo plan_info,
const double &  sampling_time,
trajectory_msgs::JointTrajectory &  joint_trajectory 
)
overrideprivatevirtual

Implements pilz::TrajectoryGenerator.

Definition at line 174 of file trajectory_generator_circ.cpp.

std::unique_ptr< KDL::Path > pilz::TrajectoryGeneratorCIRC::setPathCIRC ( const MotionPlanInfo info) const
private

Construct a KDL::Path object for a Cartesian path of an arc.

Returns
A unique pointer of the path object, null_ptr in case of an error.
Exceptions
CircleNoPlaneif the plane in which the circle resides, could not be determined.
CircleToSmallif the specified circ radius is to small.
CenterPointDifferentRadiusif the distances between start-center and goal-center are different.

Definition at line 204 of file trajectory_generator_circ.cpp.


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


pilz_trajectory_generation
Author(s):
autogenerated on Mon Apr 6 2020 03:17:34