moveit2
The MoveIt Motion Planning Framework for ROS 2.
test_ompl_constraints.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 */
36 
44 #include "load_test_robot.h"
45 
46 #include <memory>
47 #include <string>
48 #include <iostream>
49 
50 #include <gtest/gtest.h>
51 #include <Eigen/Dense>
52 
58 #include <moveit_msgs/msg/constraints.hpp>
59 
60 #include <ompl/util/Exception.h>
61 #include <ompl/base/spaces/RealVectorStateSpace.h>
62 #include <ompl/base/spaces/constraint/ProjectedStateSpace.h>
63 #include <ompl/base/ConstrainedSpaceInformation.h>
64 
65 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ompl_planning.test.test_ompl_constraints");
66 
68 constexpr int NUM_RANDOM_TESTS = 10;
69 
71 constexpr unsigned int DIFFERENT_LINK_OFFSET = 2;
72 
78 constexpr double JAC_ERROR_TOLERANCE = 1e-4;
79 
81 moveit_msgs::msg::PositionConstraint createPositionConstraint(std::string& base_link, std::string& ee_link)
82 {
83  shape_msgs::msg::SolidPrimitive box_constraint;
84  box_constraint.type = shape_msgs::msg::SolidPrimitive::BOX;
85  box_constraint.dimensions = { 0.05, 0.4, 0.05 }; /* use -1 to indicate no constraints. */
86 
87  geometry_msgs::msg::Pose box_pose;
88  box_pose.position.x = 0.9;
89  box_pose.position.y = 0.0;
90  box_pose.position.z = 0.2;
91  box_pose.orientation.w = 1.0;
92 
93  moveit_msgs::msg::PositionConstraint position_constraint;
94  position_constraint.header.frame_id = base_link;
95  position_constraint.link_name = ee_link;
96  position_constraint.constraint_region.primitives.push_back(box_constraint);
97  position_constraint.constraint_region.primitive_poses.push_back(box_pose);
98 
99  return position_constraint;
100 }
101 
102 class TestOMPLConstraints : public ompl_interface_testing::LoadTestRobot, public testing::Test
103 {
104 protected:
105  TestOMPLConstraints(const std::string& robot_name, const std::string& group_name)
106  : LoadTestRobot(robot_name, group_name)
107  {
108  }
109 
110  void SetUp() override
111  {
112  }
113 
114  void TearDown() override
115  {
116  }
117 
119  const Eigen::Isometry3d fk(const Eigen::VectorXd& q, const std::string& link_name) const
120  {
121  robot_state_->setJointGroupPositions(joint_model_group_, q);
122  return robot_state_->getGlobalLinkTransform(link_name);
123  }
124 
125  Eigen::VectorXd getRandomState()
126  {
127  robot_state_->setToRandomPositions(joint_model_group_);
128  Eigen::VectorXd joint_positions;
129  robot_state_->copyJointGroupPositions(joint_model_group_, joint_positions);
130  return joint_positions;
131  }
132 
133  Eigen::MatrixXd numericalJacobianPosition(const Eigen::VectorXd& q, const std::string& link_name) const
134  {
135  const double h = 1e-6; /* step size for numerical derivation */
136 
137  Eigen::MatrixXd jacobian = Eigen::MatrixXd::Zero(3, num_dofs_);
138 
139  // helper matrix for differentiation.
140  Eigen::MatrixXd m_helper = h * Eigen::MatrixXd::Identity(num_dofs_, num_dofs_);
141 
142  for (std::size_t dim = 0; dim < num_dofs_; ++dim)
143  {
144  Eigen::Vector3d pos = fk(q, link_name).translation();
145  Eigen::Vector3d pos_plus_h = fk(q + m_helper.col(dim), link_name).translation();
146  Eigen::Vector3d col = (pos_plus_h - pos) / h;
147  jacobian.col(dim) = col;
148  }
149  return jacobian;
150  }
151 
153  {
154  moveit_msgs::msg::Constraints constraint_msgs;
155  constraint_msgs.position_constraints.push_back(createPositionConstraint(base_link_name_, ee_link_name_));
156 
157  constraint_ = std::make_shared<ompl_interface::BoxConstraint>(robot_model_, group_name_, num_dofs_);
158  constraint_->init(constraint_msgs);
159  }
160 
163  {
164  std::string different_link = joint_model_group_->getLinkModelNames().at(num_dofs_ - DIFFERENT_LINK_OFFSET);
165 
166  RCLCPP_DEBUG_STREAM(LOGGER, different_link);
167 
168  moveit_msgs::msg::Constraints constraint_msgs;
169  constraint_msgs.position_constraints.push_back(createPositionConstraint(base_link_name_, different_link));
170 
171  constraint_ = std::make_shared<ompl_interface::BoxConstraint>(robot_model_, group_name_, num_dofs_);
172  constraint_->init(constraint_msgs);
173  }
174 
176  {
177  moveit_msgs::msg::PositionConstraint pos_con_msg = createPositionConstraint(base_link_name_, ee_link_name_);
178 
179  // Make the tolerance on the x dimension smaller than the threshold used to recognize equality constraints.
180  // (see docstring EqualityPositionConstraint::equality_constraint_threshold).
181  pos_con_msg.constraint_region.primitives.at(0).dimensions[0] = 0.0005;
182 
183  // The unconstrained dimensions are set to a large (unused) value
184  pos_con_msg.constraint_region.primitives.at(0).dimensions[1] = 1.0;
185  pos_con_msg.constraint_region.primitives.at(0).dimensions[2] = 1.0;
186 
187  moveit_msgs::msg::Constraints constraint_msgs;
188  constraint_msgs.position_constraints.push_back(pos_con_msg);
189 
190  // Tell the planner to use an Equality constraint model
191  constraint_msgs.name = "use_equality_constraints";
192 
193  constraint_ = std::make_shared<ompl_interface::EqualityPositionConstraint>(robot_model_, group_name_, num_dofs_);
194  constraint_->init(constraint_msgs);
195  }
196 
198  {
199  SCOPED_TRACE("testJacobian");
200 
201  double total_error = 999.9;
202 
203  for (int i = 0; i < NUM_RANDOM_TESTS; ++i)
204  {
205  auto q = getRandomState();
206  auto jac_exact = constraint_->calcErrorJacobian(q);
207 
208  Eigen::MatrixXd jac_approx = numericalJacobianPosition(q, constraint_->getLinkName());
209 
210  RCLCPP_DEBUG_STREAM(LOGGER, "Analytical jacobian:");
211  RCLCPP_DEBUG_STREAM(LOGGER, jac_exact);
212  RCLCPP_DEBUG_STREAM(LOGGER, "Finite difference jacobian:");
213  RCLCPP_DEBUG_STREAM(LOGGER, jac_approx);
214 
215  total_error = (jac_exact - jac_approx).lpNorm<1>();
216  EXPECT_LT(total_error, JAC_ERROR_TOLERANCE);
217  }
218  }
219 
221  {
222  SCOPED_TRACE("testOMPLProjectedStateSpaceConstruction");
223 
224  auto state_space = std::make_shared<ompl::base::RealVectorStateSpace>(num_dofs_);
225  ompl::base::RealVectorBounds bounds(num_dofs_);
226 
227  // get joint limits from the joint model group
229  EXPECT_EQ(joint_limits.size(), num_dofs_);
230 
231  for (std::size_t i = 0; i < num_dofs_; ++i)
232  {
233  EXPECT_EQ(joint_limits[i]->size(), (unsigned int)1);
234  bounds.setLow(i, joint_limits[i]->at(0).min_position_);
235  bounds.setHigh(i, joint_limits[i]->at(0).max_position_);
236  }
237 
238  state_space->setBounds(bounds);
239 
240  auto constrained_state_space = std::make_shared<ompl::base::ProjectedStateSpace>(state_space, constraint_);
241 
242  // constrained_state_space->setStateSamplerAllocator()
243 
244  auto constrained_state_space_info =
245  std::make_shared<ompl::base::ConstrainedSpaceInformation>(constrained_state_space);
246 
247  // TODO(jeroendm) There are some issue with the sanity checks.
248  // But these issues do not prevent us to use the ConstrainedPlanningStateSpace! :)
249  // The jacobian test is expected to fail because of the discontinuous constraint derivative.
250  // In addition not all samples returned from the state sampler will be valid.
251  // For more details: https://github.com/ros-planning/moveit/issues/2092#issuecomment-669911722
252  try
253  {
254  constrained_state_space->sanityChecks();
255  }
256  catch (ompl::Exception& ex)
257  {
258  RCLCPP_ERROR(LOGGER, "Sanity checks did not pass: %s", ex.what());
259  }
260  }
261 
263  {
264  SCOPED_TRACE("testEqualityPositionConstraints");
265 
266  EXPECT_NE(constraint_, nullptr) << "First call setEqualityPositionConstraints before calling this test.";
267 
268  // all test below are in the assumption that we have equality constraints on the x-position, dimension 0.
269 
270  Eigen::VectorXd joint_values = getDeterministicState();
271 
273  f << 99, 99, 99; // fill in known but wrong values that should all be overwritten
274  constraint_->function(joint_values, f);
275 
276  // f should always be zero for unconstrained dimensions
277  EXPECT_DOUBLE_EQ(f[1], 0.0);
278  EXPECT_DOUBLE_EQ(f[2], 0.0);
279 
280  Eigen::MatrixXd jac(3, num_dofs_);
281  jac.setOnes(); // fill in known but wrong values that should all be overwritten
282  constraint_->jacobian(joint_values, jac);
283 
284  for (std::size_t i = 0; i < num_dofs_; ++i)
285  {
286  // rows for unconstrained dimensions should always be zero
287  EXPECT_DOUBLE_EQ(jac(1, i), 0.0);
288  EXPECT_DOUBLE_EQ(jac(2, i), 0.0);
289  }
290  // the constrained x-dimension has some non-zeros
291  // ( we checked this is true for the given joint values!)
292  EXPECT_NE(f[0], 0.0);
293  EXPECT_NE(jac.row(0).squaredNorm(), 0.0);
294  }
295 
296 protected:
297  std::shared_ptr<ompl_interface::BaseConstraint> constraint_;
298 };
299 
300 /***************************************************************************
301  * Run all tests on the Panda robot
302  * ************************************************************************/
304 {
305 protected:
306  PandaConstraintTest() : TestOMPLConstraints("panda", "panda_arm")
307  {
308  }
309 };
310 
311 TEST_F(PandaConstraintTest, InitPositionConstraint)
312 {
313  setPositionConstraints();
314  setPositionConstraintsDifferentLink();
315 }
316 
317 TEST_F(PandaConstraintTest, PositionConstraintJacobian)
318 {
319  setPositionConstraints();
320  testJacobian();
321 
322  constraint_.reset();
323  setPositionConstraintsDifferentLink();
324  testJacobian();
325 }
326 
327 TEST_F(PandaConstraintTest, PositionConstraintOMPLCheck)
328 {
329  setPositionConstraints();
330  testOMPLProjectedStateSpaceConstruction();
331  // testOMPLStateSampler();
332 
333  constraint_.reset();
334  setPositionConstraintsDifferentLink();
335  testOMPLProjectedStateSpaceConstruction();
336 }
337 
338 TEST_F(PandaConstraintTest, EqualityPositionConstraints)
339 {
340  setEqualityPositionConstraints();
341  testOMPLProjectedStateSpaceConstruction();
342  testEqualityPositionConstraints();
343 }
344 /***************************************************************************
345  * Run all tests on the Fanuc robot
346  * ************************************************************************/
348 {
349 protected:
350  FanucConstraintTest() : TestOMPLConstraints("fanuc", "manipulator")
351  {
352  }
353 };
354 
355 TEST_F(FanucConstraintTest, InitPositionConstraint)
356 {
357  setPositionConstraints();
358  setPositionConstraintsDifferentLink();
359 }
360 
361 TEST_F(FanucConstraintTest, PositionConstraintJacobian)
362 {
363  setPositionConstraints();
364  testJacobian();
365 
366  constraint_.reset();
367  setPositionConstraintsDifferentLink();
368  testJacobian();
369 }
370 
371 TEST_F(FanucConstraintTest, PositionConstraintOMPLCheck)
372 {
373  setPositionConstraints();
374  testOMPLProjectedStateSpaceConstruction();
375  // testOMPLStateSampler();
376 
377  constraint_.reset();
378  setPositionConstraintsDifferentLink();
379  testOMPLProjectedStateSpaceConstruction();
380 }
381 
382 TEST_F(FanucConstraintTest, EqualityPositionConstraints)
383 {
384  setEqualityPositionConstraints();
385  testOMPLProjectedStateSpaceConstruction();
386  testEqualityPositionConstraints();
387 }
388 
389 /***************************************************************************
390  * Run all tests on the PR2's left arm
391  * ************************************************************************/
393 {
394 protected:
396  {
397  }
398 };
399 
400 TEST_F(PR2LeftArmConstraintTest, InitPositionConstraint)
401 {
402  setPositionConstraints();
403  setPositionConstraintsDifferentLink();
404 }
405 
406 TEST_F(PR2LeftArmConstraintTest, PositionConstraintJacobian)
407 {
408  setPositionConstraints();
409  testJacobian();
410 
411  constraint_.reset();
412  setPositionConstraintsDifferentLink();
413  testJacobian();
414 }
415 
416 TEST_F(PR2LeftArmConstraintTest, PositionConstraintOMPLCheck)
417 {
418  setPositionConstraints();
419  testOMPLProjectedStateSpaceConstruction();
420 
421  constraint_.reset();
422  setPositionConstraintsDifferentLink();
423  testOMPLProjectedStateSpaceConstruction();
424 }
425 
426 TEST_F(PR2LeftArmConstraintTest, EqualityPositionConstraints)
427 {
428  setEqualityPositionConstraints();
429  testOMPLProjectedStateSpaceConstruction();
430  testEqualityPositionConstraints();
431 }
432 
433 /***************************************************************************
434  * MAIN
435  * ************************************************************************/
436 int main(int argc, char** argv)
437 {
438  testing::InitGoogleTest(&argc, argv);
439  return RUN_ALL_TESTS();
440 }
TestOMPLConstraints(const std::string &robot_name, const std::string &group_name)
std::shared_ptr< ompl_interface::BaseConstraint > constraint_
Eigen::VectorXd getRandomState()
const Eigen::Isometry3d fk(const Eigen::VectorXd &q, const std::string &link_name) const
Robot forward kinematics.
Eigen::MatrixXd numericalJacobianPosition(const Eigen::VectorXd &q, const std::string &link_name) const
void setPositionConstraintsDifferentLink()
Test position constraints a link that is not the end-effector.
const std::vector< std::string > & getLinkModelNames() const
Get the names of the links that are part of this joint group.
const JointBoundsVector & getActiveJointModelsBounds() const
Get the bounds for all the active joints.
Robot independent test class setup.
moveit::core::RobotStatePtr robot_state_
Eigen::VectorXd getDeterministicState() const
Create a joint position vector with values 0.1, 0.2, 0.3, ... where the length depends on the number ...
moveit::core::RobotModelPtr robot_model_
LoadTestRobot(const std::string &robot_name, const std::string &group_name)
const moveit::core::JointModelGroup * joint_model_group_
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
constexpr int NUM_RANDOM_TESTS
Number of times to run a test that uses randomly generated input.
TEST_F(PandaConstraintTest, InitPositionConstraint)
int main(int argc, char **argv)
constexpr unsigned int DIFFERENT_LINK_OFFSET
Select a robot link at (num_dofs - different_link_offset) to test another link than the end-effector.
constexpr double JAC_ERROR_TOLERANCE
Allowed error when comparing Jacobian matrix error.
moveit_msgs::msg::PositionConstraint createPositionConstraint(std::string &base_link, std::string &ee_link)
Helper function to create a specific position constraint.