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

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...

#include <problem_description.h>

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

Public Member Functions

 JointPoseTermInfo ()
 Initialize term with it's supported types. More...
 
void addObjectiveTerms (TrajOptProblem &prob) override
 Converts term info into cost/constraint and adds it to trajopt problem. 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

trajopt::DblVec coeffs
 Vector of coefficients that scale the cost. Size should be the DOF of the system. Default: vector of 0's. More...
 
trajopt::DblVec targets
 Vector of position targets. This is a required value. Size should be the DOF of the system. More...
 
trajopt::DblVec upper_tols
 Vector of position upper limits. Size should be the DOF of the system. Default: vector of 0's. More...
 
trajopt::DblVec lower_tols
 Vector of position lower limits. Size should be the DOF of the system. Default: vector of 0's. More...
 
int first_step = 0
 First time step to which the term is applied. Default: 0. More...
 
int last_step = -1
 Last time step to which the term is applied. Default: prob.GetNumSteps() - 1. 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

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.

\begin{align*} \sum_i c_i (x_i - xtarg_i)^2 \end{align*}

where $i$ indexes over dof and $c_i$ are coeffs

Definition at line 308 of file problem_description.h.

Constructor & Destructor Documentation

◆ JointPoseTermInfo()

trajopt_interface::JointPoseTermInfo::JointPoseTermInfo ( )
inline

Initialize term with it's supported types.

Definition at line 324 of file problem_description.h.

Member Function Documentation

◆ addObjectiveTerms()

void trajopt_interface::JointPoseTermInfo::addObjectiveTerms ( TrajOptProblem prob)
overridevirtual

Converts term info into cost/constraint and adds it to trajopt problem.

Implements trajopt_interface::TermInfo.

Definition at line 310 of file problem_description.cpp.

Here is the call graph for this function:

◆ create()

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

Definition at line 331 of file problem_description.h.

Member Data Documentation

◆ coeffs

trajopt::DblVec trajopt_interface::JointPoseTermInfo::coeffs

Vector of coefficients that scale the cost. Size should be the DOF of the system. Default: vector of 0's.

Definition at line 311 of file problem_description.h.

◆ first_step

int trajopt_interface::JointPoseTermInfo::first_step = 0

First time step to which the term is applied. Default: 0.

Definition at line 319 of file problem_description.h.

◆ last_step

int trajopt_interface::JointPoseTermInfo::last_step = -1

Last time step to which the term is applied. Default: prob.GetNumSteps() - 1.

Definition at line 321 of file problem_description.h.

◆ lower_tols

trajopt::DblVec trajopt_interface::JointPoseTermInfo::lower_tols

Vector of position lower limits. Size should be the DOF of the system. Default: vector of 0's.

Definition at line 317 of file problem_description.h.

◆ targets

trajopt::DblVec trajopt_interface::JointPoseTermInfo::targets

Vector of position targets. This is a required value. Size should be the DOF of the system.

Definition at line 313 of file problem_description.h.

◆ upper_tols

trajopt::DblVec trajopt_interface::JointPoseTermInfo::upper_tols

Vector of position upper limits. Size should be the DOF of the system. Default: vector of 0's.

Definition at line 315 of file problem_description.h.


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