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