| 
    moveit2
    
   The MoveIt Motion Planning Framework for ROS 2. 
   | 
 
Classes | |
| struct | CartPoseErrCalculator | 
| Used to calculate the error for StaticCartPoseTermInfo This is converted to a cost or constraint using TrajOptCostFromErrFunc or TrajOptConstraintFromErrFunc.  More... | |
| struct | JointVelErrCalculator | 
| struct | JointVelJacobianCalculator | 
| struct | BasicInfo | 
| struct | InitInfo | 
| struct | TermInfo | 
| struct | ProblemInfo | 
| class | TrajOptProblem | 
| struct | CartPoseTermInfo | 
| This term is used when the goal frame is fixed in cartesian space.  More... | |
| struct | JointPoseTermInfo | 
| Joint space position cost Position operates on a single point (unlike velocity, etc). This is b/c the primary usecase is joint-space position waypoints.  More... | |
| struct | JointVelTermInfo | 
| class | TrajOptInterface | 
| class | TrajOptPlanningContext | 
| class | TrajOptPlannerManager | 
Enumerations | |
| enum | TermType { TT_COST = 0x1 , TT_CNT = 0x2 , TT_USE_TIME = 0x4 } | 
Functions | |
| Eigen::Vector3d | quaternionRotationVector (const Eigen::Matrix3d &matrix) | 
| Extracts the vector part of quaternion.  More... | |
| Eigen::VectorXd | concatVector (const Eigen::VectorXd &vector_a, const Eigen::VectorXd &vector_b) | 
| Appends b to a of type VectorXd.  More... | |
| template<typename T > | |
| std::vector< T > | concatVector (const std::vector< T > &vector_a, const std::vector< T > &vector_b) | 
| Appends b to a of type T.  More... | |
| MOVEIT_CLASS_FORWARD (TermInfo) | |
| MOVEIT_CLASS_FORWARD (TrajOptProblem) | |
| MOVEIT_CLASS_FORWARD (JointPoseTermInfo) | |
| MOVEIT_CLASS_FORWARD (CartPoseTermInfo) | |
| MOVEIT_CLASS_FORWARD (JointVelTermInfo) | |
| TrajOptProblemPtr | ConstructProblem (const ProblemInfo &) | 
| void | generateInitialTrajectory (const ProblemInfo &pci, const std::vector< double > ¤t_joint_values, trajopt::TrajArray &init_traj) | 
| MOVEIT_CLASS_FORWARD (TrajOptInterface) | |
| void | callBackFunc (sco::OptProb *opt_prob, sco::OptResults &opt_res) | 
| MOVEIT_CLASS_FORWARD (TrajOptPlanningContext) | |
| Enumerator | |
|---|---|
| TT_COST | |
| TT_CNT | |
| TT_USE_TIME | |
Definition at line 58 of file problem_description.h.
| void trajopt_interface::callBackFunc | ( | sco::OptProb * | opt_prob, | 
| sco::OptResults & | opt_res | ||
| ) | 
      
  | 
  inline | 
Appends b to a of type VectorXd.
Definition at line 22 of file kinematic_terms.h.

      
  | 
  inline | 
Appends b to a of type T.
Definition at line 34 of file kinematic_terms.h.
| TrajOptProblemPtr trajopt_interface::ConstructProblem | ( | const ProblemInfo & | pci | ) | 
Definition at line 138 of file problem_description.cpp.


| void trajopt_interface::generateInitialTrajectory | ( | const ProblemInfo & | pci, | 
| const std::vector< double > & | current_joint_values, | ||
| trajopt::TrajArray & | init_traj | ||
| ) | 
| trajopt_interface::MOVEIT_CLASS_FORWARD | ( | CartPoseTermInfo | ) | 
| trajopt_interface::MOVEIT_CLASS_FORWARD | ( | JointPoseTermInfo | ) | 
| trajopt_interface::MOVEIT_CLASS_FORWARD | ( | JointVelTermInfo | ) | 
| trajopt_interface::MOVEIT_CLASS_FORWARD | ( | TermInfo | ) | 
| trajopt_interface::MOVEIT_CLASS_FORWARD | ( | TrajOptInterface | ) | 
| trajopt_interface::MOVEIT_CLASS_FORWARD | ( | TrajOptPlanningContext | ) | 
| trajopt_interface::MOVEIT_CLASS_FORWARD | ( | TrajOptProblem | ) | 
      
  | 
  inline | 
Extracts the vector part of quaternion.
Definition at line 12 of file kinematic_terms.h.