40 #include <urdf_parser/urdf_parser.h>
42 #include <boost/filesystem.hpp>
43 #include <gtest/gtest.h>
49 #ifndef VISUALIZE_PR2_RVIZ
50 #define VISUALIZE_PR2_RVIZ 0
53 #if VISUALIZE_PR2_RVIZ
55 #include <visualization_msgs/Marker.h>
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);
100 EXPECT_NEAR(offset_base_footprint[2], 0.071, 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);
140 #if VISUALIZE_PR2_RVIZ
141 std::cout <<
"Overall bounding box of PR2:" << std::endl;
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) << std::endl;
162 visualization_msgs::Marker msg;
163 msg.header.frame_id = pr2_state.
getRobotModel()->getRootLinkName();
164 msg.type = visualization_msgs::Marker::CUBE;
166 msg.lifetime.sec = 3000;
170 msg.pose.position.x = (pr2_aabb[0] + pr2_aabb[1]) / 2;
171 msg.pose.position.y = (pr2_aabb[2] + pr2_aabb[3]) / 2;
172 msg.pose.position.z = (pr2_aabb[4] + pr2_aabb[5]) / 2;
173 msg.pose.orientation.x = msg.pose.orientation.y = msg.pose.orientation.z = 0;
174 msg.pose.orientation.w = 1;
175 msg.scale.x = pr2_aabb[1] - pr2_aabb[0];
176 msg.scale.y = pr2_aabb[3] - pr2_aabb[2];
177 msg.scale.z = pr2_aabb[5] - pr2_aabb[4];
181 std::vector<const moveit::core::LinkModel*> links = pr2_state.
getRobotModel()->getLinkModelsWithCollisionGeometry();
182 for (std::size_t i = 0; i < links.size(); ++i)
186 transform.translate(links[i]->getCenteredBoundingBoxOffset());
191 msg.ns = links[i]->getName();
192 msg.pose.position.x =
transform.translation()[0];
193 msg.pose.position.y =
transform.translation()[1];
194 msg.pose.position.z =
transform.translation()[2];
195 msg.pose.orientation.x = msg.pose.orientation.y = msg.pose.orientation.z = 0;
196 msg.pose.orientation.w = 1;
199 msg.scale.x =
aabb.sizes()[0];
200 msg.scale.y =
aabb.sizes()[1];
201 msg.scale.z =
aabb.sizes()[2];
206 msg.pose.position.x =
transform.translation()[0];
207 msg.pose.position.y =
transform.translation()[1];
208 msg.pose.position.z =
transform.translation()[2];
214 Eigen::Quaterniond q(
transform.linear());
215 msg.pose.orientation.x = q.x();
216 msg.pose.orientation.y = q.y();
217 msg.pose.orientation.z = q.z();
218 msg.pose.orientation.w = q.w();
219 pub_obb.publish(msg);
223 std::vector<const moveit::core::AttachedBody*> attached_bodies;
225 for (std::vector<const moveit::core::AttachedBody*>::const_iterator it = attached_bodies.begin();
226 it != attached_bodies.end(); ++it)
229 const std::vector<shapes::ShapeConstPtr>&
shapes = (*it)->getShapes();
230 for (std::size_t i = 0; i < transforms.size(); ++i)
234 aabb.extendWithTransformedBox(transforms[i],
extents);
237 msg.ns = (*it)->getName() + boost::lexical_cast<std::string>(i);
238 msg.pose.position.x = transforms[i].translation()[0];
239 msg.pose.position.y = transforms[i].translation()[1];
240 msg.pose.position.z = transforms[i].translation()[2];
241 msg.pose.orientation.x = msg.pose.orientation.y = msg.pose.orientation.z = 0;
242 msg.pose.orientation.w = 1;
245 msg.scale.x =
aabb.sizes()[0];
246 msg.scale.y =
aabb.sizes()[1];
247 msg.scale.z =
aabb.sizes()[2];
252 msg.pose.position.x = transforms[i].translation()[0];
253 msg.pose.position.y = transforms[i].translation()[1];
254 msg.pose.position.z = transforms[i].translation()[2];
260 Eigen::Quaterniond q(transforms[i].linear());
261 msg.pose.orientation.x = q.x();
262 msg.pose.orientation.y = q.y();
263 msg.pose.orientation.z = q.z();
264 msg.pose.orientation.w = q.w();
265 pub_obb.publish(msg);
275 geometry_msgs::Pose origin;
276 tf2::toMsg(tf2::Vector3(0, 0, 0.051), origin.position);
277 origin.orientation.w = 1.0;
278 builder.
addChain(
"base_footprint->base_link",
"fixed", { origin });
280 tf2::toMsg(tf2::Vector3(0, 0, 0), origin.position);
281 builder.
addCollisionMesh(
"base_link",
"package://moveit_resources_pr2_description/urdf/meshes/base_v0/base_L.stl",
284 tf2::toMsg(tf2::Vector3(0, 0, 0.071), origin.position);
285 builder.
addCollisionBox(
"base_footprint", { 0.001, 0.001, 0.001 }, origin);
287 builder.
addVirtualJoint(
"odom_combined",
"base_footprint",
"planar",
"world_joint");
288 builder.
addGroup({}, {
"world_joint" },
"base");
290 ASSERT_TRUE(builder.
isValid());
292 std::vector<double> simple_aabb;
295 ASSERT_EQ(simple_aabb.size(), 6u);
308 geometry_msgs::Pose origin;
309 tf2::toMsg(tf2::Vector3(0, 0, 1.0), origin.position);
313 builder.
addChain(
"base_footprint->base_link",
"fixed", { origin });
314 tf2::toMsg(tf2::Vector3(5.0, 0, 1.0), origin.position);
316 tf2::toMsg(tf2::Vector3(4.0, 0, 1.0), origin.position);
318 tf2::toMsg(tf2::Vector3(-5.0, 0.0, -1.0), origin.position);
322 builder.
addVirtualJoint(
"odom_combined",
"base_footprint",
"planar",
"world_joint");
323 builder.
addGroup({}, {
"world_joint" },
"base");
325 ASSERT_TRUE(builder.
isValid());
342 std::vector<double> complex_aabb;
345 ASSERT_EQ(complex_aabb.size(), 6u);
354 int main(
int argc,
char** argv)
356 testing::InitGoogleTest(&argc, argv);
357 return RUN_ALL_TESTS();