moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
This class combines CartesianLimit and JointLimits into on single class. More...
#include <limits_container.h>
Public Member Functions | |
LimitsContainer () | |
bool | hasJointLimits () const |
Return if this LimitsContainer has defined joint limits. More... | |
void | setJointLimits (JointLimitsContainer &joint_limits) |
Set joint limits. More... | |
const JointLimitsContainer & | getJointLimitContainer () const |
Obtain the Joint Limits from the container. More... | |
bool | hasFullCartesianLimits () const |
Return if this LimitsContainer has defined cartesian limits. More... | |
void | setCartesianLimits (CartesianLimit &cartesian_limit) |
Set cartesian limits. More... | |
const CartesianLimit & | getCartesianLimits () const |
Return the cartesian limits. More... | |
This class combines CartesianLimit and JointLimits into on single class.
Definition at line 47 of file limits_container.h.
pilz_industrial_motion_planner::LimitsContainer::LimitsContainer | ( | ) |
Definition at line 37 of file limits_container.cpp.
const pilz_industrial_motion_planner::CartesianLimit & pilz_industrial_motion_planner::LimitsContainer::getCartesianLimits | ( | ) | const |
Return the cartesian limits.
Definition at line 75 of file limits_container.cpp.
const pilz_industrial_motion_planner::JointLimitsContainer & pilz_industrial_motion_planner::LimitsContainer::getJointLimitContainer | ( | ) | const |
Obtain the Joint Limits from the container.
Definition at line 55 of file limits_container.cpp.
bool pilz_industrial_motion_planner::LimitsContainer::hasFullCartesianLimits | ( | ) | const |
Return if this LimitsContainer has defined cartesian limits.
Definition at line 60 of file limits_container.cpp.
bool pilz_industrial_motion_planner::LimitsContainer::hasJointLimits | ( | ) | const |
Return if this LimitsContainer has defined joint limits.
Definition at line 42 of file limits_container.cpp.
void pilz_industrial_motion_planner::LimitsContainer::setCartesianLimits | ( | pilz_industrial_motion_planner::CartesianLimit & | cartesian_limit | ) |
Set cartesian limits.
cartesian_limit |
Definition at line 67 of file limits_container.cpp.
void pilz_industrial_motion_planner::LimitsContainer::setJointLimits | ( | pilz_industrial_motion_planner::JointLimitsContainer & | joint_limits | ) |
Set joint limits.
joint_limits |
Definition at line 47 of file limits_container.cpp.