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