active_joint_model_name_vector_ | moveit::core::JointModelGroup | protected |
active_joint_model_start_index_ | moveit::core::JointModelGroup | protected |
active_joint_model_vector_ | moveit::core::JointModelGroup | protected |
active_joint_models_bounds_ | moveit::core::JointModelGroup | protected |
active_variable_count_ | moveit::core::JointModelGroup | protected |
addDefaultState(const std::string &name, const std::map< std::string, double > &default_state) | moveit::core::JointModelGroup | |
attached_end_effector_names_ | moveit::core::JointModelGroup | protected |
attachEndEffector(const std::string &eef_name) | moveit::core::JointModelGroup | |
canSetStateFromIK(const std::string &tip) const | moveit::core::JointModelGroup | |
common_root_ | moveit::core::JointModelGroup | protected |
computeJointVariableIndices(const std::vector< std::string > &joint_names, std::vector< size_t > &joint_bijection) const | moveit::core::JointModelGroup | |
config_ | moveit::core::JointModelGroup | protected |
continuous_joint_model_vector_ | moveit::core::JointModelGroup | protected |
default_states_ | moveit::core::JointModelGroup | protected |
default_states_names_ | moveit::core::JointModelGroup | protected |
distance(const double *state1, const double *state2) const | moveit::core::JointModelGroup | |
end_effector_name_ | moveit::core::JointModelGroup | protected |
end_effector_parent_ | moveit::core::JointModelGroup | protected |
enforcePositionBounds(double *state) const | moveit::core::JointModelGroup | inline |
enforcePositionBounds(double *state, const JointBoundsVector &active_joint_bounds) const | moveit::core::JointModelGroup | |
fixed_joints_ | moveit::core::JointModelGroup | protected |
getActiveJointModelNames() const | moveit::core::JointModelGroup | inline |
getActiveJointModels() const | moveit::core::JointModelGroup | inline |
getActiveJointModelsBounds() const | moveit::core::JointModelGroup | inline |
getActiveVariableCount() const | moveit::core::JointModelGroup | inline |
getAttachedEndEffectorNames() const | moveit::core::JointModelGroup | inline |
getCommonRoot() const | moveit::core::JointModelGroup | inline |
getConfig() const | moveit::core::JointModelGroup | inline |
getContinuousJointModels() const | moveit::core::JointModelGroup | inline |
getDefaultIKTimeout() const | moveit::core::JointModelGroup | inline |
getDefaultStateNames() const | moveit::core::JointModelGroup | inline |
getEndEffectorName() const | moveit::core::JointModelGroup | inline |
getEndEffectorParentGroup() const | moveit::core::JointModelGroup | inline |
getEndEffectorTips(std::vector< const LinkModel * > &tips) const | moveit::core::JointModelGroup | |
getEndEffectorTips(std::vector< std::string > &tips) const | moveit::core::JointModelGroup | |
getFixedJointModels() const | moveit::core::JointModelGroup | inline |
getGroupKinematics() const | moveit::core::JointModelGroup | inline |
getJointModel(const std::string &joint) const | moveit::core::JointModelGroup | |
getJointModelNames() const | moveit::core::JointModelGroup | inline |
getJointModels() const | moveit::core::JointModelGroup | inline |
getJointRoots() const | moveit::core::JointModelGroup | inline |
getKinematicsSolverJointBijection() const | moveit::core::JointModelGroup | inline |
getLinkModel(const std::string &link) const | moveit::core::JointModelGroup | |
getLinkModelNames() const | moveit::core::JointModelGroup | inline |
getLinkModelNamesWithCollisionGeometry() const | moveit::core::JointModelGroup | inline |
getLinkModels() const | moveit::core::JointModelGroup | inline |
getLowerAndUpperLimits() const | moveit::core::JointModelGroup | |
getMaximumExtent() const | moveit::core::JointModelGroup | inline |
getMaximumExtent(const JointBoundsVector &active_joint_bounds) const | moveit::core::JointModelGroup | |
getMaxVelocitiesAndAccelerationBounds() const | moveit::core::JointModelGroup | |
getMimicJointModels() const | moveit::core::JointModelGroup | inline |
getName() const | moveit::core::JointModelGroup | inline |
getOnlyOneEndEffectorTip() const | moveit::core::JointModelGroup | |
getParentModel() const | moveit::core::JointModelGroup | inline |
getSolverInstance() const | moveit::core::JointModelGroup | inline |
getSolverInstance() | moveit::core::JointModelGroup | inline |
getSubgroupNames() const | moveit::core::JointModelGroup | inline |
getSubgroups(std::vector< const JointModelGroup * > &sub_groups) const | moveit::core::JointModelGroup | |
getUpdatedLinkModelNames() const | moveit::core::JointModelGroup | inline |
getUpdatedLinkModels() const | moveit::core::JointModelGroup | inline |
getUpdatedLinkModelsSet() const | moveit::core::JointModelGroup | inline |
getUpdatedLinkModelsWithGeometry() const | moveit::core::JointModelGroup | inline |
getUpdatedLinkModelsWithGeometryNames() const | moveit::core::JointModelGroup | inline |
getUpdatedLinkModelsWithGeometryNamesSet() const | moveit::core::JointModelGroup | inline |
getUpdatedLinkModelsWithGeometrySet() const | moveit::core::JointModelGroup | inline |
getVariableCount() const | moveit::core::JointModelGroup | inline |
getVariableDefaultPositions(const std::string &name, std::map< std::string, double > &values) const | moveit::core::JointModelGroup | |
getVariableDefaultPositions(std::map< std::string, double > &values) const | moveit::core::JointModelGroup | |
getVariableDefaultPositions(std::vector< double > &values) const | moveit::core::JointModelGroup | inline |
getVariableDefaultPositions(double *values) const | moveit::core::JointModelGroup | |
getVariableGroupIndex(const std::string &variable) const | moveit::core::JointModelGroup | |
getVariableIndexList() const | moveit::core::JointModelGroup | inline |
getVariableNames() const | moveit::core::JointModelGroup | inline |
getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values) const | moveit::core::JointModelGroup | inline |
getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, std::vector< double > &values) const | moveit::core::JointModelGroup | inline |
getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values, const JointBoundsVector &active_joint_bounds) const | moveit::core::JointModelGroup | |
getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator &rng, double *values, const double *near, const double distance) const | moveit::core::JointModelGroup | inline |
getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator &rng, std::vector< double > &values, const std::vector< double > &near, double distance) const | moveit::core::JointModelGroup | inline |
getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator &rng, std::vector< double > &values, const std::vector< double > &near, const std::map< JointModel::JointType, double > &distance_map) const | moveit::core::JointModelGroup | inline |
getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator &rng, double *values, const double *near, const std::vector< double > &distances) const | moveit::core::JointModelGroup | inline |
getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator &rng, std::vector< double > &values, const std::vector< double > &near, const std::vector< double > &distances) const | moveit::core::JointModelGroup | inline |
getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator &rng, double *values, const JointBoundsVector &active_joint_bounds, const double *near, const double distance) const | moveit::core::JointModelGroup | |
getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator &rng, double *values, const JointBoundsVector &active_joint_bounds, const double *near, const std::map< JointModel::JointType, double > &distance_map) const | moveit::core::JointModelGroup | |
getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator &rng, double *values, const JointBoundsVector &active_joint_bounds, const double *near, const std::vector< double > &distances) const | moveit::core::JointModelGroup | |
group_kinematics_ | moveit::core::JointModelGroup | protected |
group_mimic_update_ | moveit::core::JointModelGroup | protected |
hasJointModel(const std::string &joint) const | moveit::core::JointModelGroup | |
hasLinkModel(const std::string &link) const | moveit::core::JointModelGroup | |
interpolate(const double *from, const double *to, double t, double *state) const | moveit::core::JointModelGroup | |
is_chain_ | moveit::core::JointModelGroup | protected |
is_contiguous_index_list_ | moveit::core::JointModelGroup | protected |
is_single_dof_ | moveit::core::JointModelGroup | protected |
isChain() const | moveit::core::JointModelGroup | inline |
isContiguousWithinState() const | moveit::core::JointModelGroup | inline |
isEndEffector() const | moveit::core::JointModelGroup | inline |
isLinkUpdated(const std::string &name) const | moveit::core::JointModelGroup | inline |
isSingleDOFJoints() const | moveit::core::JointModelGroup | inline |
isSubgroup(const std::string &group) const | moveit::core::JointModelGroup | inline |
isValidVelocityMove(const std::vector< double > &from_joint_pose, const std::vector< double > &to_joint_pose, double dt) const | moveit::core::JointModelGroup | |
isValidVelocityMove(const double *from_joint_pose, const double *to_joint_pose, std::size_t array_size, double dt) const | moveit::core::JointModelGroup | |
joint_model_map_ | moveit::core::JointModelGroup | protected |
joint_model_name_vector_ | moveit::core::JointModelGroup | protected |
joint_model_vector_ | moveit::core::JointModelGroup | protected |
joint_roots_ | moveit::core::JointModelGroup | protected |
joint_variables_index_map_ | moveit::core::JointModelGroup | protected |
JointModelGroup(const std::string &name, const srdf::Model::Group &config, const std::vector< const JointModel * > &joint_vector, const RobotModel *parent_model) | moveit::core::JointModelGroup | |
KinematicsSolverMap typedef | moveit::core::JointModelGroup | |
link_model_map_ | moveit::core::JointModelGroup | protected |
link_model_name_vector_ | moveit::core::JointModelGroup | protected |
link_model_vector_ | moveit::core::JointModelGroup | protected |
link_model_with_geometry_name_vector_ | moveit::core::JointModelGroup | protected |
link_model_with_geometry_vector_ | moveit::core::JointModelGroup | protected |
mimic_joints_ | moveit::core::JointModelGroup | protected |
name_ | moveit::core::JointModelGroup | protected |
parent_model_ | moveit::core::JointModelGroup | protected |
printGroupInfo(std::ostream &out=std::cout) const | moveit::core::JointModelGroup | |
satisfiesPositionBounds(const double *state, double margin=0.0) const | moveit::core::JointModelGroup | inline |
satisfiesPositionBounds(const double *state, const JointBoundsVector &active_joint_bounds, double margin=0.0) const | moveit::core::JointModelGroup | |
setDefaultIKTimeout(double ik_timeout) | moveit::core::JointModelGroup | |
setEndEffectorName(const std::string &name) | moveit::core::JointModelGroup | |
setEndEffectorParent(const std::string &group, const std::string &link) | moveit::core::JointModelGroup | |
setRedundantJoints(const std::vector< std::string > &joints) | moveit::core::JointModelGroup | inline |
setSolverAllocators(const SolverAllocatorFn &solver, const SolverAllocatorMapFn &solver_map=SolverAllocatorMapFn()) | moveit::core::JointModelGroup | inline |
setSolverAllocators(const std::pair< SolverAllocatorFn, SolverAllocatorMapFn > &solvers) | moveit::core::JointModelGroup | |
setSubgroupNames(const std::vector< std::string > &subgroups) | moveit::core::JointModelGroup | |
subgroup_names_ | moveit::core::JointModelGroup | protected |
subgroup_names_set_ | moveit::core::JointModelGroup | protected |
updated_link_model_name_set_ | moveit::core::JointModelGroup | protected |
updated_link_model_name_vector_ | moveit::core::JointModelGroup | protected |
updated_link_model_set_ | moveit::core::JointModelGroup | protected |
updated_link_model_vector_ | moveit::core::JointModelGroup | protected |
updated_link_model_with_geometry_name_set_ | moveit::core::JointModelGroup | protected |
updated_link_model_with_geometry_name_vector_ | moveit::core::JointModelGroup | protected |
updated_link_model_with_geometry_set_ | moveit::core::JointModelGroup | protected |
updated_link_model_with_geometry_vector_ | moveit::core::JointModelGroup | protected |
updateMimicJoints(double *values) const | moveit::core::JointModelGroup | protected |
variable_count_ | moveit::core::JointModelGroup | protected |
variable_index_list_ | moveit::core::JointModelGroup | protected |
variable_names_ | moveit::core::JointModelGroup | protected |
variable_names_set_ | moveit::core::JointModelGroup | protected |
~JointModelGroup() | moveit::core::JointModelGroup | |