model_based_state_space.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
37 #pragma once
38 
39 #include <ompl/base/StateSpace.h>
44 
45 namespace ompl_interface
46 {
47 typedef std::function<bool(const ompl::base::State* from, const ompl::base::State* to, const double t,
48  ompl::base::State* state)>
50 typedef std::function<double(const ompl::base::State* state1, const ompl::base::State* state2)> DistanceFunction;
51 
52 struct ModelBasedStateSpaceSpecification
53 {
54  ModelBasedStateSpaceSpecification(const moveit::core::RobotModelConstPtr& robot_model,
56  : robot_model_(robot_model), joint_model_group_(jmg)
57  {
58  }
59 
60  ModelBasedStateSpaceSpecification(const moveit::core::RobotModelConstPtr& robot_model, const std::string& group_name)
61  : robot_model_(robot_model), joint_model_group_(robot_model_->getJointModelGroup(group_name))
62  {
63  if (!joint_model_group_)
64  throw std::runtime_error("Group '" + group_name + "' was not found");
65  }
66 
67  moveit::core::RobotModelConstPtr robot_model_;
70 };
71 
72 OMPL_CLASS_FORWARD(ModelBasedStateSpace);
73 
74 class ModelBasedStateSpace : public ompl::base::StateSpace
75 {
76 public:
77  class StateType : public ompl::base::State
78  {
79  public:
80  enum
81  {
85  IS_START_STATE = 8,
87  };
88 
89  StateType() : ompl::base::State(), values(nullptr), tag(-1), flags(0), distance(0.0)
90  {
91  }
92 
93  void markValid(double d)
94  {
95  distance = d;
97  markValid();
98  }
99 
100  void markValid()
101  {
103  }
104 
105  void markInvalid(double d)
106  {
107  distance = d;
110  }
111 
112  void markInvalid()
113  {
116  }
117 
118  bool isValidityKnown() const
119  {
120  return flags & VALIDITY_KNOWN;
121  }
122 
123  void clearKnownInformation()
124  {
125  flags = 0;
126  }
127 
128  bool isMarkedValid() const
129  {
130  return flags & VALIDITY_TRUE;
131  }
132 
133  bool isGoalDistanceKnown() const
134  {
135  return flags & GOAL_DISTANCE_KNOWN;
136  }
137 
138  bool isStartState() const
139  {
140  return flags & IS_START_STATE;
141  }
142 
143  bool isGoalState() const
144  {
145  return flags & IS_GOAL_STATE;
146  }
147 
148  bool isInputState() const
149  {
151  }
152 
153  void markStartState()
154  {
156  }
157 
158  void markGoalState()
159  {
161  }
162 
163  double* values;
164  int tag;
165  int flags;
166  double distance;
167  };
168 
171 
173  {
175  }
176 
177  void setDistanceFunction(const DistanceFunction& fun)
178  {
179  distance_function_ = fun;
180  }
181 
182  ompl::base::State* allocState() const override;
183  void freeState(ompl::base::State* state) const override;
184  unsigned int getDimension() const override;
185  void enforceBounds(ompl::base::State* state) const override;
186  bool satisfiesBounds(const ompl::base::State* state) const override;
187 
188  void copyState(ompl::base::State* destination, const ompl::base::State* source) const override;
189  void interpolate(const ompl::base::State* from, const ompl::base::State* to, const double t,
190  ompl::base::State* state) const override;
191  double distance(const ompl::base::State* state1, const ompl::base::State* state2) const override;
192  bool equalStates(const ompl::base::State* state1, const ompl::base::State* state2) const override;
193  double getMaximumExtent() const override;
194  double getMeasure() const override;
195 
196  unsigned int getSerializationLength() const override;
197  void serialize(void* serialization, const ompl::base::State* state) const override;
198  void deserialize(ompl::base::State* state, const void* serialization) const override;
199  double* getValueAddressAtIndex(ompl::base::State* state, const unsigned int index) const override;
200 
201  ompl::base::StateSamplerPtr allocDefaultStateSampler() const override;
202 
203  virtual const std::string& getParameterizationType() const = 0;
204 
205  const moveit::core::RobotModelConstPtr& getRobotModel() const
206  {
207  return spec_.robot_model_;
208  }
209 
211  {
212  return spec_.joint_model_group_;
213  }
214 
215  const std::string& getJointModelGroupName() const
216  {
217  return getJointModelGroup()->getName();
218  }
219 
220  const ModelBasedStateSpaceSpecification& getSpecification() const
221  {
222  return spec_;
223  }
224 
225  void printState(const ompl::base::State* state, std::ostream& out) const override;
226  void printSettings(std::ostream& out) const override;
227 
229  virtual void setPlanningVolume(double minX, double maxX, double minY, double maxY, double minZ, double maxZ);
230 
232  {
233  return spec_.joint_bounds_;
234  }
235 
237  // The joint states \b must be specified in the same order as the joint models in the constructor
238  virtual void copyToRobotState(moveit::core::RobotState& rstate, const ompl::base::State* state) const;
239 
241  // The joint states \b must be specified in the same order as the joint models in the constructor
242  virtual void copyToOMPLState(ompl::base::State* state, const moveit::core::RobotState& rstate) const;
243 
254  virtual void copyJointToOMPLState(ompl::base::State* state, const moveit::core::RobotState& robot_state,
255  const moveit::core::JointModel* joint_model, int ompl_state_joint_index) const;
256 
257  double getTagSnapToSegment() const;
258  void setTagSnapToSegment(double snap);
259 
260 protected:
262  std::vector<moveit::core::JointModel::Bounds> joint_bounds_storage_;
263  std::vector<const moveit::core::JointModel*> joint_model_vector_;
264  unsigned int variable_count_;
265  size_t state_values_size_;
266 
269 
270  double tag_snap_to_segment_;
272 };
273 } // namespace ompl_interface
ompl_interface::ModelBasedStateSpace::deserialize
void deserialize(ompl::base::State *state, const void *serialization) const override
Definition: model_based_state_space.cpp:137
ompl_interface::ModelBasedStateSpace::StateType::isInputState
bool isInputState() const
Definition: model_based_state_space.h:180
robot_model.h
ompl_interface::ModelBasedStateSpace::StateType::values
double * values
Definition: model_based_state_space.h:195
ompl_interface::ModelBasedStateSpace::joint_bounds_storage_
std::vector< moveit::core::JointModel::Bounds > joint_bounds_storage_
Definition: model_based_state_space.h:294
ompl_interface::ModelBasedStateSpace::StateType::VALIDITY_TRUE
@ VALIDITY_TRUE
Definition: model_based_state_space.h:116
ompl_interface::ModelBasedStateSpace::getTagSnapToSegment
double getTagSnapToSegment() const
Definition: model_based_state_space.cpp:85
ompl_interface::ModelBasedStateSpace::freeState
void freeState(ompl::base::State *state) const override
Definition: model_based_state_space.cpp:111
ompl_interface::ModelBasedStateSpace::StateType::distance
double distance
Definition: model_based_state_space.h:198
ompl_interface::OMPL_CLASS_FORWARD
OMPL_CLASS_FORWARD(ModelBasedStateSpace)
ompl_interface::ModelBasedStateSpace::setDistanceFunction
void setDistanceFunction(const DistanceFunction &fun)
Definition: model_based_state_space.h:209
ompl_interface::ModelBasedStateSpace::tag_snap_to_segment_complement_
double tag_snap_to_segment_complement_
Definition: model_based_state_space.h:303
ompl_interface::ModelBasedStateSpace::interpolate
void interpolate(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state) const override
Definition: model_based_state_space.cpp:199
ompl_interface::ModelBasedStateSpace::StateType::GOAL_DISTANCE_KNOWN
@ GOAL_DISTANCE_KNOWN
Definition: model_based_state_space.h:115
ompl_interface::ModelBasedStateSpace::getJointModelGroupName
const std::string & getJointModelGroupName() const
Definition: model_based_state_space.h:247
ompl_interface::ModelBasedStateSpace::StateType::markValid
void markValid()
Definition: model_based_state_space.h:132
ompl_interface::ModelBasedStateSpace::StateType::IS_START_STATE
@ IS_START_STATE
Definition: model_based_state_space.h:117
ompl_interface::ModelBasedStateSpaceSpecification
Definition: model_based_state_space.h:84
ompl_interface::ModelBasedStateSpace::distance
double distance(const ompl::base::State *state1, const ompl::base::State *state2) const override
Definition: model_based_state_space.cpp:169
ompl_interface
The MoveIt interface to OMPL.
Definition: constrained_goal_sampler.h:46
ompl_interface::ModelBasedStateSpace::getSerializationLength
unsigned int getSerializationLength() const override
Definition: model_based_state_space.cpp:126
ompl_interface::ModelBasedStateSpace::spec_
ModelBasedStateSpaceSpecification spec_
Definition: model_based_state_space.h:293
ompl_interface::ModelBasedStateSpace::getValueAddressAtIndex
double * getValueAddressAtIndex(ompl::base::State *state, const unsigned int index) const override
Definition: model_based_state_space.cpp:221
moveit::core::JointBoundsVector
std::vector< const JointModel::Bounds * > JointBoundsVector
ompl_interface::ModelBasedStateSpace::getSpecification
const ModelBasedStateSpaceSpecification & getSpecification() const
Definition: model_based_state_space.h:252
ompl_interface::ModelBasedStateSpace::getMaximumExtent
double getMaximumExtent() const override
Definition: model_based_state_space.cpp:151
moveit::core::RobotState
ompl_interface::ModelBasedStateSpace::StateType::clearKnownInformation
void clearKnownInformation()
Definition: model_based_state_space.h:155
robot_state.h
ompl_interface::ModelBasedStateSpace::StateType::isMarkedValid
bool isMarkedValid() const
Definition: model_based_state_space.h:160
ompl_interface::ModelBasedStateSpace::printState
void printState(const ompl::base::State *state, std::ostream &out) const override
Definition: model_based_state_space.cpp:295
ompl_interface::ModelBasedStateSpace::distance_function_
DistanceFunction distance_function_
Definition: model_based_state_space.h:300
ompl_interface::ModelBasedStateSpaceSpecification::joint_bounds_
moveit::core::JointBoundsVector joint_bounds_
Definition: model_based_state_space.h:101
ompl_interface::ModelBasedStateSpaceSpecification::robot_model_
moveit::core::RobotModelConstPtr robot_model_
Definition: model_based_state_space.h:99
ompl_interface::ModelBasedStateSpace::getJointsBounds
const moveit::core::JointBoundsVector & getJointsBounds() const
Definition: model_based_state_space.h:263
ompl_interface::ModelBasedStateSpace::copyToOMPLState
virtual void copyToOMPLState(ompl::base::State *state, const moveit::core::RobotState &rstate) const
Copy the data from a set of joint states to an OMPL state.
Definition: model_based_state_space.cpp:328
ompl_interface::ModelBasedStateSpaceSpecification::ModelBasedStateSpaceSpecification
ModelBasedStateSpaceSpecification(const moveit::core::RobotModelConstPtr &robot_model, const moveit::core::JointModelGroup *jmg)
Definition: model_based_state_space.h:86
ompl_interface::ModelBasedStateSpaceSpecification::joint_model_group_
const moveit::core::JointModelGroup * joint_model_group_
Definition: model_based_state_space.h:100
ompl_interface::ModelBasedStateSpace::getDimension
unsigned int getDimension() const override
Definition: model_based_state_space.cpp:143
ompl_interface::ModelBasedStateSpace::satisfiesBounds
bool satisfiesBounds(const ompl::base::State *state) const override
Definition: model_based_state_space.cpp:193
moveit::core::JointModelGroup::getName
const std::string & getName() const
ompl_interface::ModelBasedStateSpace::getRobotModel
const moveit::core::RobotModelConstPtr & getRobotModel() const
Definition: model_based_state_space.h:237
ompl_interface::DistanceFunction
std::function< double(const ompl::base::State *state1, const ompl::base::State *state2)> DistanceFunction
Definition: model_based_state_space.h:82
ompl_interface::ModelBasedStateSpace::tag_snap_to_segment_
double tag_snap_to_segment_
Definition: model_based_state_space.h:302
ompl_interface::ModelBasedStateSpace::~ModelBasedStateSpace
~ModelBasedStateSpace() override
ompl_interface::ModelBasedStateSpace::StateType::isValidityKnown
bool isValidityKnown() const
Definition: model_based_state_space.h:150
ompl_interface::ModelBasedStateSpace::serialize
void serialize(void *serialization, const ompl::base::State *state) const override
Definition: model_based_state_space.cpp:131
ompl_interface::ModelBasedStateSpace::allocDefaultStateSampler
ompl::base::StateSamplerPtr allocDefaultStateSampler() const override
Definition: model_based_state_space.cpp:251
ompl_interface::ModelBasedStateSpace::setInterpolationFunction
void setInterpolationFunction(const InterpolationFunction &fun)
Definition: model_based_state_space.h:204
d
d
ompl_interface::ModelBasedStateSpace::StateType::tag
int tag
Definition: model_based_state_space.h:196
kinematic_constraint.h
ompl_interface::ModelBasedStateSpace::copyState
void copyState(ompl::base::State *destination, const ompl::base::State *source) const override
Definition: model_based_state_space.cpp:117
ompl_interface::ModelBasedStateSpace::copyToRobotState
virtual void copyToRobotState(moveit::core::RobotState &rstate, const ompl::base::State *state) const
Copy the data from an OMPL state to a set of joint states.
Definition: model_based_state_space.cpp:321
ompl_interface::ModelBasedStateSpace::StateType::markInvalid
void markInvalid()
Definition: model_based_state_space.h:144
ompl_interface::ModelBasedStateSpace::state_values_size_
size_t state_values_size_
Definition: model_based_state_space.h:297
ompl_interface::ModelBasedStateSpace::StateType::markStartState
void markStartState()
Definition: model_based_state_space.h:185
ompl_interface::ModelBasedStateSpace::StateType::flags
int flags
Definition: model_based_state_space.h:197
ompl_interface::ModelBasedStateSpace::StateType::IS_GOAL_STATE
@ IS_GOAL_STATE
Definition: model_based_state_space.h:118
ompl_interface::ModelBasedStateSpace::getMeasure
double getMeasure() const override
Definition: model_based_state_space.cpp:156
ompl_interface::ModelBasedStateSpace::ModelBasedStateSpace
ModelBasedStateSpace(ModelBasedStateSpaceSpecification spec)
Definition: model_based_state_space.cpp:45
ompl_interface::ModelBasedStateSpace::getParameterizationType
virtual const std::string & getParameterizationType() const =0
ompl_interface::ModelBasedStateSpace::equalStates
bool equalStates(const ompl::base::State *state1, const ompl::base::State *state2) const override
Definition: model_based_state_space.cpp:178
ompl_interface::ModelBasedStateSpace::StateType::VALIDITY_KNOWN
@ VALIDITY_KNOWN
Definition: model_based_state_space.h:114
ompl_interface::ModelBasedStateSpace::StateType::isGoalDistanceKnown
bool isGoalDistanceKnown() const
Definition: model_based_state_space.h:165
ompl_interface::ModelBasedStateSpace::enforceBounds
void enforceBounds(ompl::base::State *state) const override
Definition: model_based_state_space.cpp:188
ompl_interface::ModelBasedStateSpace::setTagSnapToSegment
void setTagSnapToSegment(double snap)
Definition: model_based_state_space.cpp:90
moveit::core::JointModelGroup
ompl_interface::ModelBasedStateSpace::getJointModelGroup
const moveit::core::JointModelGroup * getJointModelGroup() const
Definition: model_based_state_space.h:242
ompl_interface::ModelBasedStateSpace::printSettings
void printSettings(std::ostream &out) const override
Definition: model_based_state_space.cpp:290
ompl_interface::ModelBasedStateSpace::copyJointToOMPLState
virtual void copyJointToOMPLState(ompl::base::State *state, const moveit::core::RobotState &robot_state, const moveit::core::JointModel *joint_model, int ompl_state_joint_index) const
Copy a single joint's values (which might have multiple variables) from a MoveIt robot_state to an OM...
Definition: model_based_state_space.cpp:336
ompl_interface::InterpolationFunction
std::function< bool(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state)> InterpolationFunction
Definition: model_based_state_space.h:81
ompl_interface::ModelBasedStateSpace::StateType::isStartState
bool isStartState() const
Definition: model_based_state_space.h:170
ompl_interface::ModelBasedStateSpace::setPlanningVolume
virtual void setPlanningVolume(double minX, double maxX, double minY, double maxY, double minZ, double maxZ)
Set the planning volume for the possible SE2 and/or SE3 components of the state space.
Definition: model_based_state_space.cpp:229
ompl_interface::ModelBasedStateSpace::StateType::StateType
StateType()
Definition: model_based_state_space.h:121
constraint_sampler.h
ompl_interface::ModelBasedStateSpace::StateType::markGoalState
void markGoalState()
Definition: model_based_state_space.h:190
ompl_interface::ModelBasedStateSpace::joint_model_vector_
std::vector< const moveit::core::JointModel * > joint_model_vector_
Definition: model_based_state_space.h:295
ompl_interface::ModelBasedStateSpace::StateType::isGoalState
bool isGoalState() const
Definition: model_based_state_space.h:175
ompl_interface::ModelBasedStateSpace::allocState
ompl::base::State * allocState() const override
Definition: model_based_state_space.cpp:104
moveit::core::JointModel
ompl_interface::ModelBasedStateSpace::variable_count_
unsigned int variable_count_
Definition: model_based_state_space.h:296
ompl_interface::ModelBasedStateSpace::interpolation_function_
InterpolationFunction interpolation_function_
Definition: model_based_state_space.h:299


ompl
Author(s): Ioan Sucan
autogenerated on Thu Apr 18 2024 02:24:37