Classes | Namespaces | Typedefs | Functions
joint_model.h File Reference
#include <string>
#include <vector>
#include <map>
#include <iostream>
#include <moveit_msgs/JointLimits.h>
#include <random_numbers/random_numbers.h>
#include <Eigen/Geometry>
Include dependency graph for joint_model.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  moveit::core::JointModel
 A joint from the robot. Models the transform that this joint applies in the kinematic chain. A joint consists of multiple variables. In the simplest case, when the joint is a single DOF, there is only one variable and its name is the same as the joint's name. For multi-DOF joints, each variable has a local name (e.g., x, y) but the full variable name as seen from the outside of this class is a concatenation of the "joint name"/"local name" (e.g., a joint named 'base' with local variables 'x' and 'y' will store its full variable names as 'base/x' and 'base/y'). Local names are never used to reference variables directly. More...
struct  moveit::core::VariableBounds

Namespaces

namespace  moveit
 

Main namespace for MoveIt!


namespace  moveit::core
 

Core components of MoveIt!


Typedefs

typedef std::map< std::string,
JointModel * > 
moveit::core::JointModelMap
 Map of names to instances for JointModel.
typedef std::map< std::string,
const JointModel * > 
moveit::core::JointModelMapConst
 Map of names to const instances for JointModel.
typedef std::map< std::string,
VariableBounds > 
moveit::core::VariableBoundsMap
 Data type for holding mappings from variable names to their bounds.
typedef std::map< std::string,
int > 
moveit::core::VariableIndexMap
 Data type for holding mappings from variable names to their position in a state vector.

Functions

std::ostream & moveit::core::operator<< (std::ostream &out, const VariableBounds &b)
 Operator overload for printing variable bounds to a stream.


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Aug 27 2015 13:58:53