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);
96 const Eigen::Vector3d& offset_base_footprint =
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);
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);
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);
113 std::vector<double> pr2_aabb;
115 ASSERT_EQ(pr2_aabb.size(), 6u);
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);
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);
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)
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';
153 rclcpp::init(argc, argv);
154 auto node = rclcpp::Node::make_shared(
"visualize_pr2");
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);
164 auto msg = std::make_shared<visualization_msgs::msg::Marker>();
166 msg->header.frame_id = pr2_state.
getRobotModel()->getRootLinkName();
167 msg->type = visualization_msgs::msg::Marker::CUBE;
169 msg->lifetime.sec = 3000;
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);
184 std::vector<const moveit::core::LinkModel*> links = pr2_state.
getRobotModel()->getLinkModelsWithCollisionGeometry();
185 for (std::size_t i = 0; i < links.size(); ++i)
188 const Eigen::Vector3d& extents = links[i]->getShapeExtentsAtOrigin();
189 transform.translate(links[i]->getCenteredBoundingBoxOffset());
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;
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);
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];
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);
226 std::vector<const moveit::core::AttachedBody*> attached_bodies;
228 for (std::vector<const moveit::core::AttachedBody*>::const_iterator it = attached_bodies.begin();
229 it != attached_bodies.end(); ++it)
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)
235 Eigen::Vector3d extents = shapes::computeShapeExtents(
shapes[i].get());
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;
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);
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];
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);
317 geometry_msgs::msg::Pose origin;
318 origin.position.x = 0;
319 origin.position.y = 0;
320 origin.position.z = 1.0;
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;
329 origin.position.x = 4.0;
330 origin.position.y = 0;
331 origin.position.z = 1.0;
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);
339 builder.
addVirtualJoint(
"odom_combined",
"base_footprint",
"planar",
"world_joint");
340 builder.
addGroup({}, {
"world_joint" },
"base");
342 ASSERT_TRUE(builder.
isValid());
359 std::vector<double> complex_aabb;
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);