moveit2
The MoveIt Motion Planning Framework for ROS 2.
test_constrained_planning_state_space.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 
41 #include <memory>
42 #include <string>
43 #include <iostream>
44 
45 #include <gtest/gtest.h>
46 #include <Eigen/Dense>
47 
53 #include <moveit_msgs/msg/constraints.hpp>
54 
55 #include <ompl/util/Exception.h>
56 #include <ompl/base/spaces/RealVectorStateSpace.h>
57 #include <ompl/base/spaces/constraint/ProjectedStateSpace.h>
58 
59 #include "load_test_robot.h"
60 
61 static const rclcpp::Logger LOGGER =
62  rclcpp::get_logger("moveit.ompl_planning.test.test_constrained_planning_state_space");
63 
65 class DummyConstraint : public ompl::base::Constraint
66 {
67 public:
68  DummyConstraint(const unsigned int num_dofs) : ompl::base::Constraint(num_dofs, 1)
69  {
70  }
71  void function(const Eigen::Ref<const Eigen::VectorXd>& /*unused*/, Eigen::Ref<Eigen::VectorXd> out) const override
72  {
73  out[0] = 0.0;
74  }
75 };
76 
79 {
80 protected:
81  TestConstrainedStateSpace(const std::string& robot_name, const std::string& group_name)
82  : LoadTestRobot(robot_name, group_name)
83  {
84  }
85 
86  void SetUp() override
87  {
88  // create a constrained state space for testing
91  };
92 
93  void TearDown() override
94  {
95  }
96 
98  {
100  moveit_state_space_ = std::make_shared<ompl_interface::ConstrainedPlanningStateSpace>(space_spec);
101  }
102 
104  {
105  // first call setupMoveItStateSpace()
106  assert(moveit_state_space_ != nullptr);
107  auto con = std::make_shared<DummyConstraint>(num_dofs_);
108  constrained_state_space_ = std::make_shared<ompl::base::ProjectedStateSpace>(moveit_state_space_, con);
109  }
110 
112  {
113  SCOPED_TRACE("testGetValueAddressAtIndex");
114 
115  Eigen::VectorXd joint_positions = getDeterministicState();
116  ompl::base::ScopedState<> ompl_state(constrained_state_space_);
117  auto state_ptr = ompl_state->as<ompl::base::ConstrainedStateSpace::StateType>()->getState();
118  double* out_joint_positions = dynamic_cast<ompl_interface::ModelBasedStateSpace::StateType*>(state_ptr)->values;
119  EXPECT_FALSE(out_joint_positions == nullptr);
120 
121  for (std::size_t i = 0; i < num_dofs_; ++i)
122  {
123  *(out_joint_positions + i) = joint_positions[i];
124  }
125 
126  // check getValueAddressAtIndex
127  // it can only be called with an already unwrapped state,
128  // this unwrapping is either done in the constrained_state_space_ (see WrapperStateSpace in OMPL),
129  // or in copyJointToOMPLState in the implementation of ConstrainedPlanningStateSpace in MoveIt.
130  for (std::size_t i = 0; i < num_dofs_; ++i)
131  {
132  EXPECT_EQ(joint_positions[i], *(constrained_state_space_->getValueAddressAtIndex(ompl_state.get(), i)));
133  }
134  }
135 
137  {
138  SCOPED_TRACE("testCopyToRobotState");
139 
140  // create and OMPL state
141  // The copy operation of the ConstraintStateSpace::StateType show below is not supported
142  // ompl_state->as<ompl::base::ConstrainedStateSpace::StateType>()->copy(joint_positions);
143  // Because the state spaces implemented in MoveIt do not support casting to Eigen::VectorXd
144  Eigen::VectorXd joint_positions = getDeterministicState();
145  ompl::base::ScopedState<> ompl_state(constrained_state_space_);
146  auto state_ptr = ompl_state->as<ompl::base::ConstrainedStateSpace::StateType>()->getState();
147  double* out_joint_positions = dynamic_cast<ompl_interface::ModelBasedStateSpace::StateType*>(state_ptr)->values;
148  EXPECT_FALSE(out_joint_positions == nullptr);
149 
150  for (std::size_t i = 0; i < num_dofs_; ++i)
151  {
152  *(out_joint_positions + i) = joint_positions[i];
153  }
154 
155  // copy into a MoveIt state
157  moveit_state.setToDefaultValues();
158  moveit_state_space_->copyToRobotState(moveit_state, ompl_state.get());
159 
160  // check if copy worked out as expected
161  Eigen::VectorXd out_joint_position(num_dofs_);
162  moveit_state.copyJointGroupPositions(joint_model_group_, out_joint_position);
163 
164  EXPECT_EQ(joint_positions.size(), out_joint_position.size());
165 
166  for (std::size_t i = 0; i < num_dofs_; ++i)
167  {
168  EXPECT_EQ(joint_positions[i], out_joint_position[i]);
169  }
170  }
171 
173  {
174  SCOPED_TRACE("testCopyToOMPLState");
175 
176  // create a MoveIt state
177  Eigen::VectorXd joint_positions = getDeterministicState();
179  moveit_state.setToDefaultValues();
180  moveit_state.setJointGroupPositions(joint_model_group_, joint_positions);
181 
182  // copy into an OMPL state
183  ompl::base::ScopedState<> ompl_state(constrained_state_space_);
184  moveit_state_space_->copyToOMPLState(ompl_state.get(), moveit_state);
185 
186  // check if copy worked out as expected
187  // (Again, support for casting to Eigen::VectorXd would have been nice here.)
188  auto state_ptr = ompl_state->as<ompl::base::ConstrainedStateSpace::StateType>()->getState();
189  double* out_joint_positions = dynamic_cast<ompl_interface::ModelBasedStateSpace::StateType*>(state_ptr)->values;
190  EXPECT_FALSE(out_joint_positions == nullptr);
191 
192  for (std::size_t i = 0; i < num_dofs_; ++i)
193  {
194  EXPECT_EQ(joint_positions[i], *(out_joint_positions + i));
195  }
196  }
197 
199  {
200  SCOPED_TRACE("testCopyJointToOMPLState");
201 
202  EXPECT_TRUE(true);
203  // create a MoveIt state
204  Eigen::VectorXd joint_positions = getDeterministicState();
206  moveit_state.setToDefaultValues();
207  moveit_state.setJointGroupPositions(joint_model_group_, joint_positions);
208 
209  // copy into an OMPL state, one index at a time
210  ompl::base::ScopedState<> ompl_state(constrained_state_space_);
211  auto joint_model_names = joint_model_group_->getActiveJointModelNames();
212 
213  for (std::size_t joint_index = 0; joint_index < num_dofs_; ++joint_index)
214  {
215  const moveit::core::JointModel* joint_model = joint_model_group_->getJointModel(joint_model_names[joint_index]);
216  EXPECT_FALSE(joint_model == nullptr);
217 
218  RCLCPP_DEBUG_STREAM(LOGGER, "Joint model: " << joint_model->getName() << " index: " << joint_index);
219  RCLCPP_DEBUG_STREAM(LOGGER, "first index: " << joint_model->getFirstVariableIndex() * sizeof(double));
220  RCLCPP_DEBUG_STREAM(LOGGER, "width: " << joint_model->getVariableCount() * sizeof(double));
221 
222  moveit_state_space_->copyJointToOMPLState(ompl_state.get(), moveit_state, joint_model, joint_index);
223  }
224 
225  // check if copy worked out as expected
226  auto state_ptr = ompl_state->as<ompl::base::ConstrainedStateSpace::StateType>()->getState();
227  double* out_joint_positions = dynamic_cast<ompl_interface::ModelBasedStateSpace::StateType*>(state_ptr)->values;
228  EXPECT_FALSE(out_joint_positions == nullptr);
229 
230  for (std::size_t i = 0; i < num_dofs_; ++i)
231  {
232  EXPECT_EQ(joint_positions[i], *(out_joint_positions + i));
233  }
234  }
235 
236 protected:
237  ompl::base::ConstrainedStateSpacePtr constrained_state_space_;
238  ompl_interface::ConstrainedPlanningStateSpacePtr moveit_state_space_;
239 };
240 
241 // /***************************************************************************
242 // * Run all tests on the Panda robot
243 // * ************************************************************************/
245 {
246 protected:
248  {
249  }
250 };
251 
252 TEST_F(PandaCopyStateTest, testGetValueAddressAtIndex)
253 {
254  testGetValueAddressAtIndex();
255 }
256 
257 TEST_F(PandaCopyStateTest, testCopyToRobotState)
258 {
259  testCopyToRobotState();
260 }
261 
262 TEST_F(PandaCopyStateTest, testCopyToOMPLState)
263 {
264  testCopyToOMPLState();
265 }
266 
267 TEST_F(PandaCopyStateTest, testCopyJointToOMPLState)
268 {
269  testCopyJointToOMPLState();
270 }
271 
272 /***************************************************************************
273  * Run all tests on the Fanuc robot
274  * ************************************************************************/
276 {
277 protected:
278  FanucCopyStateTest() : TestConstrainedStateSpace("fanuc", "manipulator")
279  {
280  }
281 };
282 
283 TEST_F(FanucCopyStateTest, testGetValueAddressAtIndex)
284 {
285  testGetValueAddressAtIndex();
286 }
287 
288 TEST_F(FanucCopyStateTest, testCopyToRobotState)
289 {
290  testCopyToRobotState();
291 }
292 
293 TEST_F(FanucCopyStateTest, testCopyToOMPLState)
294 {
295  testCopyToOMPLState();
296 }
297 
298 TEST_F(FanucCopyStateTest, testCopyJointToOMPLState)
299 {
300  testCopyJointToOMPLState();
301 }
302 
303 // /***************************************************************************
304 // * Run all tests on the PR2 robot its left arm
305 // * ************************************************************************/
307 {
308 protected:
310  {
311  }
312 };
313 
314 TEST_F(PR2CopyStateTest, testGetValueAddressAtIndex)
315 {
316  testGetValueAddressAtIndex();
317 }
318 
319 TEST_F(PR2CopyStateTest, testCopyToRobotState)
320 {
321  testCopyToRobotState();
322 }
323 
324 TEST_F(PR2CopyStateTest, testCopyToOMPLState)
325 {
326  testCopyToOMPLState();
327 }
328 
329 TEST_F(PR2CopyStateTest, testCopyJointToOMPLState)
330 {
331  testCopyJointToOMPLState();
332 }
333 
334 /***************************************************************************
335  * MAIN
336  * ************************************************************************/
337 int main(int argc, char** argv)
338 {
339  testing::InitGoogleTest(&argc, argv);
340  return RUN_ALL_TESTS();
341 }
Dummy constraint for testing, always satisfied. We need this to create and OMPL ConstrainedStateSpace...
DummyConstraint(const unsigned int num_dofs)
Robot indepentent implementation of the tests.
TestConstrainedStateSpace(const std::string &robot_name, const std::string &group_name)
ompl_interface::ConstrainedPlanningStateSpacePtr moveit_state_space_
ompl::base::ConstrainedStateSpacePtr constrained_state_space_
const JointModel * getJointModel(const std::string &joint) const
Get a joint by its name. Throw an exception if the joint is not part of this group.
const std::vector< std::string > & getActiveJointModelNames() const
Get the names of the active joints in this group. These are the names of the joints returned by getJo...
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:117
size_t getFirstVariableIndex() const
Get the index of this joint's first variable within the full robot state.
Definition: joint_model.h:216
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
Definition: joint_model.h:210
const std::string & getName() const
Get the name of the joint.
Definition: joint_model.h:145
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
Definition: robot_state.h:605
void copyJointGroupPositions(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the position values of the variables that make up the group into another loca...
Definition: robot_state.h:691
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
Robot independent test class setup.
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_
TEST_F(PandaCopyStateTest, testGetValueAddressAtIndex)
int main(int argc, char **argv)
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)