|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
This term is used when the goal frame is fixed in cartesian space. More...
#include <problem_description.h>


Public Member Functions | |
| CartPoseTermInfo () | |
| void | addObjectiveTerms (TrajOptProblem &prob) override |
| Used to add term to pci from json. More... | |
Public Member Functions inherited from trajopt_interface::TermInfo | |
| int | getSupportedTypes () |
| TermInfo ()=default | |
| TermInfo (const TermInfo &)=default | |
| TermInfo (TermInfo &&)=default | |
| TermInfo & | operator= (const TermInfo &)=default |
| TermInfo & | operator= (TermInfo &&)=default |
| virtual | ~TermInfo ()=default |
Static Public Member Functions | |
| static TermInfoPtr | create () |
Static Public Member Functions inherited from trajopt_interface::TermInfo | |
| static TermInfoPtr | fromName (const std::string &type) |
| static void | RegisterMaker (const std::string &type, MakerFunc) |
Public Attributes | |
| int | timestep |
| Timestep at which to apply term. More... | |
| Eigen::Vector3d | xyz |
| Cartesian position. More... | |
| Eigen::Vector4d | wxyz |
| Rotation quaternion. More... | |
| Eigen::Vector3d | pos_coeffs |
| coefficients for position and rotation More... | |
| Eigen::Vector3d | rot_coeffs |
| std::string | link |
| Link which should reach desired pose. More... | |
| Eigen::Isometry3d | tcp |
| Static transform applied to the link. More... | |
Public Attributes inherited from trajopt_interface::TermInfo | |
| std::string | name |
| int | term_type |
Additional Inherited Members | |
Public Types inherited from trajopt_interface::TermInfo | |
| using | MakerFunc = TermInfoPtr(*)(void) |
Protected Member Functions inherited from trajopt_interface::TermInfo | |
| TermInfo (int supported_term_types) | |
This term is used when the goal frame is fixed in cartesian space.
Set term_type == TT_COST or TT_CNT for cost or constraint.
Definition at line 268 of file problem_description.h.
| trajopt_interface::CartPoseTermInfo::CartPoseTermInfo | ( | ) |
Definition at line 268 of file problem_description.cpp.
|
overridevirtual |
Used to add term to pci from json.
Converts term info into cost/constraint and adds it to trajopt problem
Implements trajopt_interface::TermInfo.
Definition at line 275 of file problem_description.cpp.

|
inlinestatic |
Definition at line 292 of file problem_description.h.
| std::string trajopt_interface::CartPoseTermInfo::link |
Link which should reach desired pose.
Definition at line 281 of file problem_description.h.
| Eigen::Vector3d trajopt_interface::CartPoseTermInfo::pos_coeffs |
coefficients for position and rotation
Definition at line 279 of file problem_description.h.
| Eigen::Vector3d trajopt_interface::CartPoseTermInfo::rot_coeffs |
Definition at line 279 of file problem_description.h.
| Eigen::Isometry3d trajopt_interface::CartPoseTermInfo::tcp |
Static transform applied to the link.
Definition at line 283 of file problem_description.h.
| int trajopt_interface::CartPoseTermInfo::timestep |
Timestep at which to apply term.
Definition at line 273 of file problem_description.h.
| Eigen::Vector4d trajopt_interface::CartPoseTermInfo::wxyz |
Rotation quaternion.
Definition at line 277 of file problem_description.h.
| Eigen::Vector3d trajopt_interface::CartPoseTermInfo::xyz |
Cartesian position.
Definition at line 275 of file problem_description.h.