Go to the documentation of this file.
55 #include <Eigen/Geometry>
68 if (std::isnan(t) || std::isinf(t))
70 throw Exception(
"Interpolation parameter is NaN or inf.");
87 const std::string&
getName()
const
108 const urdf::ModelInterfaceSharedPtr&
getURDF()
const
142 const JointModel*
getJointModel(
const std::string& joint)
const;
274 Eigen::Isometry3d& transform,
279 Eigen::Isometry3d unused;
347 std::map<std::string, double>& values)
const;
362 double margin = 0.0)
const;
370 double distance(
const double* state1,
const double* state2)
const;
380 void interpolate(
const double* from,
const double* to,
double t,
double* state)
const;
417 const JointModelGroup*
getEndEffector(
const std::string& name)
const;
458 std::vector<std::string>& missing_variables)
const;
498 urdf::ModelInterfaceSharedPtr
urdf_;
A link from the robot. Contains the constant transform applied to the link and its geometry.
Core components of MoveIt.
const std::string & getModelFrame() const
Get the frame in which the transforms for this model are computed (when using a RobotState)....
locale-agnostic conversion functions from floating point numbers to strings
std::size_t variable_count_
Get the number of variables necessary to describe this model.
const std::vector< const LinkModel * > & getLinkModels() const
Get the array of links
const JointModel * getJointModel(const std::string &joint) const
Get a joint by its name. Output error and return NULL when the joint is missing.
const std::vector< std::string > & getActiveJointModelNames() const
Get the array of active joint names, in the order they appear in the robot state.
std::vector< const JointModelGroup * > end_effectors_
The array of end-effectors, in alphabetical order.
const srdf::ModelConstSharedPtr & getSRDF() const
Get the parsed SRDF model.
std::vector< JointModel * > active_joint_model_vector_
The vector of joints in the model, in the order they appear in the state vector.
std::vector< const JointModel * > active_joint_model_vector_const_
The vector of joints in the model, in the order they appear in the state vector.
const urdf::ModelInterfaceSharedPtr & getURDF() const
Get the parsed URDF model.
void setKinematicsAllocators(const std::map< std::string, SolverAllocatorFn > &allocators)
A map of known kinematics solvers (associated to their group name)
LinkModel * constructLinkModel(const urdf::Link *urdf_link)
Given a urdf link, build the corresponding LinkModel object.
std::vector< const JointModel * > joint_model_vector_const_
The vector of joints in the model, in the order they appear in the state vector.
bool addJointModelGroup(const srdf::Model::Group &group)
Construct a JointModelGroup given a SRDF description group.
std::vector< const JointModelGroup * > joint_model_groups_const_
The array of joint model groups, in alphabetical order.
void buildGroupsInfoSubgroups()
Compute helpful information about groups (that can be queried later)
std::map< std::string, int > VariableIndexMap
Data type for holding mappings from variable names to their position in a state vector.
static const moveit::core::LinkModel * getRigidlyConnectedParentLinkModel(const LinkModel *link, Eigen::Isometry3d &transform, const JointModelGroup *jmg=nullptr)
Get the latest link upwards the kinematic tree, which is only connected via fixed joints.
const std::string & getName() const
Get the name of the joint.
std::size_t link_geometry_count_
Total number of geometric shapes in this model.
void computeDescendants()
For every joint, pre-compute the list of descendant joints & links.
std::vector< std::string > joint_model_names_vector_
The vector of joint names that corresponds to joint_model_vector_.
const VariableBounds & getVariableBounds(const std::string &variable) const
Get the bounds for a specific variable. Throw an exception of variable is not found.
std::vector< const JointModel * > continuous_joint_model_vector_
The set of continuous joints this model contains.
const JointModel * getRootJoint() const
Get the root joint. There will be one root joint unless the model is empty. This is either extracted ...
std::vector< JointModel * > joint_model_vector_
The vector of joints in the model, in the order they appear in the state vector.
JointModelGroupMap joint_model_group_map_
A map from group names to joint groups.
std::vector< const JointModel::Bounds * > JointBoundsVector
std::size_t getLinkGeometryCount() const
std::size_t getVariableCount() const
Get the number of variables that describe this model.
JointModel * buildRecursive(LinkModel *parent, const urdf::Link *link, const srdf::Model &srdf_model)
(This function is mostly intended for internal use). Given a parent link, build up (recursively),...
void computeCommonRoots()
For every pair of joints, pre-compute the common roots of the joints.
std::vector< std::string > joint_model_group_names_
A vector of all group names, in alphabetical order.
std::vector< JointModelGroup * > joint_model_groups_
The array of joint model groups, in alphabetical order.
const JointModelGroup * getJointModelGroup(const std::string &name) const
Get a joint group from this model (by name)
void buildMimic(const urdf::ModelInterface &urdf_model)
Given the URDF model, build up the mimic joints (mutually constrained joints)
void interpolate(const double *from, const double *to, double t, double *state) const
JointModelMap joint_model_map_
A map from joint names to their instances.
std::vector< const JointModel * > single_dof_joints_
LinkModelMap link_model_map_
A map from link names to their instances.
std::vector< const LinkModel * > link_model_vector_const_
The vector of links that are updated when computeTransforms() is called, in the order they are update...
srdf::ModelConstSharedPtr srdf_
std::vector< LinkModel * > link_model_vector_
The vector of links that are updated when computeTransforms() is called, in the order they are update...
const std::vector< const JointModelGroup * > & getEndEffectors() const
Get the map between end effector names and the groups they correspond to.
double getMaximumExtent() const
bool hasEndEffector(const std::string &eef) const
Check if an end effector exists.
std::shared_ptr< Shape > ShapePtr
std::map< std::string, JointModel * > JointModelMap
Map of names to instances for JointModel.
std::vector< const LinkModel * > link_models_with_collision_geometry_vector_
Only links that have collision geometry specified.
std::vector< int > common_joint_roots_
For every two joints, the index of the common root for thw joints is stored.
const std::vector< const LinkModel * > & getLinkModelsWithCollisionGeometry() const
Get the link models that have some collision geometry associated to themselves.
bool isEmpty() const
Return true if the model is empty (has no root link, no joints)
const VariableBounds & getVariableBounds(const std::string &variable) const
Get the bounds for a variable. Throw an exception if the variable was not found.
std::vector< const JointModel * > mimic_joints_
The set of mimic joints this model contains.
const std::vector< std::string > & getJointModelGroupNames() const
Get the names of all groups that are defined for this model.
const std::vector< std::string > & getVariableNames() const
Get the names of the variables that make up the joints that form this state. Fixed joints have no DOF...
std::string model_frame_
The reference (base) frame for this model. The frame is either extracted from the SRDF as a virtual j...
std::vector< const JointModel * > multi_dof_joints_
const LinkModel * root_link_
The first physical link for the robot.
std::vector< std::string > link_model_names_vector_
The vector of link names that corresponds to link_model_vector_.
urdf::ModelInterfaceSharedPtr urdf_
RobotModel(const urdf::ModelInterfaceSharedPtr &urdf_model, const srdf::ModelConstSharedPtr &srdf_model)
Construct a kinematic model from a parsed description and a list of planning groups.
const JointModel * getJointOfVariable(int variable_index) const
void buildGroupsInfoEndEffectors(const srdf::Model &srdf_model)
Compute helpful information about groups (that can be queried later)
std::shared_ptr< const Model > ModelConstSharedPtr
void computeFixedTransforms(const LinkModel *link, const Eigen::Isometry3d &transform, LinkTransformMap &associated_transforms)
Get the transforms between link and all its rigidly attached descendants.
bool hasJointModelGroup(const std::string &group) const
Check if the JointModelGroup group exists.
std::vector< const JointModel * > joints_of_variable_
The joints that correspond to each variable index.
const std::vector< const JointModel * > & getActiveJointModels() const
Get the array of joints that are active (not fixed, not mimic) in this model.
bool satisfiesPositionBounds(const double *state, double margin=0.0) const
JointBoundsVector active_joint_models_bounds_
The bounds for all the active joint models.
std::size_t getLinkModelCount() const
bool enforcePositionBounds(double *state) const
const std::vector< const JointModel * > & getContinuousJointModels() const
Get the array of continuous joints, in the order they appear in the robot state.
JointModel * constructJointModel(const urdf::Joint *urdf_joint_model, const urdf::Link *child_link, const srdf::Model &srdf_model)
Given a urdf joint model, a child link and a set of virtual joints, build up the corresponding JointM...
int getJointIndex() const
Get the index of this joint within the robot model.
std::vector< std::string > link_model_names_with_collision_geometry_vector_
The vector of link names that corresponds to link_models_with_collision_geometry_vector_.
std::vector< std::string > variable_names_
The names of the DOF that make up this state (this is just a sequence of joint variable names; not ne...
const std::string LOGNAME
void buildGroupStates(const srdf::Model &srdf_model)
Given a SRDF model describing the groups, build the default states defined in the SRDF.
const LinkModel * getRootLink() const
Get the physical root link of the robot.
void buildJointInfo()
Compute helpful information about joints.
std::map< const LinkModel *, Eigen::Isometry3d, std::less< const LinkModel * >, Eigen::aligned_allocator< std::pair< const LinkModel *const, Eigen::Isometry3d > > > LinkTransformMap
Map from link model instances to Eigen transforms.
std::vector< int > active_joint_model_start_index_
const std::string & getName() const
Get the model name.
#define ROS_WARN_STREAM_COND_NAMED(cond, name, args)
std::map< std::string, LinkModel * > LinkModelMap
Map of names to instances for LinkModel.
void printModelInfo(std::ostream &out) const
Print information about the constructed model.
const LinkModel * getLinkModel(const std::string &link, bool *has_link=nullptr) const
Get a link by its name. Output error and return NULL when the link is missing.
void getMissingVariableNames(const std::vector< std::string > &variables, std::vector< std::string > &missing_variables) const
Main namespace for MoveIt.
std::vector< double > values
const JointModel * getCommonRoot(const JointModel *a, const JointModel *b) const
Get the deepest joint in the kinematic tree that is a common parent of both joints passed as argument...
std::string model_name_
The name of the robot.
const std::vector< const JointModelGroup * > & getJointModelGroups() const
Get the available joint groups.
MOVEIT_CLASS_FORWARD(JointModelGroup)
const std::string & getRootLinkName() const
Get the name of the root link of the robot.
const std::vector< const JointModel * > & getMimicJointModels() const
Get the array of mimic joints, in the order they appear in the robot state.
std::vector< std::string > active_joint_model_names_vector_
The vector of joint names that corresponds to active_joint_model_vector_.
int getVariableIndex(const std::string &variable) const
Get the index of a variable in the robot state.
const JointBoundsVector & getActiveJointModelsBounds() const
Get the bounds for all the active joints.
double distance(const double *state1, const double *state2) const
Return the sum of joint distances between two states. Only considers active joints.
const std::vector< std::string > & getLinkModelNames() const
Get the link names (of all links)
const std::vector< const JointModel * > & getJointModels() const
Get the array of joints, in the order they appear in the robot state.
std::map< std::string, JointModelGroup * > JointModelGroupMap
Map of names to instances for JointModelGroup.
bool hasJointModel(const std::string &name) const
Check if a joint exists. Return true if it does.
shapes::ShapePtr constructShape(const urdf::Geometry *geom)
Given a geometry spec from the URDF and a filename (for a mesh), construct the corresponding shape ob...
VariableIndexMap joint_variables_index_map_
The state includes all the joint variables that make up the joints the state consists of....
const std::vector< const JointModel * > & getMultiDOFJointModels() const
This is a list of all multi-dof joints.
const std::string & getName() const
The name of this link.
std::size_t getJointModelCount() const
const std::vector< std::string > & getLinkModelNamesWithCollisionGeometry() const
Get the names of the link models that have some collision geometry associated to themselves.
const JointModel * root_joint_
The root joint.
void buildGroups(const srdf::Model &srdf_model)
Given a SRDF model describing the groups, build up the groups in this kinematic model.
void getVariableDefaultPositions(double *values) const
Compute the default values for a RobotState.
const std::vector< const JointModel * > & getSingleDOFJointModels() const
This is a list of all single-dof joints (including mimic joints)
static void checkInterpolationParamBounds(const char LOGNAME[], double t)
void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values) const
Compute the random values for a RobotState.
void updateMimicJoints(double *values) const
Update the variable values for the state of a group with respect to the mimic joints.
~RobotModel()
Destructor. Clear all memory.
const JointModel * computeCommonRoot(const JointModel *a, const JointModel *b) const
Given two joints, find their common root.
void buildModel(const urdf::ModelInterface &urdf_model, const srdf::Model &srdf_model)
Given an URDF model and a SRDF model, build a full kinematic model.
const std::vector< std::string > & getJointModelNames() const
Get the array of joint names, in the order they appear in the robot state.
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
const std::string & getRootJointName() const
Return the name of the root joint. Throws an exception if there is no root joint.
bool hasLinkModel(const std::string &name) const
Check if a link exists. Return true if it does.
const JointModelGroup * getEndEffector(const std::string &name) const
Get the joint group that corresponds to a given end-effector name.
JointModelGroupMap end_effectors_map_
The known end effectors.
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:15