moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
test_aabb.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, 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 the 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: Martin Pecka */
36
40#include <urdf_parser/urdf_parser.h>
41#include <fstream>
42#include <string>
43#include <gtest/gtest.h>
44#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
45#include <tf2/LinearMath/Vector3.h>
47
48// To visualize bbox of the PR2, set this to 1.
49#ifndef VISUALIZE_PR2_RVIZ
50#define VISUALIZE_PR2_RVIZ 0
51#endif
52
53#if VISUALIZE_PR2_RVIZ
54#include <rclcpp/rclcpp.hpp>
55#include <visualization_msgs/msg/marker.hpp>
56#include <geometric_shapes/shape_operations.h>
57#endif
58
59class TestAABB : public testing::Test
60{
61protected:
62 void SetUp() override{};
63
64 moveit::core::RobotState loadModel(const std::string& robot_name)
65 {
66 moveit::core::RobotModelPtr model = moveit::core::loadTestingRobotModel(robot_name);
67 return loadModel(model);
68 }
69
70 moveit::core::RobotState loadModel(const moveit::core::RobotModelPtr& model)
71 {
73 robot_state.setToDefaultValues();
74 robot_state.update(true);
75
76 return robot_state;
77 }
78
79 void TearDown() override
80 {
81 }
82};
83
85{
86 // Contains a link with mesh geometry that is not centered
87
88 moveit::core::RobotState pr2_state = this->loadModel("pr2");
89
90 const Eigen::Vector3d& extents_base_footprint = pr2_state.getLinkModel("base_footprint")->getShapeExtentsAtOrigin();
91 // values taken from moveit_resources_pr2_description/urdf/robot.xml
92 EXPECT_NEAR(extents_base_footprint[0], 0.001, 1e-4);
93 EXPECT_NEAR(extents_base_footprint[1], 0.001, 1e-4);
94 EXPECT_NEAR(extents_base_footprint[2], 0.001, 1e-4);
95
96 const Eigen::Vector3d& offset_base_footprint =
97 pr2_state.getLinkModel("base_footprint")->getCenteredBoundingBoxOffset();
98 EXPECT_NEAR(offset_base_footprint[0], 0.0, 1e-4);
99 EXPECT_NEAR(offset_base_footprint[1], 0.0, 1e-4);
100 EXPECT_NEAR(offset_base_footprint[2], 0.071, 1e-4);
101
102 const Eigen::Vector3d& extents_base_link = pr2_state.getLinkModel("base_link")->getShapeExtentsAtOrigin();
103 // values computed from moveit_resources_pr2_description/urdf/meshes/base_v0/base_L.stl in e.g. Meshlab
104 EXPECT_NEAR(extents_base_link[0], 0.668242, 1e-4);
105 EXPECT_NEAR(extents_base_link[1], 0.668242, 1e-4);
106 EXPECT_NEAR(extents_base_link[2], 0.656175, 1e-4);
107
108 const Eigen::Vector3d& offset_base_link = pr2_state.getLinkModel("base_link")->getCenteredBoundingBoxOffset();
109 EXPECT_NEAR(offset_base_link[0], 0.0, 1e-4);
110 EXPECT_NEAR(offset_base_link[1], 0.0, 1e-4);
111 EXPECT_NEAR(offset_base_link[2], 0.656175 / 2, 1e-4); // The 3D mesh isn't centered, but is whole above z axis
112
113 std::vector<double> pr2_aabb;
114 pr2_state.computeAABB(pr2_aabb);
115 ASSERT_EQ(pr2_aabb.size(), 6u);
116
117 EXPECT_NEAR(pr2_aabb[0], -0.3376, 1e-4);
118 EXPECT_NEAR(pr2_aabb[1], 0.6499, 1e-4);
119 EXPECT_NEAR(pr2_aabb[2], -0.6682 / 2, 1e-4);
120 EXPECT_NEAR(pr2_aabb[3], 0.6682 / 2, 1e-4);
121 EXPECT_NEAR(pr2_aabb[4], 0.0044, 1e-4);
122 EXPECT_NEAR(pr2_aabb[5], 1.6328, 1e-4);
123
124 // Test a specific link known to have some global rotation in the default pose
125
126 const moveit::core::LinkModel* link = pr2_state.getLinkModel("l_forearm_link");
127 Eigen::Isometry3d transform = pr2_state.getGlobalLinkTransform(link); // intentional copy, we will translate
128 const Eigen::Vector3d& extents = link->getShapeExtentsAtOrigin();
129 transform.translate(link->getCenteredBoundingBoxOffset());
131 aabb.extendWithTransformedBox(transform, extents);
132
133 EXPECT_NEAR(aabb.center()[0], 0.5394, 1e-4);
134 EXPECT_NEAR(aabb.center()[1], 0.1880, 1e-4);
135 EXPECT_NEAR(aabb.center()[2], 1.1665, 1e-4);
136 EXPECT_NEAR(aabb.sizes()[0], 0.2209, 1e-4);
137 EXPECT_NEAR(aabb.sizes()[1], 0.1201, 1e-4);
138 EXPECT_NEAR(aabb.sizes()[2], 0.2901, 1e-4);
139
140#if VISUALIZE_PR2_RVIZ
141 std::cout << "Overall bounding box of PR2:" << '\n';
142 std::string dims[] = { "x", "y", "z" };
143 for (std::size_t i = 0; i < 3; ++i)
144 {
145 double dim = pr2_aabb[2 * i + 1] - pr2_aabb[2 * i];
146 double center = dim / 2;
147 std::cout << dims[i] << ": size=" << dim << ", offset=" << (pr2_aabb[2 * i + 1] - center) << '\n';
148 }
149
150 // Initialize a ROS publisher
151 char* argv[0];
152 int argc = 0;
153 rclcpp::init(argc, argv);
154 auto node = rclcpp::Node::make_shared("visualize_pr2");
155 auto pub_aabb =
156 node->create_publisher<visualization_msgs::msg::Marker>("/visualization_aabb", rmw_qos_profile_default);
157 auto pub_obb = node->create_publisher<visualization_msgs::msg::Marker>("/visualization_obb", rmw_qos_profile_default);
158 rclcpp::Rate loop_rate(10);
159
160 // Wait for the publishers to establish connections
161 sleep(5);
162
163 // Prepare the ROS message we will reuse throughout the rest of the function.
164 auto msg = std::make_shared<visualization_msgs::msg::Marker>();
165
166 msg->header.frame_id = pr2_state.getRobotModel()->getRootLinkName();
167 msg->type = visualization_msgs::msg::Marker::CUBE;
168 msg->color.a = 0.5;
169 msg->lifetime.sec = 3000;
170
171 // Publish the AABB of the whole model
172 msg->ns = "pr2";
173 msg->pose.position.x = (pr2_aabb[0] + pr2_aabb[1]) / 2;
174 msg->pose.position.y = (pr2_aabb[2] + pr2_aabb[3]) / 2;
175 msg->pose.position.z = (pr2_aabb[4] + pr2_aabb[5]) / 2;
176 msg->pose.orientation.x = msg->pose.orientation.y = msg->pose.orientation.z = 0;
177 msg->pose.orientation.w = 1;
178 msg->scale.x = pr2_aabb[1] - pr2_aabb[0];
179 msg->scale.y = pr2_aabb[3] - pr2_aabb[2];
180 msg->scale.z = pr2_aabb[5] - pr2_aabb[4];
181 pub_aabb->publish(msg);
182
183 // Publish BBs for all links
184 std::vector<const moveit::core::LinkModel*> links = pr2_state.getRobotModel()->getLinkModelsWithCollisionGeometry();
185 for (std::size_t i = 0; i < links.size(); ++i)
186 {
187 Eigen::Isometry3d transform = pr2_state.getGlobalLinkTransform(links[i]); // intentional copy, we will translate
188 const Eigen::Vector3d& extents = links[i]->getShapeExtentsAtOrigin();
189 transform.translate(links[i]->getCenteredBoundingBoxOffset());
191 aabb.extendWithTransformedBox(transform, extents);
192
193 // Publish AABB
194 msg->ns = links[i]->getName();
195 msg->pose.position.x = transform.translation()[0];
196 msg->pose.position.y = transform.translation()[1];
197 msg->pose.position.z = transform.translation()[2];
198 msg->pose.orientation.x = msg->pose.orientation.y = msg->pose.orientation.z = 0;
199 msg->pose.orientation.w = 1;
200 msg->color.r = 1;
201 msg->color.b = 0;
202 msg->scale.x = aabb.sizes()[0];
203 msg->scale.y = aabb.sizes()[1];
204 msg->scale.z = aabb.sizes()[2];
205 pub_aabb->publish(msg);
206
207 // Publish OBB (oriented BB)
208 msg->ns += "-obb";
209 msg->pose.position.x = transform.translation()[0];
210 msg->pose.position.y = transform.translation()[1];
211 msg->pose.position.z = transform.translation()[2];
212 msg->scale.x = extents[0];
213 msg->scale.y = extents[1];
214 msg->scale.z = extents[2];
215 msg->color.r = 0;
216 msg->color.b = 1;
217 Eigen::Quaterniond q(transform.linear());
218 msg->pose.orientation.x = q.x();
219 msg->pose.orientation.y = q.y();
220 msg->pose.orientation.z = q.z();
221 msg->pose.orientation.w = q.w();
222 pub_obb->publish(msg);
223 }
224
225 // Publish BBs for all attached bodies
226 std::vector<const moveit::core::AttachedBody*> attached_bodies;
227 pr2_state.getAttachedBodies(attached_bodies);
228 for (std::vector<const moveit::core::AttachedBody*>::const_iterator it = attached_bodies.begin();
229 it != attached_bodies.end(); ++it)
230 {
231 const EigenSTL::vector_Isometry3d& transforms = (*it)->getGlobalCollisionBodyTransforms();
232 const std::vector<shapes::ShapeConstPtr>& shapes = (*it)->getShapes();
233 for (std::size_t i = 0; i < transforms.size(); ++i)
234 {
235 Eigen::Vector3d extents = shapes::computeShapeExtents(shapes[i].get());
237 aabb.extendWithTransformedBox(transforms[i], extents);
238
239 // Publish AABB
240 msg->ns = (*it)->getName() + std::to_string(i);
241 msg->pose.position.x = transforms[i].translation()[0];
242 msg->pose.position.y = transforms[i].translation()[1];
243 msg->pose.position.z = transforms[i].translation()[2];
244 msg->pose.orientation.x = msg->pose.orientation.y = msg->pose.orientation.z = 0;
245 msg->pose.orientation.w = 1;
246 msg->color.r = 1;
247 msg->color.b = 0;
248 msg->scale.x = aabb.sizes()[0];
249 msg->scale.y = aabb.sizes()[1];
250 msg->scale.z = aabb.sizes()[2];
251 pub_aabb->publish(msg);
252
253 // Publish OBB (oriented BB)
254 msg->ns += "-obb";
255 msg->pose.position.x = transforms[i].translation()[0];
256 msg->pose.position.y = transforms[i].translation()[1];
257 msg->pose.position.z = transforms[i].translation()[2];
258 msg->scale.x = extents[0];
259 msg->scale.y = extents[1];
260 msg->scale.z = extents[2];
261 msg->color.r = 0;
262 msg->color.b = 1;
263 Eigen::Quaterniond q(transforms[i].linear());
264 msg->pose.orientation.x = q.x();
265 msg->pose.orientation.y = q.y();
266 msg->pose.orientation.z = q.z();
267 msg->pose.orientation.w = q.w();
268 pub_obb->publish(msg);
269 }
270 }
271#endif
272}
273
274TEST_F(TestAABB, TestSimple)
275{
276 // Contains a link with simple geometry and an offset in the collision link
277 moveit::core::RobotModelBuilder builder("simple", "base_footprint");
278 geometry_msgs::msg::Pose origin;
279 origin.position.x = 0;
280 origin.position.y = 0;
281 origin.position.z = 0.051;
282 origin.orientation.w = 1.0;
283 builder.addChain("base_footprint->base_link", "fixed", { origin });
284
285 origin.position.x = 0;
286 origin.position.y = 0;
287 origin.position.z = 0;
288 builder.addCollisionMesh("base_link", "package://moveit_resources_pr2_description/urdf/meshes/base_v0/base_L.stl",
289 origin);
290
291 origin.position.x = 0;
292 origin.position.y = 0;
293 origin.position.z = 0.071;
294 builder.addCollisionBox("base_footprint", { 0.001, 0.001, 0.001 }, origin);
295
296 builder.addVirtualJoint("odom_combined", "base_footprint", "planar", "world_joint");
297 builder.addGroup({}, { "world_joint" }, "base");
298
299 ASSERT_TRUE(builder.isValid());
300 moveit::core::RobotState simple_state = loadModel(builder.build());
301 std::vector<double> simple_aabb;
302 simple_state.computeAABB(simple_aabb);
303
304 ASSERT_EQ(simple_aabb.size(), 6u);
305 EXPECT_NEAR(simple_aabb[0], -0.6682 / 2, 1e-4);
306 EXPECT_NEAR(simple_aabb[1], 0.6682 / 2, 1e-4);
307 EXPECT_NEAR(simple_aabb[2], -0.6682 / 2, 1e-4);
308 EXPECT_NEAR(simple_aabb[3], 0.6682 / 2, 1e-4);
309 EXPECT_NEAR(simple_aabb[4], 0.0510, 1e-4);
310 EXPECT_NEAR(simple_aabb[5], 0.7071, 1e-4);
311}
312
313TEST_F(TestAABB, TestComplex)
314{
315 // Contains a link with simple geometry and an offset and rotation in the collision link
316 moveit::core::RobotModelBuilder builder("complex", "base_footprint");
317 geometry_msgs::msg::Pose origin;
318 origin.position.x = 0;
319 origin.position.y = 0;
320 origin.position.z = 1.0;
321 tf2::Quaternion q;
322 q.setRPY(0, 0, 1.5708);
323 origin.orientation = tf2::toMsg(q);
324 builder.addChain("base_footprint->base_link", "fixed", { origin });
325 origin.position.x = 5.0;
326 origin.position.y = 0;
327 origin.position.z = 1.0;
328 builder.addCollisionBox("base_link", { 1.0, 0.1, 0.1 }, origin);
329 origin.position.x = 4.0;
330 origin.position.y = 0;
331 origin.position.z = 1.0;
332 builder.addCollisionBox("base_link", { 1.0, 0.1, 0.1 }, origin);
333 origin.position.x = -5.0;
334 origin.position.y = 0;
335 origin.position.z = -1.0;
336 q.setRPY(0, 1.5708, 0);
337 origin.orientation = tf2::toMsg(q);
338 builder.addCollisionBox("base_footprint", { 0.1, 1.0, 0.1 }, origin);
339 builder.addVirtualJoint("odom_combined", "base_footprint", "planar", "world_joint");
340 builder.addGroup({}, { "world_joint" }, "base");
341
342 ASSERT_TRUE(builder.isValid());
343 moveit::core::RobotState complex_state = this->loadModel(builder.build());
344
345 EXPECT_NEAR(complex_state.getLinkModel("base_footprint")->getShapeExtentsAtOrigin()[0], 0.1, 1e-4);
346 EXPECT_NEAR(complex_state.getLinkModel("base_footprint")->getShapeExtentsAtOrigin()[1], 1.0, 1e-4);
347 EXPECT_NEAR(complex_state.getLinkModel("base_footprint")->getShapeExtentsAtOrigin()[2], 0.1, 1e-4);
348 EXPECT_NEAR(complex_state.getLinkModel("base_footprint")->getCenteredBoundingBoxOffset()[0], -5.0, 1e-4);
349 EXPECT_NEAR(complex_state.getLinkModel("base_footprint")->getCenteredBoundingBoxOffset()[1], 0.0, 1e-4);
350 EXPECT_NEAR(complex_state.getLinkModel("base_footprint")->getCenteredBoundingBoxOffset()[2], -1.0, 1e-4);
351
352 EXPECT_NEAR(complex_state.getLinkModel("base_link")->getShapeExtentsAtOrigin()[0], 1.1, 1e-4);
353 EXPECT_NEAR(complex_state.getLinkModel("base_link")->getShapeExtentsAtOrigin()[1], 1.0, 1e-4);
354 EXPECT_NEAR(complex_state.getLinkModel("base_link")->getShapeExtentsAtOrigin()[2], 0.1, 1e-4);
355 EXPECT_NEAR(complex_state.getLinkModel("base_link")->getCenteredBoundingBoxOffset()[0], 4.5, 1e-4);
356 EXPECT_NEAR(complex_state.getLinkModel("base_link")->getCenteredBoundingBoxOffset()[1], 0.0, 1e-4);
357 EXPECT_NEAR(complex_state.getLinkModel("base_link")->getCenteredBoundingBoxOffset()[2], 1.0, 1e-4);
358
359 std::vector<double> complex_aabb;
360 complex_state.computeAABB(complex_aabb);
361
362 ASSERT_EQ(complex_aabb.size(), 6u);
363 EXPECT_NEAR(complex_aabb[0], -5.05, 1e-4);
364 EXPECT_NEAR(complex_aabb[1], 0.5, 1e-4);
365 EXPECT_NEAR(complex_aabb[2], -0.5, 1e-4);
366 EXPECT_NEAR(complex_aabb[3], 5.05, 1e-4);
367 EXPECT_NEAR(complex_aabb[4], -1.05, 1e-4);
368 EXPECT_NEAR(complex_aabb[5], 2.05, 1e-4);
369}
370
371int main(int argc, char** argv)
372{
373 testing::InitGoogleTest(&argc, argv);
374 return RUN_ALL_TESTS();
375}
moveit::core::RobotState loadModel(const moveit::core::RobotModelPtr &model)
Definition test_aabb.cpp:70
void SetUp() override
Definition test_aabb.cpp:62
void TearDown() override
Definition test_aabb.cpp:79
moveit::core::RobotState loadModel(const std::string &robot_name)
Definition test_aabb.cpp:64
Represents an axis-aligned bounding box.
Definition aabb.h:47
void extendWithTransformedBox(const Eigen::Isometry3d &transform, const Eigen::Vector3d &box)
Extend with a box transformed by the given transform.
Definition aabb.cpp:40
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition link_model.h:72
const Eigen::Vector3d & getCenteredBoundingBoxOffset() const
Get the offset of the center of the bounding box of this link when the link is positioned at origin.
Definition link_model.h:192
const Eigen::Vector3d & getShapeExtentsAtOrigin() const
Get the extents of the link's geometry (dimensions of axis-aligned bounding box around all shapes tha...
Definition link_model.h:186
Easily build different robot models for testing. Essentially a programmer-friendly light wrapper arou...
void addChain(const std::string &section, const std::string &type, const std::vector< geometry_msgs::msg::Pose > &joint_origins={}, urdf::Vector3 joint_axis=urdf::Vector3(1.0, 0.0, 0.0))
Adds a chain of links and joints to the builder. The joint names are generated automatically as "<par...
void addCollisionBox(const std::string &link_name, const std::vector< double > &dims, geometry_msgs::msg::Pose origin)
Adds a collision box to a specific link.
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.
void addCollisionMesh(const std::string &link_name, const std::string &filename, geometry_msgs::msg::Pose origin)
Adds a collision mesh to a specific link.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
void getAttachedBodies(std::vector< const AttachedBody * > &attached_bodies) const
Get all bodies attached to the model corresponding to this state.
void computeAABB(std::vector< double > &aabb) const
Compute an axis-aligned bounding box that contains the current state. The format for aabb is (minx,...
const LinkModel * getLinkModel(const std::string &link) const
Get the model of a particular link.
const RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
void update(bool force=false)
Update all transforms.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within 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...
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.
Definition world.h:49
int main(int argc, char **argv)
TEST_F(TestAABB, TestPR2)
Definition test_aabb.cpp:84