test_state_validity_checker.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2020, KU Leuven
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 KU Leuven 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: Jeroen De Maeyer */
51 #include "load_test_robot.h"
52 
53 #include <limits>
54 #include <ostream>
55 
56 #include <gtest/gtest.h>
57 
62 
63 #include <ompl/geometric/SimpleSetup.h>
64 
66 constexpr bool VERBOSE{ false };
67 
68 constexpr char LOGNAME[] = "test_state_validity_checker";
69 
71 std::ostream& operator<<(std::ostream& os, const std::vector<double>& v)
72 {
73  os << "( ";
74  for (auto value : v)
75  os << value << ", ";
76  os << " )";
77  return os;
78 }
79 
82 {
83 public:
84  TestStateValidityChecker(const std::string& robot_name, const std::string& group_name)
85  : LoadTestRobot(robot_name, group_name)
86  {
87  }
88 
89  /***************************************************************************
90  * START Test implementations
91  * ************************************************************************/
92 
94  {
95  ompl::base::StateValidityCheckerPtr checker =
96  std::make_shared<ompl_interface::StateValidityChecker>(planning_context_.get());
97  }
98 
100  void testJointLimits(const std::vector<double>& position_in_limits)
101  {
102  // create a validity checker for this test
103  auto checker = std::make_shared<ompl_interface::StateValidityChecker>(planning_context_.get());
104  checker->setVerbose(VERBOSE);
105 
106  robot_state_->setJointGroupPositions(joint_model_group_, position_in_limits);
107 
108  // use a scoped OMPL state so we don't have to call allocState and freeState
109  // (as recommended in the OMPL documantion)
110  ompl::base::ScopedState<> ompl_state(state_space_);
111  state_space_->copyToOMPLState(ompl_state.get(), *robot_state_);
112 
113  ROS_DEBUG_STREAM_NAMED(LOGNAME, ompl_state.reals());
114 
115  // assume the given position is not in self-collision
116  // and there are no collision objects or path constraints so this state should be valid
117  EXPECT_TRUE(checker->isValid(ompl_state.get()));
118 
119  // move first joint obviously outside any joint limits
120  ompl_state->as<ompl_interface::JointModelStateSpace::StateType>()->values[0] = std::numeric_limits<double>::max();
121  ompl_state->as<ompl_interface::JointModelStateSpace::StateType>()->clearKnownInformation();
122 
123  ROS_DEBUG_STREAM_NAMED(LOGNAME, ompl_state.reals());
124 
125  EXPECT_FALSE(checker->isValid(ompl_state.get()));
126  }
127 
129  void testSelfCollision(const std::vector<double>& position_in_self_collision)
130  {
131  // create a validity checker for this test
132  auto checker = std::make_shared<ompl_interface::StateValidityChecker>(planning_context_.get());
133  checker->setVerbose(VERBOSE);
134 
135  robot_state_->setJointGroupPositions(joint_model_group_, position_in_self_collision);
136 
137  // use a scoped OMPL state so we don't have to call allocState and freeState
138  // (as recommended in the OMPL documantion)
139  ompl::base::ScopedState<> ompl_state(state_space_);
140  state_space_->copyToOMPLState(ompl_state.get(), *robot_state_);
141 
142  ROS_DEBUG_STREAM_NAMED(LOGNAME, ompl_state.reals());
143 
144  // the given state is known to be in self-collision, we check it here
145  EXPECT_FALSE(checker->isValid(ompl_state.get()));
146 
147  // but it should respect the joint limits
148  EXPECT_TRUE(robot_state_->satisfiesBounds());
149  }
150 
151  void testPathConstraints(const std::vector<double>& position_in_joint_limits)
152  {
153  ASSERT_NE(planning_context_, nullptr) << "Initialize planning context before adding path constraints.";
154 
155  // set the robot to a known position that is withing the joint limits and collision free
156  robot_state_->setJointGroupPositions(joint_model_group_, position_in_joint_limits);
157 
158  // create position constraints around the given robot state
159  moveit_msgs::Constraints path_constraints;
160  Eigen::Isometry3d ee_pose = robot_state_->getGlobalLinkTransform(ee_link_name_);
161  path_constraints.name = "test_position_constraints";
162  path_constraints.position_constraints.push_back(createPositionConstraint(
163  { ee_pose.translation().x(), ee_pose.translation().y(), ee_pose.translation().z() }, { 0.1, 0.1, 0.1 }));
164 
165  moveit_msgs::MoveItErrorCodes error_code_not_used;
166  ASSERT_TRUE(planning_context_->setPathConstraints(path_constraints, &error_code_not_used));
167 
168  auto checker = std::make_shared<ompl_interface::StateValidityChecker>(planning_context_.get());
169  checker->setVerbose(VERBOSE);
170 
171  // use a scoped OMPL state so we don't have to call allocState and freeState
172  // (as recommended in the OMPL documantion)
173  ompl::base::ScopedState<> ompl_state(state_space_);
174  state_space_->copyToOMPLState(ompl_state.get(), *robot_state_);
175 
176  ROS_DEBUG_STREAM_NAMED(LOGNAME, ompl_state.reals());
177 
178  EXPECT_TRUE(checker->isValid(ompl_state.get()));
179 
180  // move the position constraints away from the curren end-effector position to make it fail
181  moveit_msgs::Constraints path_constraints_2(path_constraints);
182  path_constraints_2.position_constraints.at(0).constraint_region.primitive_poses.at(0).position.z += 0.2;
183 
184  ASSERT_TRUE(planning_context_->setPathConstraints(path_constraints_2, &error_code_not_used));
185 
186  // clear the cached validity of the state before checking again,
187  // otherwise the path constraints will not be checked.
188  ompl_state->as<ompl_interface::JointModelStateSpace::StateType>()->clearKnownInformation();
189 
190  EXPECT_FALSE(checker->isValid(ompl_state.get()));
191  }
192 
193  /***************************************************************************
194  * END Test implementation
195  * ************************************************************************/
196 
197 protected:
198  void SetUp() override
199  {
200  // setup all the input we need to create a StateValidityChecker
201  setupStateSpace();
203  };
204 
206  {
208  state_space_ = std::make_shared<ompl_interface::JointModelStateSpace>(space_spec);
209  state_space_->computeLocations(); // this gets normally called in the state space factory
210  }
211 
213  {
214  ASSERT_NE(state_space_, nullptr) << "Initialize state space before creating the planning context.";
215 
217  planning_context_spec_.ompl_simple_setup_ = std::make_shared<ompl::geometric::SimpleSetup>(state_space_);
219  std::make_shared<ompl_interface::ModelBasedPlanningContext>(group_name_, planning_context_spec_);
220 
221  planning_scene_ = std::make_shared<planning_scene::PlanningScene>(robot_model_);
222  planning_context_->setPlanningScene(planning_scene_);
224  start_state.setToDefaultValues();
225  planning_context_->setCompleteInitialState(start_state);
226  }
227 
229  moveit_msgs::PositionConstraint createPositionConstraint(std::array<double, 3> position,
230  std::array<double, 3> dimensions)
231  {
232  shape_msgs::SolidPrimitive box;
233  box.type = shape_msgs::SolidPrimitive::BOX;
234  box.dimensions.resize(3);
235  box.dimensions[shape_msgs::SolidPrimitive::BOX_X] = dimensions[0];
236  box.dimensions[shape_msgs::SolidPrimitive::BOX_Y] = dimensions[1];
237  box.dimensions[shape_msgs::SolidPrimitive::BOX_Z] = dimensions[2];
238 
239  geometry_msgs::Pose box_pose;
240  box_pose.position.x = position[0];
241  box_pose.position.y = position[1];
242  box_pose.position.z = position[2];
243  box_pose.orientation.w = 1.0;
244 
245  moveit_msgs::PositionConstraint position_constraint;
246  position_constraint.header.frame_id = base_link_name_;
247  position_constraint.link_name = ee_link_name_;
248  position_constraint.constraint_region.primitives.push_back(box);
249  position_constraint.constraint_region.primitive_poses.push_back(box_pose);
250 
251  // set the default weight to avoid warning in test output
252  position_constraint.weight = 1.0;
253 
254  return position_constraint;
255  }
256 
257  ompl_interface::ModelBasedStateSpacePtr state_space_;
259  ompl_interface::ModelBasedPlanningContextPtr planning_context_;
260  planning_scene::PlanningScenePtr planning_scene_;
261 };
262 
263 // /***************************************************************************
264 // * Run all tests on the Panda robot
265 // * ************************************************************************/
267 {
268 protected:
269  PandaValidity() : TestStateValidityChecker("panda", "panda_arm")
270  {
271  }
272 };
273 
274 TEST_F(PandaValidity, testConstructor)
275 {
276  testConstructor();
277 }
278 
279 TEST_F(PandaValidity, testJointLimits)
280 {
281  // use the panda "ready" state from the srdf config
282  // we know this state should be within limits and self-collision free
283  testJointLimits({ 0, -0.785, 0, -2.356, 0, 1.571, 0.785 });
284 }
285 
286 TEST_F(PandaValidity, testSelfCollision)
287 {
288  // the given state has self collision between "hand" and "panda_link2"
289  // (I just tried a couple of random states until I found one that collided.)
290  testSelfCollision({ 2.31827, -0.169668, 2.5225, -2.98568, -0.36355, 0.808339, 0.0843406 });
291 }
292 
293 TEST_F(PandaValidity, testPathConstraints)
294 {
295  // use the panda "ready" state from the srdf config
296  // we know this state should be within limits and self-collision free
297  testPathConstraints({ 0, -0.785, 0, -2.356, 0, 1.571, 0.785 });
298 }
299 
300 /***************************************************************************
301  * Run all tests on the Fanuc robot
302  * ************************************************************************/
304 {
305 protected:
306  FanucTest() : TestStateValidityChecker("fanuc", "manipulator")
307  {
308  }
309 };
310 
311 TEST_F(FanucTest, createStateValidityChecker)
312 {
313  testConstructor();
314 }
315 
316 TEST_F(FanucTest, testJointLimits)
317 {
318  // I assume the Fanucs's zero state is within limits and self-collision free
319  testJointLimits({ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 });
320 }
321 
322 TEST_F(FanucTest, testSelfCollision)
323 {
324  // the given state has self collision between "base_link" and "link_5"
325  // (I just tried a couple of random states until I found one that collided.)
326  testSelfCollision({ -2.95993, -0.682185, -2.43873, -0.939784, 3.0544, 0.882294 });
327 }
328 
329 TEST_F(FanucTest, testPathConstraints)
330 {
331  // I assume the Fanucs's zero state is within limits and self-collision free
332  testPathConstraints({ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 });
333 }
334 
335 /***************************************************************************
336  * MAIN
337  * ************************************************************************/
338 int main(int argc, char** argv)
339 {
340  testing::InitGoogleTest(&argc, argv);
341  return RUN_ALL_TESTS();
342 }
TestStateValidityChecker::setupStateSpace
void setupStateSpace()
Definition: test_state_validity_checker.cpp:205
ompl_interface_testing::LoadTestRobot::ee_link_name_
std::string ee_link_name_
Definition: load_test_robot.h:192
TestStateValidityChecker::planning_context_spec_
ompl_interface::ModelBasedPlanningContextSpecification planning_context_spec_
Definition: test_state_validity_checker.cpp:258
main
int main(int argc, char **argv)
Definition: test_state_validity_checker.cpp:338
model_based_planning_context.h
ROS_DEBUG_STREAM_NAMED
#define ROS_DEBUG_STREAM_NAMED(name, args)
TestStateValidityChecker::TestStateValidityChecker
TestStateValidityChecker(const std::string &robot_name, const std::string &group_name)
Definition: test_state_validity_checker.cpp:84
TestStateValidityChecker::testJointLimits
void testJointLimits(const std::vector< double > &position_in_limits)
Definition: test_state_validity_checker.cpp:100
ompl_interface::ModelBasedStateSpaceSpecification
Definition: model_based_state_space.h:84
FanucTest::FanucTest
FanucTest()
Definition: test_state_validity_checker.cpp:308
TestStateValidityChecker::testConstructor
void testConstructor()
Definition: test_state_validity_checker.cpp:93
ompl_interface::ModelBasedStateSpace::StateType
Definition: model_based_state_space.h:109
LOGNAME
constexpr char LOGNAME[]
Definition: test_state_validity_checker.cpp:68
moveit::core::RobotState
ompl_interface_testing::LoadTestRobot
Robot independent test class setup.
Definition: load_test_robot.h:130
PandaValidity
Definition: test_state_validity_checker.cpp:266
ompl_interface_testing::LoadTestRobot::base_link_name_
std::string base_link_name_
Definition: load_test_robot.h:191
ompl_interface_testing::LoadTestRobot::LoadTestRobot
LoadTestRobot(const std::string &robot_name, const std::string &group_name)
Definition: load_test_robot.h:165
EXPECT_TRUE
#define EXPECT_TRUE(args)
ompl_interface_testing::LoadTestRobot::joint_model_group_
const robot_state::JointModelGroup * joint_model_group_
Definition: load_test_robot.h:188
load_test_robot.h
ompl_interface::ModelBasedPlanningContextSpecification::ompl_simple_setup_
og::SimpleSetupPtr ompl_simple_setup_
Definition: model_based_planning_context.h:102
TestStateValidityChecker::testSelfCollision
void testSelfCollision(const std::vector< double > &position_in_self_collision)
Definition: test_state_validity_checker.cpp:129
joint_model_state_space.h
TestStateValidityChecker::SetUp
void SetUp() override
Definition: test_state_validity_checker.cpp:198
state_validity_checker.h
moveit::core::RobotState::setToDefaultValues
void setToDefaultValues()
TestStateValidityChecker::createPositionConstraint
moveit_msgs::PositionConstraint createPositionConstraint(std::array< double, 3 > position, std::array< double, 3 > dimensions)
Helper function to create a position constraint.
Definition: test_state_validity_checker.cpp:229
TestStateValidityChecker::testPathConstraints
void testPathConstraints(const std::vector< double > &position_in_joint_limits)
Definition: test_state_validity_checker.cpp:151
ompl_interface_testing::LoadTestRobot::group_name_
const std::string group_name_
Definition: load_test_robot.h:183
ompl_interface_testing::LoadTestRobot::robot_state_
robot_state::RobotStatePtr robot_state_
Definition: load_test_robot.h:187
FanucTest
Definition: test_state_validity_checker.cpp:303
ompl_interface::ModelBasedPlanningContextSpecification
Definition: model_based_planning_context.h:95
TestStateValidityChecker::planning_scene_
planning_scene::PlanningScenePtr planning_scene_
Definition: test_state_validity_checker.cpp:260
planning_scene.h
values
std::vector< double > values
VERBOSE
constexpr bool VERBOSE
This flag sets the verbosity level for the state validity checker.
Definition: test_state_validity_checker.cpp:66
TestStateValidityChecker::state_space_
ompl_interface::ModelBasedStateSpacePtr state_space_
Definition: test_state_validity_checker.cpp:257
x
double x
PandaValidity::PandaValidity
PandaValidity()
Definition: test_state_validity_checker.cpp:269
operator<<
std::ostream & operator<<(std::ostream &os, const std::vector< double > &v)
Pretty print std:vectors.
Definition: test_state_validity_checker.cpp:71
ompl_interface_testing::LoadTestRobot::robot_model_
moveit::core::RobotModelPtr robot_model_
Definition: load_test_robot.h:186
TestStateValidityChecker::planning_context_
ompl_interface::ModelBasedPlanningContextPtr planning_context_
Definition: test_state_validity_checker.cpp:259
TestStateValidityChecker::setupPlanningContext
void setupPlanningContext()
Definition: test_state_validity_checker.cpp:212
ompl_interface::ModelBasedPlanningContextSpecification::state_space_
ModelBasedStateSpacePtr state_space_
Definition: model_based_planning_context.h:101
TEST_F
TEST_F(PandaValidity, testConstructor)
Definition: test_state_validity_checker.cpp:274
TestStateValidityChecker
Generic implementation of the tests that can be executed on different robots.
Definition: test_state_validity_checker.cpp:81
EXPECT_FALSE
#define EXPECT_FALSE(args)


ompl
Author(s): Ioan Sucan
autogenerated on Wed Feb 21 2024 03:26:02