Class TrajectoryGenerator

Nested Relationships

Nested Types

Inheritance Relationships

Derived Types

Class Documentation

class TrajectoryGenerator

Base class of trajectory generators.

Note: All derived classes cannot have a start velocity

Subclassed by pilz_industrial_motion_planner::TrajectoryGeneratorCIRC, pilz_industrial_motion_planner::TrajectoryGeneratorLIN, pilz_industrial_motion_planner::TrajectoryGeneratorPTP

Public Functions

inline TrajectoryGenerator(const moveit::core::RobotModelConstPtr &robot_model, const pilz_industrial_motion_planner::LimitsContainer &planner_limits)
virtual ~TrajectoryGenerator() = default
void generate(const planning_scene::PlanningSceneConstPtr &scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res, double sampling_time = 0.1)

generate robot trajectory with given sampling time

Parameters:
  • req – motion plan request

  • res – motion plan response

  • sampling_time – sampling time of the generate trajectory

Protected Functions

std::unique_ptr<KDL::VelocityProfile> cartesianTrapVelocityProfile(double max_velocity_scaling_factor, double max_acceleration_scaling_factor, const std::unique_ptr<KDL::Path> &path) const

build cartesian velocity profile for the path

Uses the path to get the cartesian length and the angular distance from start to goal. The trap profile returns uses the longer distance of translational and rotational motion.

Protected Attributes

const moveit::core::RobotModelConstPtr robot_model_
const pilz_industrial_motion_planner::LimitsContainer planner_limits_
const std::unique_ptr<rclcpp::Clock> clock_

Protected Static Attributes

static constexpr double MIN_SCALING_FACTOR = {0.0001}
static constexpr double MAX_SCALING_FACTOR = {1.}
static constexpr double VELOCITY_TOLERANCE = {1e-8}
class MotionPlanInfo

This class is used to extract needed information from motion plan request.

Public Members

std::string group_name
Eigen::Isometry3d start_pose
Eigen::Isometry3d goal_pose
std::map<std::string, double> start_joint_position
std::map<std::string, double> goal_joint_position
std::pair<std::string, Eigen::Vector3d> circ_path_point