moveit2
The MoveIt Motion Planning Framework for ROS 2.
pose_model_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 
40 #include <ompl/base/spaces/SE3StateSpace.h>
41 
42 namespace ompl_interface
43 {
45 {
46 public:
47  static const std::string PARAMETERIZATION_TYPE;
48 
50  {
51  public:
52  enum
53  {
55  POSE_COMPUTED = 512
56  };
57 
59  {
61  }
62 
63  bool jointsComputed() const
64  {
65  return flags & JOINTS_COMPUTED;
66  }
67 
68  bool poseComputed() const
69  {
70  return flags & POSE_COMPUTED;
71  }
72 
73  void setJointsComputed(bool value)
74  {
75  if (value)
76  {
78  }
79  else
80  {
82  }
83  }
84 
85  void setPoseComputed(bool value)
86  {
87  if (value)
88  {
90  }
91  else
92  {
93  flags &= ~POSE_COMPUTED;
94  }
95  }
96 
97  ompl::base::SE3StateSpace::StateType** poses;
98  };
99 
102 
103  ompl::base::State* allocState() const override;
104  void freeState(ompl::base::State* state) const override;
105  void copyState(ompl::base::State* destination, const ompl::base::State* source) const override;
106  void interpolate(const ompl::base::State* from, const ompl::base::State* to, const double t,
107  ompl::base::State* state) const override;
108  double distance(const ompl::base::State* state1, const ompl::base::State* state2) const override;
109  double getMaximumExtent() const override;
110 
111  ompl::base::StateSamplerPtr allocDefaultStateSampler() const override;
112 
113  bool computeStateFK(ompl::base::State* state) const;
114  bool computeStateIK(ompl::base::State* state) const;
115  bool computeStateK(ompl::base::State* state) const;
116 
117  void setPlanningVolume(double minX, double maxX, double minY, double maxY, double minZ, double maxZ) override;
118  void copyToOMPLState(ompl::base::State* state, const moveit::core::RobotState& rstate) const override;
119  void sanityChecks() const override;
120 
121  const std::string& getParameterizationType() const override
122  {
123  return PARAMETERIZATION_TYPE;
124  }
125 
126 private:
127  struct PoseComponent
128  {
129  PoseComponent(const moveit::core::JointModelGroup* subgroup,
131 
132  bool computeStateFK(StateType* full_state, unsigned int idx) const;
133  bool computeStateIK(StateType* full_state, unsigned int idx) const;
134 
135  bool operator<(const PoseComponent& o) const
136  {
137  return subgroup_->getName() < o.subgroup_->getName();
138  }
139 
140  const moveit::core::JointModelGroup* subgroup_;
141  kinematics::KinematicsBasePtr kinematics_solver_;
142  std::vector<size_t> bijection_;
143  ompl::base::StateSpacePtr state_space_;
144  std::vector<std::string> fk_link_;
145  };
146 
147  std::vector<PoseComponent> poses_;
148  double jump_factor_;
149 };
150 } // namespace ompl_interface
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
ompl::base::SE3StateSpace::StateType ** poses
double distance(const ompl::base::State *state1, const ompl::base::State *state2) const override
ompl::base::State * allocState() const override
PoseModelStateSpace(const ModelBasedStateSpaceSpecification &spec)
void copyState(ompl::base::State *destination, const ompl::base::State *source) const override
void setPlanningVolume(double minX, double maxX, double minY, double maxY, double minZ, double maxZ) override
Set the planning volume for the possible SE2 and/or SE3 components of the state space.
bool computeStateFK(ompl::base::State *state) const
void copyToOMPLState(ompl::base::State *state, const moveit::core::RobotState &rstate) const override
Copy the data from a set of joint states to an OMPL state.
bool computeStateK(ompl::base::State *state) const
void freeState(ompl::base::State *state) const override
static const std::string PARAMETERIZATION_TYPE
ompl::base::StateSamplerPtr allocDefaultStateSampler() const override
const std::string & getParameterizationType() const override
void interpolate(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state) const override
bool computeStateIK(ompl::base::State *state) const
The MoveIt interface to OMPL.