#define MOVEIT_CLASS_FORWARD(C)
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Representation of a robot's state. This includes position, velocity, acceleration and effort.
State space to be used in combination with OMPL's constrained planning functionality.
void copyJointToOMPLState(ompl::base::State *ompl_state, const moveit::core::RobotState &robot_state, const moveit::core::JointModel *joint_model, int ompl_state_joint_index) const override
Copy a single joint's values (which might have multiple variables) from a MoveIt robot_state to an OM...
const std::string & getParameterizationType() const override
double * getValueAddressAtIndex(ompl::base::State *ompl_state, const unsigned int index) const override
void copyToOMPLState(ompl::base::State *ompl_state, const moveit::core::RobotState &robot_state) const override
Copy the data from a set of joint states to an OMPL state.
static const std::string PARAMETERIZATION_TYPE
void copyToRobotState(moveit::core::RobotState &robot_state, const ompl::base::State *ompl_state) const override
Copy the data from an OMPL state to a set of joint states.
The MoveIt interface to OMPL.