moveit2
The MoveIt Motion Planning Framework for ROS 2.
test_constrained_state_validity_checker.cpp
Go to the documentation of this file.
1 
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2020, KU Leuven
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of KU Leuven nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 /* Author: Jeroen De Maeyer */
37 
38 #include "load_test_robot.h"
39 
40 #include <limits>
41 #include <ostream>
42 
43 #include <gtest/gtest.h>
44 
49 
50 #include <ompl/geometric/SimpleSetup.h>
51 #include <ompl/base/Constraint.h>
52 #include <ompl/base/ConstrainedSpaceInformation.h>
53 #include <ompl/base/spaces/constraint/ProjectedStateSpace.h>
54 
56 constexpr bool VERBOSE = false;
57 
58 static const rclcpp::Logger LOGGER =
59  rclcpp::get_logger("moveit.ompl_planning.test.test_constrained_state_validity_checker");
60 
62 std::ostream& operator<<(std::ostream& os, const std::vector<double>& v)
63 {
64  os << "( ";
65  for (auto value : v)
66  os << value << ", ";
67  os << " )";
68  return os;
69 }
70 
72 class DummyConstraint : public ompl::base::Constraint
73 {
74 public:
75  DummyConstraint(const unsigned int num_dofs) : ompl::base::Constraint(num_dofs, 1)
76  {
77  }
78  void function(const Eigen::Ref<const Eigen::VectorXd>& /*unused*/, Eigen::Ref<Eigen::VectorXd> out) const override
79  {
80  out[0] = 0.0;
81  }
82 };
83 
86 {
87 public:
88  TestStateValidityChecker(const std::string& robot_name, const std::string& group_name)
89  : LoadTestRobot(robot_name, group_name)
90  {
91  initial_robot_state_ = std::make_shared<moveit::core::RobotState>(robot_model_);
92  initial_robot_state_->setToDefaultValues();
93  }
94 
96  {
97  SCOPED_TRACE("testEqualityPositionConstraints");
98  EXPECT_TRUE(planning_context_.get());
99  }
100 
101  void testJointLimits(const std::vector<double>& position_in_limits)
102  {
103  SCOPED_TRACE("testJointLimits");
104 
105  // create a validity checker for this test
106  auto checker = std::make_shared<ompl_interface::ConstrainedPlanningStateValidityChecker>(planning_context_.get());
107  checker->setVerbose(VERBOSE);
108 
109  // setup an ompl state with the "position_in_limits" joint values
110  robot_state_->setJointGroupPositions(joint_model_group_, position_in_limits);
111  ompl::base::ScopedState<> ompl_state(constrained_state_space_);
112  state_space_->copyToOMPLState(ompl_state.get(), *robot_state_);
113 
114  // cast ompl state to a specific type, useful in the rest of this test
115  auto state = ompl_state->as<ompl::base::ConstrainedStateSpace::StateType>()
116  ->getState()
118 
119  RCLCPP_DEBUG_STREAM(LOGGER,
120  std::vector<double>(state->values, state->values + joint_model_group_->getVariableCount()));
121 
122  // assume the default position in not in self-collision
123  // and there are no collision objects of path constraints so this state should be valid
124  bool result = checker->isValid(ompl_state.get());
125  EXPECT_TRUE(result);
126 
127  // do the same for the version with distance
128  double distance = 0.0;
129  result = checker->isValid(ompl_state.get(), distance);
130 
131  RCLCPP_DEBUG(LOGGER, "Distance from the isValid function '%f': ", distance);
132  EXPECT_TRUE(result);
133  EXPECT_GT(distance, 0.0);
134 
135  // move first joint obviously outside any joint limits
136  state->values[0] = std::numeric_limits<double>::max();
137  state->clearKnownInformation(); // make sure the validity checker does not use the cached value
138 
139  RCLCPP_DEBUG_STREAM(LOGGER,
140  std::vector<double>(state->values, state->values + joint_model_group_->getVariableCount()));
141 
142  bool result_2 = checker->isValid(ompl_state.get());
143  EXPECT_FALSE(result_2);
144 
145  // do the same for the version with distance
146  double distance_2 = 0.0;
147  result_2 = checker->isValid(ompl_state.get(), distance_2);
148  EXPECT_FALSE(result_2);
149  // isValid function returned false before any distance calculation is done
150  EXPECT_EQ(distance_2, 0.0);
151  }
152 
153  void testSelfCollision(const std::vector<double>& position_in_self_collision)
154  {
155  SCOPED_TRACE("testSelfCollision");
156 
157  // create a validity checker for this test
158  auto checker = std::make_shared<ompl_interface::ConstrainedPlanningStateValidityChecker>(planning_context_.get());
159  checker->setVerbose(VERBOSE);
160 
161  robot_state_->setJointGroupPositions(joint_model_group_, position_in_self_collision);
162 
163  // use a scoped OMPL state so we don't have to call allocState and freeState
164  // (as recommended in the OMPL documantion)
165  ompl::base::ScopedState<> ompl_state(constrained_state_space_);
166  state_space_->copyToOMPLState(ompl_state.get(), *robot_state_);
167 
168  // The code below is just to print the state to the debug stream
169  auto state = ompl_state->as<ompl::base::ConstrainedStateSpace::StateType>()
170  ->getState()
172 
173  // ompl_state.reals() throws a segmentation fault for this state type
174  // use a more involved conversion to std::vector for logging
175  RCLCPP_DEBUG_STREAM(LOGGER,
176  std::vector<double>(state->values, state->values + joint_model_group_->getVariableCount()));
177 
178  // the given state is known to be in self-collision, we check it here
179  bool result = checker->isValid(ompl_state.get());
180  EXPECT_FALSE(result);
181 
182  // do the same for the version with distance
183  double distance = 0.0;
184  result = checker->isValid(ompl_state.get(), distance);
185  EXPECT_FALSE(result);
186 
187  // but it should respect the joint limits
188  bool result_2 = robot_state_->satisfiesBounds();
189  EXPECT_TRUE(result_2);
190  }
191 
192  // /***************************************************************************
193  // * END Test implementation
194  // * ************************************************************************/
195 
196 protected:
197  void SetUp() override
198  {
199  // setup all the input we need to create a StateValidityChecker
200  setupStateSpace();
202  };
203 
204  void TearDown() override
205  {
206  }
207 
209  {
210  // note: make_shared throws if the allocations below fail, making the test fail when necessary
212  state_space_ = std::make_shared<ompl_interface::ConstrainedPlanningStateSpace>(space_spec);
213  state_space_->computeLocations(); // this gets called in the state space factory normally
214 
215  auto dummy_constraint = std::make_shared<DummyConstraint>(num_dofs_);
216  constrained_state_space_ = std::make_shared<ompl::base::ProjectedStateSpace>(state_space_, dummy_constraint);
217  }
218 
220  {
221  ASSERT_NE(state_space_, nullptr) << "Initialize state space before creating the planning context.";
223 
224  // IMPORTANT, we need to create the simple setup with a ConstrainedSpaceInformation object,
225  // not with the state space, as this will allocate the wrong type of SpaceInformation
226  auto csi = std::make_shared<ompl::base::ConstrainedSpaceInformation>(constrained_state_space_);
227  planning_context_spec_.ompl_simple_setup_ = std::make_shared<ompl::geometric::SimpleSetup>(csi);
228 
229  // check if the we succeeded in the comment above
230  auto si = planning_context_spec_.ompl_simple_setup_->getSpaceInformation();
231  auto si_constrained = dynamic_cast<ompl::base::ConstrainedSpaceInformation*>(si.get());
232  ASSERT_NE(si_constrained, nullptr);
233 
235  std::make_shared<ompl_interface::ModelBasedPlanningContext>(group_name_, planning_context_spec_);
236 
237  planning_scene_ = std::make_shared<planning_scene::PlanningScene>(robot_model_);
238  planning_context_->setPlanningScene(planning_scene_);
239  planning_context_->setCompleteInitialState(*initial_robot_state_);
240 
241  RCLCPP_DEBUG(LOGGER, "Planning context with name '%s' is ready (but not configured).",
242  planning_context_->getName().c_str());
243  }
244 
245  moveit::core::RobotStatePtr initial_robot_state_;
246 
247  ompl_interface::ModelBasedStateSpacePtr state_space_;
249  ompl_interface::ModelBasedPlanningContextPtr planning_context_;
250  planning_scene::PlanningScenePtr planning_scene_;
251 
252  ompl::base::ConstrainedStateSpacePtr constrained_state_space_;
253 };
254 
255 // /***************************************************************************
256 // * Run all tests on the Panda robot
257 // * ************************************************************************/
259 {
260 protected:
262  {
263  }
264 };
265 
267 {
268  testConstructor();
269 }
270 
272 {
273  // use the panda "ready" state from the srdf config
274  // we know this state should be within limits and self-collision free
275  testJointLimits({ 0, -0.785, 0, -2.356, 0, 1.571, 0.785 });
276 }
277 
279 {
280  // the given state has self collision between "hand" and "panda_link2"
281  // (I just tried a couple of random states until I found one that collided.)
282  testSelfCollision({ 2.31827, -0.169668, 2.5225, -2.98568, -0.36355, 0.808339, 0.0843406 });
283 }
284 
285 /***************************************************************************
286  * Run all tests on the Fanuc robot
287  * ************************************************************************/
289 {
290 protected:
292  {
293  }
294 };
295 
296 TEST_F(FanucTestStateValidityChecker, createStateValidityChecker)
297 {
298  testConstructor();
299 }
300 
302 {
303  // I assume the Fanucs's zero state is within limits and self-collision free
304  testJointLimits({ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 });
305 }
306 
308 {
309  // the given state has self collision between "base_link" and "link_5"
310  // (I just tried a couple of random states until I found one that collided.)
311  testSelfCollision({ -2.95993, -0.682185, -2.43873, -0.939784, 3.0544, 0.882294 });
312 }
313 
314 /* (Note: the PR2 has no collision geometry in the moveit_resources package.) */
315 
316 /***************************************************************************
317  * MAIN
318  * ************************************************************************/
319 int main(int argc, char** argv)
320 {
321  testing::InitGoogleTest(&argc, argv);
322  return RUN_ALL_TESTS();
323 }
Dummy constraint for testing, always satisfied. We need this to create and OMPL ConstrainedStateSpace...
DummyConstraint(const unsigned int num_dofs)
Generic implementation of the tests that can be executed on different robots.
ompl_interface::ModelBasedStateSpacePtr state_space_
void testJointLimits(const std::vector< double > &position_in_limits)
void testSelfCollision(const std::vector< double > &position_in_self_collision)
planning_scene::PlanningScenePtr planning_scene_
ompl::base::ConstrainedStateSpacePtr constrained_state_space_
ompl_interface::ModelBasedPlanningContextSpecification planning_context_spec_
ompl_interface::ModelBasedPlanningContextPtr planning_context_
TestStateValidityChecker(const std::string &robot_name, const std::string &group_name)
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
Robot independent test class setup.
moveit::core::RobotStatePtr robot_state_
moveit::core::RobotModelPtr robot_model_
LoadTestRobot(const std::string &robot_name, const std::string &group_name)
const moveit::core::JointModelGroup * joint_model_group_
double distance(const urdf::Pose &transform)
Definition: pr2_arm_ik.h:55
int main(int argc, char **argv)
std::ostream & operator<<(std::ostream &os, const std::vector< double > &v)
Pretty print std:vectors.
constexpr bool VERBOSE
This flag sets the verbosity level for the state validity checker.
TEST_F(PandaValidityCheckerTests, testConstructor)
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)