39 #include <ompl/base/spaces/constraint/ConstrainedStateSpace.h> 
   52                                                               const unsigned int index)
 const 
   54   assert(ompl_state != 
nullptr);
 
   65                                                      const ompl::base::State* ompl_state)
 const 
   67   assert(ompl_state != 
nullptr);
 
   70       ompl_state->as<ompl::base::ConstrainedStateSpace::StateType>()->getState()->as<
StateType>()->
values);
 
   77   assert(ompl_state != 
nullptr);
 
   80       ompl_state->as<ompl::base::ConstrainedStateSpace::StateType>()->getState()->as<
StateType>()->
values);
 
   83   ompl_state->as<ompl::base::ConstrainedStateSpace::StateType>()->
getState()->as<
StateType>()->clearKnownInformation();
 
   89                                                          int ompl_state_joint_index)
 const 
   91   assert(ompl_state != 
nullptr);
 
   92   assert(joint_model != 
nullptr);
 
   94                                 ompl_state_joint_index),
 
   99   ompl_state->as<ompl::base::ConstrainedStateSpace::StateType>()->
getState()->as<
StateType>()->clearKnownInformation();
 
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
 
size_t getFirstVariableIndex() const
Get the index of this joint's first variable within the full robot state.
 
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
 
Representation of a robot's state. This includes position, velocity, acceleration and effort.
 
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
 
void copyJointGroupPositions(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the position values of the variables that make up the group into another loca...
 
double * getVariablePositions()
Get a raw pointer to the positions of the variables stored in this state. Use carefully....
 
void update(bool force=false)
Update all transforms.
 
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...
 
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.
 
ConstrainedPlanningStateSpace(const ModelBasedStateSpaceSpecification &spec)
 
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.
 
ModelBasedStateSpaceSpecification spec_
 
unsigned int variable_count_
 
The MoveIt interface to OMPL.
 
const moveit::core::JointModelGroup * joint_model_group_
 
bool getState(const std::shared_ptr< moveit_msgs::srv::GetRobotStateFromWarehouse::Request > &request, const std::shared_ptr< moveit_msgs::srv::GetRobotStateFromWarehouse::Response > &response, moveit_warehouse::RobotStateStorage &rs)