#include <environment_chain3d_types.h>
Public Member Functions | |
bool | canGetCloser (double start, double goal, double delta) |
double | getDoubleDistance (double start, double end) |
int | getIntegerDistance (double start, double end, double delta) |
bool | getSuccessorValue (double start, double delta, double &end) |
JointMotionWrapper (const planning_models::RobotModel::JointModel *joint_model) | |
Protected Attributes | |
moveit_msgs::JointLimits | joint_limit_ |
const planning_models::RobotModel::JointModel * | joint_model_ |
Definition at line 175 of file environment_chain3d_types.h.
sbpl_interface::JointMotionWrapper::JointMotionWrapper | ( | const planning_models::RobotModel::JointModel * | joint_model | ) | [inline] |
Definition at line 178 of file environment_chain3d_types.h.
bool sbpl_interface::JointMotionWrapper::canGetCloser | ( | double | start, |
double | goal, | ||
double | delta | ||
) | [inline] |
Definition at line 213 of file environment_chain3d_types.h.
double sbpl_interface::JointMotionWrapper::getDoubleDistance | ( | double | start, |
double | end | ||
) | [inline] |
Definition at line 234 of file environment_chain3d_types.h.
int sbpl_interface::JointMotionWrapper::getIntegerDistance | ( | double | start, |
double | end, | ||
double | delta | ||
) | [inline] |
Definition at line 243 of file environment_chain3d_types.h.
bool sbpl_interface::JointMotionWrapper::getSuccessorValue | ( | double | start, |
double | delta, | ||
double & | end | ||
) | [inline] |
Definition at line 185 of file environment_chain3d_types.h.
moveit_msgs::JointLimits sbpl_interface::JointMotionWrapper::joint_limit_ [protected] |
Definition at line 260 of file environment_chain3d_types.h.
const planning_models::RobotModel::JointModel* sbpl_interface::JointMotionWrapper::joint_model_ [protected] |
Definition at line 259 of file environment_chain3d_types.h.