This class implements a point-to-point trajectory generator based on VelocityProfile_ATrap.
More...
#include <trajectory_generator_ptp.h>
|
virtual void | extractMotionPlanInfo (const planning_interface::MotionPlanRequest &req, MotionPlanInfo &info) const override |
| 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 |
|
void | planPTP (const std::map< std::string, double > &start_pos, const std::map< std::string, double > &goal_pos, trajectory_msgs::JointTrajectory &joint_trajectory, const std::string &group_name, const double &velocity_scaling_factor, const double &acceleration_scaling_factor, const double &sampling_time) |
| plan ptp joint trajectory with zero start velocity More...
|
|
This class implements a point-to-point trajectory generator based on VelocityProfile_ATrap.
Definition at line 40 of file trajectory_generator_ptp.h.
pilz::TrajectoryGeneratorPTP::TrajectoryGeneratorPTP |
( |
const robot_model::RobotModelConstPtr & |
robot_model, |
|
|
const pilz::LimitsContainer & |
planner_limits |
|
) |
| |
Constructor of PTP Trajectory Generator.
- Exceptions
-
TrajectoryGeneratorInvalidLimitsException | |
- Parameters
-
model | a map of joint limits information |
Definition at line 28 of file trajectory_generator_ptp.cpp.
virtual pilz::TrajectoryGeneratorPTP::~TrajectoryGeneratorPTP |
( |
| ) |
|
|
virtualdefault |
Extract needed information from a motion plan request in order to simplify further usages.
- Parameters
-
req | motion plan request |
info | information extracted from motion plan request which is necessary for the planning |
Implements pilz::TrajectoryGenerator.
Definition at line 192 of file trajectory_generator_ptp.cpp.
void pilz::TrajectoryGeneratorPTP::planPTP |
( |
const std::map< std::string, double > & |
start_pos, |
|
|
const std::map< std::string, double > & |
goal_pos, |
|
|
trajectory_msgs::JointTrajectory & |
joint_trajectory, |
|
|
const std::string & |
group_name, |
|
|
const double & |
velocity_scaling_factor, |
|
|
const double & |
acceleration_scaling_factor, |
|
|
const double & |
sampling_time |
|
) |
| |
|
private |
plan ptp joint trajectory with zero start velocity
- Parameters
-
start_pos | |
goal_pos | |
joint_trajectory | |
group_name | |
velocity_scaling_factor | |
acceleration_scaling_factor | |
sampling_time | |
Definition at line 67 of file trajectory_generator_ptp.cpp.
const double pilz::TrajectoryGeneratorPTP::MIN_MOVEMENT = 0.001 |
|
private |
The documentation for this class was generated from the following files: