moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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
45namespace ompl_interface
46{
47typedef std::function<bool(const ompl::base::State* from, const ompl::base::State* to, const double t,
48 ompl::base::State* state)>
50typedef std::function<double(const ompl::base::State* state1, const ompl::base::State* state2)> DistanceFunction;
51
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 {
64 throw std::runtime_error("Group '" + group_name + "' was not found");
65 }
66
67 moveit::core::RobotModelConstPtr robot_model_;
70};
71
73
74class ModelBasedStateSpace : public ompl::base::StateSpace
75{
76public:
77 class StateType : public ompl::base::State
78 {
79 public:
80 enum
81 {
86 IS_GOAL_STATE = 16
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
101 {
103 }
104
105 void markInvalid(double d)
106 {
107 distance = d;
109 markInvalid();
110 }
111
113 {
114 flags &= ~VALIDITY_TRUE;
116 }
117
118 bool isValidityKnown() const
119 {
120 return flags & VALIDITY_KNOWN;
121 }
122
124 {
125 flags = 0;
126 }
127
128 bool isMarkedValid() const
129 {
130 return flags & VALIDITY_TRUE;
131 }
132
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
154 {
156 }
157
159 {
161 }
162
163 double* values;
164 int tag;
165 int flags;
166 double distance;
167 };
168
171
176
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
214
215 const std::string& getJointModelGroupName() const
216 {
217 return getJointModelGroup()->getName();
218 }
219
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
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
260protected:
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_;
266
269
272};
273} // namespace ompl_interface
const std::string & getName() const
Get the name of the joint group.
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.
Definition robot_state.h:90
bool satisfiesBounds(const ompl::base::State *state) const override
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...
const moveit::core::RobotModelConstPtr & getRobotModel() const
bool equalStates(const ompl::base::State *state1, const ompl::base::State *state2) const override
void serialize(void *serialization, const ompl::base::State *state) const override
double * getValueAddressAtIndex(ompl::base::State *state, const unsigned int index) const override
const ModelBasedStateSpaceSpecification & getSpecification() const
std::vector< const moveit::core::JointModel * > joint_model_vector_
void deserialize(ompl::base::State *state, const void *serialization) const override
std::vector< moveit::core::JointModel::Bounds > joint_bounds_storage_
ModelBasedStateSpaceSpecification spec_
unsigned int getSerializationLength() const override
ompl::base::State * allocState() const override
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.
ompl::base::StateSamplerPtr allocDefaultStateSampler() const override
virtual const std::string & getParameterizationType() const =0
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.
void interpolate(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state) const override
const std::string & getJointModelGroupName() const
void printState(const ompl::base::State *state, std::ostream &out) const override
const moveit::core::JointBoundsVector & getJointsBounds() const
void setInterpolationFunction(const InterpolationFunction &fun)
void freeState(ompl::base::State *state) const override
void copyState(ompl::base::State *destination, const ompl::base::State *source) const override
const moveit::core::JointModelGroup * getJointModelGroup() const
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.
void setDistanceFunction(const DistanceFunction &fun)
void printSettings(std::ostream &out) const override
void enforceBounds(ompl::base::State *state) const override
double distance(const ompl::base::State *state1, const ompl::base::State *state2) const override
std::vector< const JointModel::Bounds * > JointBoundsVector
The MoveIt interface to OMPL.
std::function< double(const ompl::base::State *state1, const ompl::base::State *state2)> DistanceFunction
OMPL_CLASS_FORWARD(ModelBasedStateSpace)
std::function< bool(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state)> InterpolationFunction
ModelBasedStateSpaceSpecification(const moveit::core::RobotModelConstPtr &robot_model, const std::string &group_name)
const moveit::core::JointModelGroup * joint_model_group_
ModelBasedStateSpaceSpecification(const moveit::core::RobotModelConstPtr &robot_model, const moveit::core::JointModelGroup *jmg)