moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | List of all members
trajopt_interface::TrajOptProblem Class Reference

#include <problem_description.h>

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

Public Member Functions

 TrajOptProblem ()
 
 TrajOptProblem (const ProblemInfo &problem_info)
 
virtual ~TrajOptProblem ()=default
 
sco::VarVector GetVarRow (int i, int start_col, int num_col)
 Returns the values of the specified joints (start_col to num_col) for the specified timestep i. More...
 
sco::VarVector GetVarRow (int i)
 Returns the values of all joints for the specified timestep i. More...
 
sco::Var & GetVar (int i, int j)
 Returns the value of the specified joint j for the specified timestep i. More...
 
trajopt::VarArray & GetVars ()
 
int GetNumSteps ()
 Returns the number of steps in the problem. This is the number of rows in the optimization matrix. More...
 
int GetNumDOF ()
 Returns the problem DOF. This is the number of columns in the optization matrix. Note that this is not necessarily the same as the kinematic DOF. More...
 
int GetActiveGroupNumDOF ()
 Returns the kinematic DOF of the active joint model group. More...
 
planning_scene::PlanningSceneConstPtr GetPlanningScene ()
 
void SetInitTraj (const trajopt::TrajArray &x)
 
trajopt::TrajArray GetInitTraj ()
 
bool GetHasTime ()
 Returns TrajOptProb.has_time. More...
 
void SetHasTime (bool tmp)
 Sets TrajOptProb.has_time
More...
 

Detailed Description

Holds all the data for a trajectory optimization problem so you can modify it programmatically, e.g. add your own costs

Definition at line 186 of file problem_description.h.

Constructor & Destructor Documentation

◆ TrajOptProblem() [1/2]

trajopt_interface::TrajOptProblem::TrajOptProblem ( )

Definition at line 75 of file problem_description.cpp.

◆ TrajOptProblem() [2/2]

trajopt_interface::TrajOptProblem::TrajOptProblem ( const ProblemInfo problem_info)

Definition at line 79 of file problem_description.cpp.

Here is the call graph for this function:

◆ ~TrajOptProblem()

virtual trajopt_interface::TrajOptProblem::~TrajOptProblem ( )
virtualdefault

Member Function Documentation

◆ GetActiveGroupNumDOF()

int trajopt_interface::TrajOptProblem::GetActiveGroupNumDOF ( )
inline

Returns the kinematic DOF of the active joint model group.

Definition at line 224 of file problem_description.h.

Here is the caller graph for this function:

◆ GetHasTime()

bool trajopt_interface::TrajOptProblem::GetHasTime ( )
inline

Returns TrajOptProb.has_time.

Definition at line 242 of file problem_description.h.

Here is the caller graph for this function:

◆ GetInitTraj()

trajopt::TrajArray trajopt_interface::TrajOptProblem::GetInitTraj ( )
inline

Definition at line 236 of file problem_description.h.

◆ GetNumDOF()

int trajopt_interface::TrajOptProblem::GetNumDOF ( )
inline

Returns the problem DOF. This is the number of columns in the optization matrix. Note that this is not necessarily the same as the kinematic DOF.

Definition at line 218 of file problem_description.h.

Here is the caller graph for this function:

◆ GetNumSteps()

int trajopt_interface::TrajOptProblem::GetNumSteps ( )
inline

Returns the number of steps in the problem. This is the number of rows in the optimization matrix.

Definition at line 212 of file problem_description.h.

Here is the caller graph for this function:

◆ GetPlanningScene()

planning_scene::PlanningSceneConstPtr trajopt_interface::TrajOptProblem::GetPlanningScene ( )
inline

Definition at line 228 of file problem_description.h.

Here is the caller graph for this function:

◆ GetVar()

sco::Var& trajopt_interface::TrajOptProblem::GetVar ( int  i,
int  j 
)
inline

Returns the value of the specified joint j for the specified timestep i.

Definition at line 203 of file problem_description.h.

◆ GetVarRow() [1/2]

sco::VarVector trajopt_interface::TrajOptProblem::GetVarRow ( int  i)
inline

Returns the values of all joints for the specified timestep i.

Definition at line 198 of file problem_description.h.

◆ GetVarRow() [2/2]

sco::VarVector trajopt_interface::TrajOptProblem::GetVarRow ( int  i,
int  start_col,
int  num_col 
)
inline

Returns the values of the specified joints (start_col to num_col) for the specified timestep i.

Definition at line 193 of file problem_description.h.

Here is the caller graph for this function:

◆ GetVars()

trajopt::VarArray& trajopt_interface::TrajOptProblem::GetVars ( )
inline

Definition at line 207 of file problem_description.h.

Here is the caller graph for this function:

◆ SetHasTime()

void trajopt_interface::TrajOptProblem::SetHasTime ( bool  tmp)
inline

Sets TrajOptProb.has_time

Definition at line 247 of file problem_description.h.

◆ SetInitTraj()

void trajopt_interface::TrajOptProblem::SetInitTraj ( const trajopt::TrajArray &  x)
inline

Definition at line 232 of file problem_description.h.


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