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