moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
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>
Public Member Functions | |
TrajectoryGeneratorCIRC (const moveit::core::RobotModelConstPtr &robot_model, const pilz_industrial_motion_planner::LimitsContainer &planner_limits, const std::string &group_name) | |
Constructor of CIRC Trajectory Generator. | |
Public Member Functions inherited from pilz_industrial_motion_planner::TrajectoryGenerator | |
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 | |
Additional Inherited Members | |
Protected Member Functions inherited from pilz_industrial_motion_planner::TrajectoryGenerator | |
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 | |
Protected Attributes inherited from pilz_industrial_motion_planner::TrajectoryGenerator | |
const moveit::core::RobotModelConstPtr | robot_model_ |
const pilz_industrial_motion_planner::LimitsContainer | planner_limits_ |
const std::unique_ptr< rclcpp::Clock > | clock_ |
Static Protected Attributes inherited from pilz_industrial_motion_planner::TrajectoryGenerator | |
static constexpr double | MIN_SCALING_FACTOR { 0.0001 } |
static constexpr double | MAX_SCALING_FACTOR { 1. } |
static constexpr double | VELOCITY_TOLERANCE { 1e-8 } |
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 70 of file trajectory_generator_circ.h.
pilz_industrial_motion_planner::TrajectoryGeneratorCIRC::TrajectoryGeneratorCIRC | ( | const moveit::core::RobotModelConstPtr & | robot_model, |
const pilz_industrial_motion_planner::LimitsContainer & | planner_limits, | ||
const std::string & | group_name | ||
) |
Constructor of CIRC Trajectory Generator.
planner_limits | Limits in joint and Cartesian spaces |
TrajectoryGeneratorInvalidLimitsException |
Definition at line 62 of file trajectory_generator_circ.cpp.