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);
101 const Eigen::Vector3d& offset_base_footprint =
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);
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);
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);
118 std::vector<double> pr2_aabb;
120 ASSERT_EQ(pr2_aabb.size(), 6u);
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);
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);
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)
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';
158 rclcpp::init(argc, argv);
159 auto node = rclcpp::Node::make_shared(
"visualize_pr2");
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);
169 auto msg = std::make_shared<visualization_msgs::msg::Marker>();
171 msg->header.frame_id = pr2_state.
getRobotModel()->getRootLinkName();
172 msg->type = visualization_msgs::msg::Marker::CUBE;
174 msg->lifetime.sec = 3000;
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);
189 std::vector<const moveit::core::LinkModel*> links = pr2_state.
getRobotModel()->getLinkModelsWithCollisionGeometry();
190 for (std::size_t i = 0; i < links.size(); ++i)
193 const Eigen::Vector3d& extents = links[i]->getShapeExtentsAtOrigin();
194 transform.translate(links[i]->getCenteredBoundingBoxOffset());
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;
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);
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];
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);
231 std::vector<const moveit::core::AttachedBody*> attached_bodies;
233 for (std::vector<const moveit::core::AttachedBody*>::const_iterator it = attached_bodies.begin();
234 it != attached_bodies.end(); ++it)
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)
240 Eigen::Vector3d extents = shapes::computeShapeExtents(
shapes[i].get());
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;
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);
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];
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);
322 geometry_msgs::msg::Pose origin;
323 origin.position.x = 0;
324 origin.position.y = 0;
325 origin.position.z = 1.0;
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;
334 origin.position.x = 4.0;
335 origin.position.y = 0;
336 origin.position.z = 1.0;
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);
344 builder.
addVirtualJoint(
"odom_combined",
"base_footprint",
"planar",
"world_joint");
345 builder.
addGroup({}, {
"world_joint" },
"base");
347 ASSERT_TRUE(builder.
isValid());
364 std::vector<double> complex_aabb;
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);