moveit2
The MoveIt Motion Planning Framework for ROS 2.
test_state_space.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
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 Willow Garage 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: Ioan Sucan */
36 
37 #include <limits>
38 
41 
42 #include <urdf_parser/urdf_parser.h>
43 
44 #include <ompl/util/Exception.h>
47 #include <gtest/gtest.h>
48 #include <fstream>
49 
50 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ompl_planning.test.test_state_space");
51 
52 constexpr double EPSILON = std::numeric_limits<double>::epsilon();
53 
54 class LoadPlanningModelsPr2 : public testing::Test
55 {
56 protected:
57  void SetUp() override
58  {
60  };
61 
62  void TearDown() override
63  {
64  }
65 
66 protected:
67  moveit::core::RobotModelPtr robot_model_;
68 };
69 
71 {
72  ompl_interface::ModelBasedStateSpaceSpecification spec(robot_model_, "whole_body");
74  ss.setPlanningVolume(-1, 1, -1, 1, -1, 1);
75  ss.setup();
76  std::ofstream fout("ompl_interface_test_state_space_diagram1.dot");
77  ss.diagram(fout);
78  bool passed = false;
79  try
80  {
81  ss.sanityChecks();
82  passed = true;
83  }
84  catch (ompl::Exception& ex)
85  {
86  RCLCPP_ERROR(LOGGER, "Sanity checks did not pass: %s", ex.what());
87  }
88  EXPECT_TRUE(passed);
89 }
90 
92 {
93  ompl_interface::ModelBasedStateSpaceSpecification spec1(robot_model_, "right_arm");
95  ss1.setup();
96 
97  ompl_interface::ModelBasedStateSpaceSpecification spec2(robot_model_, "left_arm");
99  ss2.setup();
100 
101  ompl_interface::ModelBasedStateSpaceSpecification spec3(robot_model_, "whole_body");
103  ss3.setup();
104 
105  ompl_interface::ModelBasedStateSpaceSpecification spec4(robot_model_, "arms");
107  ss4.setup();
108 
109  std::ofstream fout("ompl_interface_test_state_space_diagram2.dot");
110  ompl::base::StateSpace::Diagram(fout);
111 }
112 
114 {
115  ompl_interface::ModelBasedStateSpaceSpecification spec(robot_model_, "right_arm");
116  ompl_interface::JointModelStateSpace joint_model_state_space(spec);
117  joint_model_state_space.setPlanningVolume(-1, 1, -1, 1, -1, 1);
118  joint_model_state_space.setup();
119  std::ofstream fout("ompl_interface_test_state_space_diagram1.dot");
120  joint_model_state_space.diagram(fout);
121  bool passed = false;
122  try
123  {
124  joint_model_state_space.sanityChecks();
125  passed = true;
126  }
127  catch (ompl::Exception& ex)
128  {
129  RCLCPP_ERROR(LOGGER, "Sanity checks did not pass: %s", ex.what());
130  }
131  EXPECT_TRUE(passed);
132 
133  moveit::core::RobotState robot_state(robot_model_);
134  robot_state.setToRandomPositions();
135  EXPECT_TRUE(robot_state.distance(robot_state) < EPSILON);
136  ompl::base::State* state = joint_model_state_space.allocState();
137  for (int i = 0; i < 10; ++i)
138  {
139  moveit::core::RobotState robot_state2(robot_state);
140  EXPECT_TRUE(robot_state.distance(robot_state2) < EPSILON);
141  joint_model_state_space.copyToOMPLState(state, robot_state);
142  robot_state.setToRandomPositions(
143  robot_state.getRobotModel()->getJointModelGroup(joint_model_state_space.getJointModelGroupName()));
144  std::cout << (robot_state.getGlobalLinkTransform("r_wrist_roll_link").translation() -
145  robot_state2.getGlobalLinkTransform("r_wrist_roll_link").translation())
146  << '\n';
147  EXPECT_TRUE(robot_state.distance(robot_state2) > EPSILON);
148  joint_model_state_space.copyToRobotState(robot_state, state);
149  std::cout << (robot_state.getGlobalLinkTransform("r_wrist_roll_link").translation() -
150  robot_state2.getGlobalLinkTransform("r_wrist_roll_link").translation())
151  << '\n';
152  EXPECT_TRUE(robot_state.distance(robot_state2) < EPSILON);
153  }
154 
155  // repeat the above test with a different method to copy the state to OMPL
156  for (int i = 0; i < 10; ++i)
157  {
158  // create two equal states
159  moveit::core::RobotState robot_state2(robot_state);
160  EXPECT_LT(robot_state.distance(robot_state2), EPSILON);
161 
162  // copy the first state to OMPL as backup (this is where the 'different' method comes into play)
163  const moveit::core::JointModelGroup* joint_model_group =
164  robot_state.getRobotModel()->getJointModelGroup(joint_model_state_space.getJointModelGroupName());
165  std::vector<std::string> joint_model_names = joint_model_group->getActiveJointModelNames();
166  for (std::size_t joint_index = 0; joint_index < joint_model_group->getVariableCount(); ++joint_index)
167  {
168  const moveit::core::JointModel* joint_model = joint_model_group->getJointModel(joint_model_names[joint_index]);
169  EXPECT_NE(joint_model, nullptr);
170  joint_model_state_space.copyJointToOMPLState(state, robot_state, joint_model, joint_index);
171  }
172 
173  // and change the joint values of the moveit state, so it is different that robot_state2
174  robot_state.setToRandomPositions(
175  robot_state.getRobotModel()->getJointModelGroup(joint_model_state_space.getJointModelGroupName()));
176  EXPECT_GT(robot_state.distance(robot_state2), EPSILON);
177 
178  // copy the backup values in the OMPL state back to the first state,
179  // and check if it is still equal to the second
180  joint_model_state_space.copyToRobotState(robot_state, state);
181  EXPECT_LT(robot_state.distance(robot_state2), EPSILON);
182  }
183 
184  joint_model_state_space.freeState(state);
185 }
186 
187 // Run the OMPL sanity checks on the diff drive model
188 TEST(TestDiffDrive, TestStateSpace)
189 {
190  moveit::core::RobotModelBuilder builder("mobile_base", "base_link");
191  builder.addVirtualJoint("odom_combined", "base_link", "planar", "base_joint");
192  builder.addJointProperty("base_joint", "motion_model", "diff_drive");
193  builder.addGroup({}, { "base_joint" }, "base");
194  ASSERT_TRUE(builder.isValid());
195 
196  auto robot_model = builder.build();
197  ompl_interface::ModelBasedStateSpaceSpecification spec(robot_model, "base");
199  ss.setPlanningVolume(-2, 2, -2, 2, -2, 2);
200  ss.setup();
201 
202  bool passed = false;
203  try
204  {
205  ss.sanityChecks();
206  passed = true;
207  }
208  catch (ompl::Exception& ex)
209  {
210  RCLCPP_ERROR(LOGGER, "Sanity checks did not pass: %s", ex.what());
211  }
212  EXPECT_TRUE(passed);
213 }
214 
215 int main(int argc, char** argv)
216 {
217  testing::InitGoogleTest(&argc, argv);
218  return RUN_ALL_TESTS();
219 }
moveit::core::RobotModelPtr robot_model_
void TearDown() override
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.
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
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
Easily build different robot models for testing. Essentially a programmer-friendly light wrapper arou...
void addJointProperty(const std::string &joint_name, const std::string &property_name, const std::string &value)
Adds a new joint property.
bool isValid()
Returns true if the building process so far has been valid.
void addGroup(const std::vector< std::string > &links, const std::vector< std::string > &joints, const std::string &name)
Adds a new group using a list of links and a list of joints.
moveit::core::RobotModelPtr build()
Builds and returns the robot model added to the builder.
void addVirtualJoint(const std::string &parent_frame, const std::string &child_link, const std::string &type, const std::string &name="")
Adds a virtual joint to the SRDF.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the ro...
Definition: robot_state.h:1339
const RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
Definition: robot_state.h:104
double distance(const RobotState &other) const
Return the sum of joint distances to "other" state. An L1 norm. Only considers active joints.
Definition: robot_state.h:1457
void setToRandomPositions()
Set all joints to random values. Values will be within default bounds.
virtual void copyJointToOMPLState(ompl::base::State *state, const moveit::core::RobotState &robot_state, const moveit::core::JointModel *joint_model, int ompl_state_joint_index) const
Copy a single joint's values (which might have multiple variables) from a MoveIt robot_state to an OM...
const std::string & getJointModelGroupName() const
ompl::base::State * allocState() const override
virtual void setPlanningVolume(double minX, double maxX, double minY, double maxY, double minZ, double maxZ)
Set the planning volume for the possible SE2 and/or SE3 components of the state space.
virtual void copyToRobotState(moveit::core::RobotState &rstate, const ompl::base::State *state) const
Copy the data from an OMPL state to a set of joint states.
void freeState(ompl::base::State *state) const override
virtual void copyToOMPLState(ompl::base::State *state, const moveit::core::RobotState &rstate) const
Copy the data from a set of joint states to an OMPL state.
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)
Loads a robot from moveit_resources.
int main(int argc, char **argv)
TEST_F(LoadPlanningModelsPr2, StateSpace)
constexpr double EPSILON
TEST(TestDiffDrive, TestStateSpace)