moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | Static Public Member Functions | Public Attributes | List of all members
trajopt_interface::CartPoseTermInfo Struct Reference

This term is used when the goal frame is fixed in cartesian space. More...

#include <problem_description.h>

Inheritance diagram for trajopt_interface::CartPoseTermInfo:
Inheritance graph
[legend]
Collaboration diagram for trajopt_interface::CartPoseTermInfo:
Collaboration graph
[legend]

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
 
TermInfooperator= (const TermInfo &)=default
 
TermInfooperator= (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)
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ CartPoseTermInfo()

trajopt_interface::CartPoseTermInfo::CartPoseTermInfo ( )

Definition at line 268 of file problem_description.cpp.

Member Function Documentation

◆ addObjectiveTerms()

void trajopt_interface::CartPoseTermInfo::addObjectiveTerms ( TrajOptProblem prob)
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.

Here is the call graph for this function:

◆ create()

static TermInfoPtr trajopt_interface::CartPoseTermInfo::create ( )
inlinestatic

Definition at line 292 of file problem_description.h.

Member Data Documentation

◆ link

std::string trajopt_interface::CartPoseTermInfo::link

Link which should reach desired pose.

Definition at line 281 of file problem_description.h.

◆ pos_coeffs

Eigen::Vector3d trajopt_interface::CartPoseTermInfo::pos_coeffs

coefficients for position and rotation

Definition at line 279 of file problem_description.h.

◆ rot_coeffs

Eigen::Vector3d trajopt_interface::CartPoseTermInfo::rot_coeffs

Definition at line 279 of file problem_description.h.

◆ tcp

Eigen::Isometry3d trajopt_interface::CartPoseTermInfo::tcp

Static transform applied to the link.

Definition at line 283 of file problem_description.h.

◆ timestep

int trajopt_interface::CartPoseTermInfo::timestep

Timestep at which to apply term.

Definition at line 273 of file problem_description.h.

◆ wxyz

Eigen::Vector4d trajopt_interface::CartPoseTermInfo::wxyz

Rotation quaternion.

Definition at line 277 of file problem_description.h.

◆ xyz

Eigen::Vector3d trajopt_interface::CartPoseTermInfo::xyz

Cartesian position.

Definition at line 275 of file problem_description.h.


The documentation for this struct was generated from the following files: