|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <problem_description.h>

Public Types | |
| using | MakerFunc = TermInfoPtr(*)(void) |
Public Member Functions | |
| int | getSupportedTypes () |
| virtual void | addObjectiveTerms (TrajOptProblem &prob)=0 |
| 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 | fromName (const std::string &type) |
| static void | RegisterMaker (const std::string &type, MakerFunc) |
Public Attributes | |
| std::string | name |
| int | term_type |
Protected Member Functions | |
| TermInfo (int supported_term_types) | |
When cost or constraint element of JSON doc is read, one of these guys gets constructed to hold the parameters. Then it later gets converted to a Cost object by the addObjectiveTerms method
Definition at line 127 of file problem_description.h.
| using trajopt_interface::TermInfo::MakerFunc = TermInfoPtr (*)(void) |
Registers a user-defined TermInfo so you can use your own cost see function RegisterMakers.cpp
Definition at line 144 of file problem_description.h.
|
default |
|
default |
|
default |
|
virtualdefault |
|
inlineprotected |
Definition at line 155 of file problem_description.h.
|
pure virtual |
|
static |
|
inline |
Definition at line 131 of file problem_description.h.
|
static |
| std::string trajopt_interface::TermInfo::name |
Definition at line 129 of file problem_description.h.
| int trajopt_interface::TermInfo::term_type |
Definition at line 130 of file problem_description.h.