moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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>
48#include <gtest/gtest.h>
49#include <fstream>
50
51rclcpp::Logger getLogger()
52{
53 return moveit::getLogger("moveit.planners.ompl.test_state_space");
54}
55
56constexpr double EPSILON = std::numeric_limits<double>::epsilon();
57
58class LoadPlanningModelsPr2 : public testing::Test
59{
60protected:
61 void SetUp() override
62 {
64 };
65
66 void TearDown() override
67 {
68 }
69
70protected:
71 moveit::core::RobotModelPtr robot_model_;
72};
73
75{
76 ompl_interface::ModelBasedStateSpaceSpecification spec(robot_model_, "whole_body");
78 ss.setPlanningVolume(-1, 1, -1, 1, -1, 1);
79 ss.setup();
80 std::ofstream fout("ompl_interface_test_state_space_diagram1.dot");
81 ss.diagram(fout);
82 bool passed = false;
83 try
84 {
85 ss.sanityChecks();
86 passed = true;
87 }
88 catch (ompl::Exception& ex)
89 {
90 RCLCPP_ERROR(getLogger(), "Sanity checks did not pass: %s", ex.what());
91 }
92 EXPECT_TRUE(passed);
93}
94
96{
97 ompl_interface::ModelBasedStateSpaceSpecification spec1(robot_model_, "right_arm");
99 ss1.setup();
100
101 ompl_interface::ModelBasedStateSpaceSpecification spec2(robot_model_, "left_arm");
103 ss2.setup();
104
105 ompl_interface::ModelBasedStateSpaceSpecification spec3(robot_model_, "whole_body");
107 ss3.setup();
108
109 ompl_interface::ModelBasedStateSpaceSpecification spec4(robot_model_, "arms");
111 ss4.setup();
112
113 std::ofstream fout("ompl_interface_test_state_space_diagram2.dot");
114 ompl::base::StateSpace::Diagram(fout);
115}
116
118{
119 ompl_interface::ModelBasedStateSpaceSpecification spec(robot_model_, "right_arm");
120 ompl_interface::JointModelStateSpace joint_model_state_space(spec);
121 joint_model_state_space.setPlanningVolume(-1, 1, -1, 1, -1, 1);
122 joint_model_state_space.setup();
123 std::ofstream fout("ompl_interface_test_state_space_diagram1.dot");
124 joint_model_state_space.diagram(fout);
125 bool passed = false;
126 try
127 {
128 joint_model_state_space.sanityChecks();
129 passed = true;
130 }
131 catch (ompl::Exception& ex)
132 {
133 RCLCPP_ERROR(getLogger(), "Sanity checks did not pass: %s", ex.what());
134 }
135 EXPECT_TRUE(passed);
136
137 moveit::core::RobotState robot_state(robot_model_);
138 robot_state.setToRandomPositions();
139 EXPECT_TRUE(robot_state.distance(robot_state) < EPSILON);
140 ompl::base::State* state = joint_model_state_space.allocState();
141 for (int i = 0; i < 10; ++i)
142 {
143 moveit::core::RobotState robot_state2(robot_state);
144 EXPECT_TRUE(robot_state.distance(robot_state2) < EPSILON);
145 joint_model_state_space.copyToOMPLState(state, robot_state);
146 robot_state.setToRandomPositions(
147 robot_state.getRobotModel()->getJointModelGroup(joint_model_state_space.getJointModelGroupName()));
148 std::cout << (robot_state.getGlobalLinkTransform("r_wrist_roll_link").translation() -
149 robot_state2.getGlobalLinkTransform("r_wrist_roll_link").translation())
150 << '\n';
151 EXPECT_TRUE(robot_state.distance(robot_state2) > EPSILON);
152 joint_model_state_space.copyToRobotState(robot_state, state);
153 std::cout << (robot_state.getGlobalLinkTransform("r_wrist_roll_link").translation() -
154 robot_state2.getGlobalLinkTransform("r_wrist_roll_link").translation())
155 << '\n';
156 EXPECT_TRUE(robot_state.distance(robot_state2) < EPSILON);
157 }
158
159 // repeat the above test with a different method to copy the state to OMPL
160 for (int i = 0; i < 10; ++i)
161 {
162 // create two equal states
163 moveit::core::RobotState robot_state2(robot_state);
164 EXPECT_LT(robot_state.distance(robot_state2), EPSILON);
165
166 // copy the first state to OMPL as backup (this is where the 'different' method comes into play)
167 const moveit::core::JointModelGroup* joint_model_group =
168 robot_state.getRobotModel()->getJointModelGroup(joint_model_state_space.getJointModelGroupName());
169 std::vector<std::string> joint_model_names = joint_model_group->getActiveJointModelNames();
170 for (std::size_t joint_index = 0; joint_index < joint_model_group->getVariableCount(); ++joint_index)
171 {
172 const moveit::core::JointModel* joint_model = joint_model_group->getJointModel(joint_model_names[joint_index]);
173 EXPECT_NE(joint_model, nullptr);
174 joint_model_state_space.copyJointToOMPLState(state, robot_state, joint_model, joint_index);
175 }
176
177 // and change the joint values of the moveit state, so it is different that robot_state2
178 robot_state.setToRandomPositions(
179 robot_state.getRobotModel()->getJointModelGroup(joint_model_state_space.getJointModelGroupName()));
180 EXPECT_GT(robot_state.distance(robot_state2), EPSILON);
181
182 // copy the backup values in the OMPL state back to the first state,
183 // and check if it is still equal to the second
184 joint_model_state_space.copyToRobotState(robot_state, state);
185 EXPECT_LT(robot_state.distance(robot_state2), EPSILON);
186 }
187
188 joint_model_state_space.freeState(state);
189}
190
191// Run the OMPL sanity checks on the diff drive model
192TEST(TestDiffDrive, TestStateSpace)
193{
194 moveit::core::RobotModelBuilder builder("mobile_base", "base_link");
195 builder.addVirtualJoint("odom_combined", "base_link", "planar", "base_joint");
196 builder.addJointProperty("base_joint", "motion_model", "diff_drive");
197 builder.addGroup({}, { "base_joint" }, "base");
198 ASSERT_TRUE(builder.isValid());
199
200 auto robot_model = builder.build();
203 ss.setPlanningVolume(-2, 2, -2, 2, -2, 2);
204 ss.setup();
205
206 bool passed = false;
207 try
208 {
209 ss.sanityChecks();
210 passed = true;
211 }
212 catch (ompl::Exception& ex)
213 {
214 RCLCPP_ERROR(getLogger(), "Sanity checks did not pass: %s", ex.what());
215 }
216 EXPECT_TRUE(passed);
217}
218
219int main(int argc, char** argv)
220{
221 testing::InitGoogleTest(&argc, argv);
222 return RUN_ALL_TESTS();
223}
moveit::core::RobotModelPtr robot_model_
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.
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
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 RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
double distance(const RobotState &other) const
Return the sum of joint distances to "other" state. An L1 norm. Only considers active joints.
void setToRandomPositions()
Set all joints to random values. Values will be within default bounds.
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...
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...
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.
const std::string & getJointModelGroupName() const
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 &package_name, const std::string &urdf_relative_path, const std::string &srdf_relative_path)
Loads a robot model given a URDF and SRDF file in a package.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79
int main(int argc, char **argv)
TEST_F(LoadPlanningModelsPr2, StateSpace)
rclcpp::Logger getLogger()
constexpr double EPSILON
TEST(TestDiffDrive, TestStateSpace)