|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <string>#include <vector>#include <map>#include <iostream>#include <moveit_msgs/msg/joint_limits.hpp>#include <random_numbers/random_numbers.h>#include <Eigen/Geometry>

Go to the source code of this file.
Classes | |
| struct | moveit::core::VariableBounds |
| 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... | |
Namespaces | |
| moveit | |
| Main namespace for MoveIt. | |
| moveit::core | |
| Core components of MoveIt. | |
Typedefs | |
| typedef std::map< std::string, size_t > | moveit::core::VariableIndexMap |
| Data type for holding mappings from variable names to their position in a state vector. More... | |
| using | moveit::core::VariableBoundsMap = std::map< std::string, VariableBounds > |
| Data type for holding mappings from variable names to their bounds. More... | |
| using | moveit::core::JointModelMap = std::map< std::string, JointModel * > |
| Map of names to instances for JointModel. More... | |
| using | moveit::core::JointModelMapConst = std::map< std::string, const JointModel * > |
| Map of names to const instances for JointModel. More... | |
Functions | |
| std::ostream & | moveit::core::operator<< (std::ostream &out, const VariableBounds &b) |
| Operator overload for printing variable bounds to a stream. More... | |