Data class storing all information regarding a Sequence command.
More...
#include <sequence.h>
|
void | add (const CmdVariant &cmd, const double blend_radius=0.) |
| Adds a command to the end of the sequence. More...
|
|
size_t | size () const |
| Returns the number of commands. More...
|
|
template<class T > |
T & | getCmd (const size_t index_cmd) |
|
template<class T > |
const T & | getCmd (const size_t index_cmd) const |
|
template<class T > |
bool | cmdIsOfType (const size_t index_cmd) const |
|
MotionCmd & | getCmd (const size_t index_cmd) |
| Returns the specific command as base class reference. This function allows the user to operate on the sequence without having knowledge of the underlying specific command type. More...
|
|
void | setAllBlendRadiiToZero () |
|
void | setBlendRadius (const size_t index_cmd, const double blend_radius) |
|
double | getBlendRadius (const size_t index_cmd) const |
|
void | erase (const size_t start, const size_t end) |
| Deletes all commands from index 'start' to index 'end'. More...
|
|
moveit_msgs::msg::MotionSequenceRequest | toRequest () const |
|
Data class storing all information regarding a Sequence command.
Definition at line 53 of file sequence.h.
◆ add()
void pilz_industrial_motion_planner_testutils::Sequence::add |
( |
const CmdVariant & |
cmd, |
|
|
const double |
blend_radius = 0. |
|
) |
| |
|
inline |
Adds a command to the end of the sequence.
- Parameters
-
cmd | The command which has to be added. |
Definition at line 103 of file sequence.h.
◆ cmdIsOfType()
template<class T >
bool pilz_industrial_motion_planner_testutils::Sequence::cmdIsOfType |
( |
const size_t |
index_cmd | ) |
const |
|
inline |
- Returns
- TRUE if the specified command is of the specified type, otherwise FALSE.
Definition at line 141 of file sequence.h.
◆ erase()
void pilz_industrial_motion_planner_testutils::Sequence::erase |
( |
const size_t |
start, |
|
|
const size_t |
end |
|
) |
| |
Deletes all commands from index 'start' to index 'end'.
Definition at line 94 of file sequence.cpp.
◆ getBlendRadius()
double pilz_industrial_motion_planner_testutils::Sequence::getBlendRadius |
( |
const size_t |
index_cmd | ) |
const |
|
inline |
◆ getCmd() [1/3]
template<class T >
T & pilz_industrial_motion_planner_testutils::Sequence::getCmd |
( |
const size_t |
index_cmd | ) |
|
|
inline |
◆ getCmd() [2/3]
MotionCmd & pilz_industrial_motion_planner_testutils::Sequence::getCmd |
( |
const size_t |
index_cmd | ) |
|
Returns the specific command as base class reference. This function allows the user to operate on the sequence without having knowledge of the underlying specific command type.
Definition at line 114 of file sequence.cpp.
◆ getCmd() [3/3]
template<class T >
const T & pilz_industrial_motion_planner_testutils::Sequence::getCmd |
( |
const size_t |
index_cmd | ) |
const |
|
inline |
◆ setAllBlendRadiiToZero()
void pilz_industrial_motion_planner_testutils::Sequence::setAllBlendRadiiToZero |
( |
| ) |
|
|
inline |
◆ setBlendRadius()
void pilz_industrial_motion_planner_testutils::Sequence::setBlendRadius |
( |
const size_t |
index_cmd, |
|
|
const double |
blend_radius |
|
) |
| |
|
inline |
◆ size()
size_t pilz_industrial_motion_planner_testutils::Sequence::size |
( |
| ) |
const |
|
inline |
Returns the number of commands.
Definition at line 108 of file sequence.h.
◆ toRequest()
moveit_msgs::msg::MotionSequenceRequest pilz_industrial_motion_planner_testutils::Sequence::toRequest |
( |
| ) |
const |
The documentation for this class was generated from the following files:
- moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h
- moveit_planners/pilz_industrial_motion_planner_testutils/src/sequence.cpp