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 {
44 class PoseModelStateSpace : public ModelBasedStateSpace
45 {
46 public:
47  static const std::string PARAMETERIZATION_TYPE;
48 
49  class StateType : public ModelBasedStateSpace::StateType
50  {
51  public:
52  enum
53  {
54  JOINTS_COMPUTED = 256,
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)
77  else
79  }
80 
81  void setPoseComputed(bool value)
82  {
83  if (value)
85  else
86  flags &= ~POSE_COMPUTED;
87  }
88 
89  ompl::base::SE3StateSpace::StateType** poses;
90  };
91 
92  PoseModelStateSpace(const ModelBasedStateSpaceSpecification& spec);
93  ~PoseModelStateSpace() override;
94 
95  ompl::base::State* allocState() const override;
96  void freeState(ompl::base::State* state) const override;
97  void copyState(ompl::base::State* destination, const ompl::base::State* source) const override;
98  void interpolate(const ompl::base::State* from, const ompl::base::State* to, const double t,
99  ompl::base::State* state) const override;
100  double distance(const ompl::base::State* state1, const ompl::base::State* state2) const override;
101  double getMaximumExtent() const override;
102 
103  ompl::base::StateSamplerPtr allocDefaultStateSampler() const override;
104 
105  bool computeStateFK(ompl::base::State* state) const;
106  bool computeStateIK(ompl::base::State* state) const;
107  bool computeStateK(ompl::base::State* state) const;
108 
109  void setPlanningVolume(double minX, double maxX, double minY, double maxY, double minZ, double maxZ) override;
110  void copyToOMPLState(ompl::base::State* state, const moveit::core::RobotState& rstate) const override;
111  void sanityChecks() const override;
112 
113  const std::string& getParameterizationType() const override
114  {
115  return PARAMETERIZATION_TYPE;
116  }
117 
118 private:
120  {
123 
124  bool computeStateFK(StateType* full_state, unsigned int idx) const;
125  bool computeStateIK(StateType* full_state, unsigned int idx) const;
126 
127  bool operator<(const PoseComponent& o) const
128  {
129  return subgroup_->getName() < o.subgroup_->getName();
130  }
131 
133  kinematics::KinematicsBasePtr kinematics_solver_;
134  std::vector<unsigned int> bijection_;
135  ompl::base::StateSpacePtr state_space_;
136  std::vector<std::string> fk_link_;
137  };
138 
139  std::vector<PoseComponent> poses_;
140  double jump_factor_;
141 };
142 } // namespace ompl_interface
ompl_interface::PoseModelStateSpace::distance
double distance(const ompl::base::State *state1, const ompl::base::State *state2) const override
Definition: pose_model_state_space.cpp:73
moveit::core::JointModelGroup::KinematicsSolver
ompl_interface::PoseModelStateSpace::PoseComponent::subgroup_
const moveit::core::JointModelGroup * subgroup_
Definition: pose_model_state_space.h:196
ompl_interface::PoseModelStateSpace::computeStateK
bool computeStateK(ompl::base::State *state) const
Definition: pose_model_state_space.cpp:290
ompl_interface::PoseModelStateSpace::StateType::StateType
StateType()
Definition: pose_model_state_space.h:122
ompl_interface::PoseModelStateSpace::StateType
Definition: pose_model_state_space.h:113
ompl_interface::PoseModelStateSpace::computeStateFK
bool computeStateFK(ompl::base::State *state) const
Definition: pose_model_state_space.cpp:262
ompl_interface::PoseModelStateSpace::PoseComponent::operator<
bool operator<(const PoseComponent &o) const
Definition: pose_model_state_space.h:191
ompl_interface::PoseModelStateSpace::PARAMETERIZATION_TYPE
static const std::string PARAMETERIZATION_TYPE
Definition: pose_model_state_space.h:111
ompl_interface::PoseModelStateSpace::StateType::setPoseComputed
void setPoseComputed(bool value)
Definition: pose_model_state_space.h:145
ompl_interface::PoseModelStateSpace::StateType::poses
ompl::base::SE3StateSpace::StateType ** poses
Definition: pose_model_state_space.h:153
ompl_interface::PoseModelStateSpace::allocDefaultStateSampler
ompl::base::StateSamplerPtr allocDefaultStateSampler() const override
Definition: pose_model_state_space.cpp:302
ompl_interface::PoseModelStateSpace::StateType::jointsComputed
bool jointsComputed() const
Definition: pose_model_state_space.h:127
ompl_interface
The MoveIt interface to OMPL.
Definition: constrained_goal_sampler.h:46
ompl_interface::PoseModelStateSpace::PoseComponent::fk_link_
std::vector< std::string > fk_link_
Definition: pose_model_state_space.h:200
moveit::core::RobotState
ompl_interface::PoseModelStateSpace::computeStateIK
bool computeStateIK(ompl::base::State *state) const
Definition: pose_model_state_space.cpp:276
model_based_state_space.h
ompl_interface::PoseModelStateSpace::StateType::poseComputed
bool poseComputed() const
Definition: pose_model_state_space.h:132
ompl_interface::PoseModelStateSpace::getParameterizationType
const std::string & getParameterizationType() const override
Definition: pose_model_state_space.h:177
ompl_interface::PoseModelStateSpace::allocState
ompl::base::State * allocState() const override
Definition: pose_model_state_space.cpp:90
ompl_interface::PoseModelStateSpace::~PoseModelStateSpace
~PoseModelStateSpace() override
ompl_interface::PoseModelStateSpace::StateType::JOINTS_COMPUTED
@ JOINTS_COMPUTED
Definition: pose_model_state_space.h:118
moveit::core::JointModelGroup::getName
const std::string & getName() const
ompl_interface::PoseModelStateSpace::StateType::POSE_COMPUTED
@ POSE_COMPUTED
Definition: pose_model_state_space.h:119
ompl_interface::PoseModelStateSpace::PoseComponent::kinematics_solver_
kinematics::KinematicsBasePtr kinematics_solver_
Definition: pose_model_state_space.h:197
ompl_interface::PoseModelStateSpace::freeState
void freeState(ompl::base::State *state) const override
Definition: pose_model_state_space.cpp:101
ompl_interface::PoseModelStateSpace::interpolate
void interpolate(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state) const override
Definition: pose_model_state_space.cpp:128
ompl_interface::PoseModelStateSpace::copyState
void copyState(ompl::base::State *destination, const ompl::base::State *source) const override
Definition: pose_model_state_space.cpp:109
ompl_interface::PoseModelStateSpace::poses_
std::vector< PoseComponent > poses_
Definition: pose_model_state_space.h:203
ompl_interface::PoseModelStateSpace::PoseComponent::bijection_
std::vector< unsigned int > bijection_
Definition: pose_model_state_space.h:198
ompl_interface::ModelBasedStateSpace::StateType::flags
int flags
Definition: model_based_state_space.h:197
ompl_interface::PoseModelStateSpace::PoseModelStateSpace
PoseModelStateSpace(const ModelBasedStateSpaceSpecification &spec)
Definition: pose_model_state_space.cpp:50
ompl_interface::ModelBasedStateSpace::ModelBasedStateSpace
ModelBasedStateSpace(ModelBasedStateSpaceSpecification spec)
Definition: model_based_state_space.cpp:45
ompl_interface::PoseModelStateSpace::copyToOMPLState
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.
Definition: pose_model_state_space.cpp:345
ompl_interface::PoseModelStateSpace::getMaximumExtent
double getMaximumExtent() const override
Definition: pose_model_state_space.cpp:82
ompl_interface::PoseModelStateSpace::sanityChecks
void sanityChecks() const override
Definition: pose_model_state_space.cpp:122
ompl_interface::PoseModelStateSpace::PoseComponent::PoseComponent
PoseComponent(const moveit::core::JointModelGroup *subgroup, const moveit::core::JointModelGroup::KinematicsSolver &k)
Definition: pose_model_state_space.cpp:184
ompl_interface::PoseModelStateSpace::PoseComponent::computeStateIK
bool computeStateIK(StateType *full_state, unsigned int idx) const
Definition: pose_model_state_space.cpp:219
ompl_interface::PoseModelStateSpace::jump_factor_
double jump_factor_
Definition: pose_model_state_space.h:204
moveit::core::JointModelGroup
ompl_interface::PoseModelStateSpace::PoseComponent
Definition: pose_model_state_space.h:183
ompl_interface::PoseModelStateSpace::StateType::setJointsComputed
void setJointsComputed(bool value)
Definition: pose_model_state_space.h:137
ompl_interface::PoseModelStateSpace::PoseComponent::computeStateFK
bool computeStateFK(StateType *full_state, unsigned int idx) const
Definition: pose_model_state_space.cpp:195
ompl_interface::PoseModelStateSpace::setPlanningVolume
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.
Definition: pose_model_state_space.cpp:169
ompl_interface::PoseModelStateSpace::PoseComponent::state_space_
ompl::base::StateSpacePtr state_space_
Definition: pose_model_state_space.h:199


ompl
Author(s): Ioan Sucan
autogenerated on Fri May 3 2024 02:29:39