|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
This class is used to extract needed information from motion plan request. More...
#include <trajectory_generator.hpp>
Public Member Functions | |
| MotionPlanInfo (const planning_scene::PlanningSceneConstPtr &scene, const planning_interface::MotionPlanRequest &req) | |
Public Attributes | |
| std::string | group_name |
| std::string | link_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 |
| planning_scene::PlanningSceneConstPtr | start_scene |
This class is used to extract needed information from motion plan request.
Definition at line 116 of file trajectory_generator.hpp.
| pilz_industrial_motion_planner::TrajectoryGenerator::MotionPlanInfo::MotionPlanInfo | ( | const planning_scene::PlanningSceneConstPtr & | scene, |
| const planning_interface::MotionPlanRequest & | req | ||
| ) |
| std::pair<std::string, Eigen::Vector3d> pilz_industrial_motion_planner::TrajectoryGenerator::MotionPlanInfo::circ_path_point |
Definition at line 127 of file trajectory_generator.hpp.
| std::map<std::string, double> pilz_industrial_motion_planner::TrajectoryGenerator::MotionPlanInfo::goal_joint_position |
Definition at line 126 of file trajectory_generator.hpp.
| Eigen::Isometry3d pilz_industrial_motion_planner::TrajectoryGenerator::MotionPlanInfo::goal_pose |
Definition at line 124 of file trajectory_generator.hpp.
| std::string pilz_industrial_motion_planner::TrajectoryGenerator::MotionPlanInfo::group_name |
Definition at line 121 of file trajectory_generator.hpp.
| std::string pilz_industrial_motion_planner::TrajectoryGenerator::MotionPlanInfo::link_name |
Definition at line 122 of file trajectory_generator.hpp.
| std::map<std::string, double> pilz_industrial_motion_planner::TrajectoryGenerator::MotionPlanInfo::start_joint_position |
Definition at line 125 of file trajectory_generator.hpp.
| Eigen::Isometry3d pilz_industrial_motion_planner::TrajectoryGenerator::MotionPlanInfo::start_pose |
Definition at line 123 of file trajectory_generator.hpp.
| planning_scene::PlanningSceneConstPtr pilz_industrial_motion_planner::TrajectoryGenerator::MotionPlanInfo::start_scene |
Definition at line 128 of file trajectory_generator.hpp.