00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include "tabletop_collision_map_processing/collision_map_interface.h"
00037
00038 #include <tf/transform_datatypes.h>
00039
00040 #include <std_srvs/Empty.h>
00041
00042 #include <arm_navigation_msgs/CollisionObject.h>
00043 #include <arm_navigation_msgs/AttachedCollisionObject.h>
00044
00045 #include <object_manipulation_msgs/FindClusterBoundingBox.h>
00046 #include <object_manipulation_msgs/FindClusterBoundingBox2.h>
00047
00048 #include <household_objects_database_msgs/DatabaseModelPose.h>
00049 #include <household_objects_database_msgs/GetModelMesh.h>
00050
00051 #include <object_manipulator/tools/msg_helpers.h>
00052
00053 namespace tabletop_collision_map_processing {
00054
00055 static const std::string CLUSTER_BOUNDING_BOX_NAME = "find_cluster_bounding_box";
00056 static const std::string CLUSTER_BOUNDING_BOX2_NAME = "find_cluster_bounding_box2";
00057 static const std::string CLUSTER_BOUNDING_BOX_3D_NAME = "find_cluster_bounding_box_3d";
00058 static const std::string CLUSTER_BOUNDING_BOX2_3D_NAME = "find_cluster_bounding_box2_3d";
00059
00060 CollisionMapInterface::CollisionMapInterface() :
00061 root_nh_(""),
00062 priv_nh_("~"),
00063 connections_established_(false),
00064 collision_object_current_id_(0)
00065 {
00066 collision_object_pub_ = root_nh_.advertise<arm_navigation_msgs::CollisionObject>("collision_object", 10);
00067 attached_object_pub_ = root_nh_.advertise<arm_navigation_msgs::AttachedCollisionObject>("attached_collision_object", 10);
00068 }
00069
00070 void CollisionMapInterface::connectServices()
00071 {
00072 cluster_bounding_box_client_ = root_nh_.serviceClient<object_manipulation_msgs::FindClusterBoundingBox>
00073 (CLUSTER_BOUNDING_BOX_NAME, true);
00074 cluster_bounding_box2_client_ = root_nh_.serviceClient<object_manipulation_msgs::FindClusterBoundingBox2>
00075 (CLUSTER_BOUNDING_BOX2_NAME, true);
00076 cluster_bounding_box_3d_client_ = root_nh_.serviceClient<object_manipulation_msgs::FindClusterBoundingBox>
00077 (CLUSTER_BOUNDING_BOX_3D_NAME, true);
00078 cluster_bounding_box2_3d_client_ = root_nh_.serviceClient<object_manipulation_msgs::FindClusterBoundingBox2>
00079 (CLUSTER_BOUNDING_BOX2_3D_NAME, true);
00080 priv_nh_.param<int>("point_skip_num", point_skip_num_, 1);
00081 priv_nh_.param<int>("collision_box_size", collision_box_size_, 0.003);
00082 priv_nh_.param<double>("table_thickness", table_thickness_, 0.);
00083 }
00084
00085 bool CollisionMapInterface::connectionsPresent()
00086 {
00087 if ( !ros::service::exists(CLUSTER_BOUNDING_BOX_NAME, true) ) return false;
00088 if ( !ros::service::exists(CLUSTER_BOUNDING_BOX2_NAME, true) ) return false;
00089 return true;
00090 }
00091
00092 bool CollisionMapInterface::connectionsEstablished(ros::Duration timeout)
00093 {
00094 if (connections_established_) return true;
00095 ros::Time start_time = ros::Time::now();
00096 ros::Duration ping_time = ros::Duration(1.0);
00097 if (timeout >= ros::Duration(0) && ping_time > timeout) ping_time = timeout;
00098 while (!connectionsPresent())
00099 {
00100 ping_time.sleep();
00101 if (!root_nh_.ok()) return false;
00102 if (timeout >= ros::Duration(0) &&
00103 ros::Time::now() - start_time >= timeout) return false;
00104 }
00105 connectServices();
00106 connections_established_ = true;
00107 return true;
00108 }
00109
00110 void CollisionMapInterface::removeCollisionModel(std::string collision_name)
00111 {
00112 arm_navigation_msgs::CollisionObject reset_object;
00113 reset_object.operation.operation = arm_navigation_msgs::CollisionObjectOperation::REMOVE;
00114 reset_object.header.frame_id = "base_link";
00115 reset_object.header.stamp = ros::Time::now();
00116 reset_object.id = collision_name;
00117 collision_object_pub_.publish(reset_object);
00118 }
00119
00120 void CollisionMapInterface::resetCollisionModels()
00121 {
00122 arm_navigation_msgs::CollisionObject reset_object;
00123 reset_object.operation.operation = arm_navigation_msgs::CollisionObjectOperation::REMOVE;
00124 reset_object.header.frame_id = "base_link";
00125 reset_object.header.stamp = ros::Time::now();
00126 reset_object.id = "all";
00127 collision_object_pub_.publish(reset_object);
00128
00129 }
00130
00131 void CollisionMapInterface::resetAttachedModels()
00132 {
00133 arm_navigation_msgs::CollisionObject reset_object;
00134 reset_object.operation.operation = arm_navigation_msgs::CollisionObjectOperation::REMOVE;
00135 reset_object.header.frame_id = "base_link";
00136 reset_object.header.stamp = ros::Time::now();
00137 reset_object.id = "all";
00138 arm_navigation_msgs::AttachedCollisionObject reset_attached_objects;
00139 reset_attached_objects.object.header.frame_id = "base_link";
00140 reset_attached_objects.object.header.stamp = ros::Time::now();
00141 reset_attached_objects.link_name = "all";
00142 reset_attached_objects.object = reset_object;
00143 attached_object_pub_.publish(reset_attached_objects);
00144 }
00145
00146 std::string CollisionMapInterface::getNextObjectName()
00147 {
00148 std::ostringstream iss;
00149 iss << collision_object_current_id_++;
00150 if (collision_object_current_id_ > 10000) collision_object_current_id_ = 0;
00151 return "graspable_object_" + iss.str();
00152 }
00153
00154 void CollisionMapInterface::processCollisionGeometryForTable(const tabletop_object_detector::Table &table,
00155 std::string table_collision_name)
00156 {
00157 arm_navigation_msgs::CollisionObject table_object;
00158 table_object.operation.operation = arm_navigation_msgs::CollisionObjectOperation::ADD;
00159 table_object.header.frame_id = table.pose.header.frame_id;
00160 table_object.header.stamp = ros::Time::now();
00161 table_object.shapes.resize(1);
00162 table_object.poses.resize(1);
00163
00164
00165 if(table.convex_hull.type == table.convex_hull.MESH && table.convex_hull.triangles.size() != 0)
00166 {
00167 ROS_INFO("using convex hull mesh for table collision geometry");
00168 table_object.shapes[0] = table.convex_hull;
00169 table_object.poses[0] = table.pose.pose;
00170 if(table_thickness_)
00171 {
00172 ROS_INFO("using table_thickness of %.3f", table_thickness_);
00173 tf::Transform T, P;
00174 tf::poseMsgToTF(table.pose.pose, P);
00175 geometry_msgs::Pose shifted_table_pose;
00176 geometry_msgs::Pose shifted_table_offset = object_manipulator::msg::createPoseMsg(tf::Pose(tf::Quaternion::getIdentity(), tf::Vector3(0,0,-table_thickness_)));
00177 tf::poseMsgToTF(shifted_table_offset, T);
00178 tf::poseTFToMsg( P*T, shifted_table_pose);
00179 table_object.shapes.push_back(table.convex_hull);
00180 table_object.poses.push_back(shifted_table_pose);
00181 }
00182 }
00183
00184
00185 else
00186 {
00187 ROS_INFO("using box table collision geometry");
00188 table_object.shapes[0].type = arm_navigation_msgs::Shape::BOX;
00189 table_object.shapes[0].dimensions.resize(3);
00190 table_object.shapes[0].dimensions[0] = fabs(table.x_max-table.x_min);
00191 table_object.shapes[0].dimensions[1] = fabs(table.y_max-table.y_min);
00192 if(table_thickness_) table_object.shapes[0].dimensions[2] = table_thickness_;
00193 else table_object.shapes[0].dimensions[2] = 0.01;
00194
00195
00196 tf::Transform table_trans;
00197 tf::poseMsgToTF(table.pose.pose, table_trans);
00198 tf::Transform table_translation;
00199 table_translation.setIdentity();
00200 table_translation.setOrigin( tf::Vector3( (table.x_min + table.x_max)/2.0, (table.y_min + table.y_max)/2.0, 0.0) );
00201 table_trans = table_trans * table_translation;
00202 tf::poseTFToMsg(table_trans, table_object.poses[0]);
00203 }
00204
00205 table_object.id = table_collision_name;
00206 collision_object_pub_.publish(table_object);
00207 }
00208
00209 void CollisionMapInterface::processCollisionGeometryForObject
00210 (const household_objects_database_msgs::DatabaseModelPose &model_pose,
00211 std::string &collision_name)
00212 {
00213 arm_navigation_msgs::CollisionObject collision_object;
00214 collision_object.shapes.resize(1);
00215
00216 if (!getMeshFromDatabasePose(model_pose, collision_object.shapes[0]))
00217 {
00218 throw CollisionMapException("Loading mesh for database object failed");
00219 }
00220 collision_object.header.frame_id = model_pose.pose.header.frame_id;
00221 collision_object.header.stamp = ros::Time::now();
00222 collision_object.poses.push_back(model_pose.pose.pose);
00223
00224 collision_object.shapes[0].type = arm_navigation_msgs::Shape::MESH;
00225 collision_object.operation.operation = arm_navigation_msgs::CollisionObjectOperation::ADD;
00226 collision_name = getNextObjectName();
00227 collision_object.id = collision_name;
00228 collision_object_pub_.publish(collision_object);
00229 }
00230
00231
00232 void CollisionMapInterface::processCollisionGeometryForObjectAsBoundingBox
00233 (const household_objects_database_msgs::DatabaseModelPose &model_pose,
00234 std::string &collision_name)
00235 {
00236 arm_navigation_msgs::Shape model_shape;
00237 if (!getMeshFromDatabasePose(model_pose, model_shape))
00238 {
00239 throw CollisionMapException("Loading mesh for database object failed");
00240 }
00241 sensor_msgs::PointCloud cluster;
00242 cluster.header = model_pose.pose.header;
00243 for (size_t i=0; i<model_shape.vertices.size(); i++)
00244 {
00245 geometry_msgs::Point32 point;
00246 point.x = model_shape.vertices[i].x;
00247 point.y = model_shape.vertices[i].y;
00248 point.z = model_shape.vertices[i].z;
00249 cluster.points.push_back(point);
00250 }
00251 object_manipulation_msgs::ClusterBoundingBox box;
00252 getClusterBoundingBox(cluster, box.pose_stamped, box.dimensions);
00253
00254 arm_navigation_msgs::CollisionObject collision_object;
00255 collision_object.operation.operation = arm_navigation_msgs::CollisionObjectOperation::ADD;
00256
00257 collision_name = getNextObjectName();
00258 collision_object.id = collision_name;
00259
00260 collision_object.header.frame_id = model_pose.pose.header.frame_id;
00261 collision_object.header.stamp = ros::Time::now();
00262
00263 arm_navigation_msgs::Shape shape;
00264 shape.type = arm_navigation_msgs::Shape::BOX;
00265 shape.dimensions.resize(3);
00266 shape.dimensions[0] = box.dimensions.x;
00267 shape.dimensions[1] = box.dimensions.y;
00268 shape.dimensions[2] = box.dimensions.z;
00269 collision_object.shapes.push_back(shape);
00270
00271
00272 tf::Transform model_trans;
00273 tf::poseMsgToTF(model_pose.pose.pose, model_trans);
00274 tf::Transform box_trans;
00275 tf::poseMsgToTF(box.pose_stamped.pose, box_trans);
00276 tf::Transform total_trans = model_trans * box_trans;
00277
00278 geometry_msgs::Pose total_pose;
00279 tf::poseTFToMsg(total_trans, total_pose);
00280 collision_object.poses.push_back(total_pose);
00281
00282 collision_object_pub_.publish(collision_object);
00283 }
00284
00285 void
00286 CollisionMapInterface::processCollisionGeometryForBoundingBox(const object_manipulation_msgs::ClusterBoundingBox &box,
00287 std::string &collision_name)
00288 {
00289 ROS_INFO("Adding bounding box with dimensions %f %f %f to collision map",
00290 box.dimensions.x, box.dimensions.y, box.dimensions.z);
00291
00292 arm_navigation_msgs::CollisionObject collision_object;
00293 collision_object.operation.operation = arm_navigation_msgs::CollisionObjectOperation::ADD;
00294
00295 collision_name = getNextObjectName();
00296 collision_object.id = collision_name;
00297
00298 collision_object.header.frame_id = box.pose_stamped.header.frame_id;
00299 collision_object.header.stamp = ros::Time::now();
00300
00301 arm_navigation_msgs::Shape shape;
00302 shape.type = arm_navigation_msgs::Shape::BOX;
00303 shape.dimensions.resize(3);
00304 shape.dimensions[0] = box.dimensions.x;
00305 shape.dimensions[1] = box.dimensions.y;
00306 shape.dimensions[2] = box.dimensions.z;
00307 collision_object.shapes.push_back(shape);
00308 collision_object.poses.push_back(box.pose_stamped.pose);
00309
00310 collision_object_pub_.publish(collision_object);
00311 }
00312
00313 void CollisionMapInterface::processCollisionGeometryForCluster(const sensor_msgs::PointCloud &cluster,
00314 std::string &collision_name, float collision_size)
00315 {
00316 ROS_INFO("Adding cluster with %u points to collision map", (unsigned int)cluster.points.size());
00317
00318 arm_navigation_msgs::CollisionObject many_boxes;
00319 many_boxes.operation.operation = arm_navigation_msgs::CollisionObjectOperation::ADD;
00320 many_boxes.header = cluster.header;
00321 many_boxes.header.stamp = ros::Time::now();
00322 unsigned int num_to_use = (unsigned int)(cluster.points.size()/point_skip_num_);
00323 many_boxes.shapes.resize(num_to_use);
00324 many_boxes.poses.resize(num_to_use);
00325
00326 if(collision_size < 0)
00327 collision_size = collision_box_size_;
00328
00329 for(unsigned int i = 0; i < num_to_use; i++) {
00330 arm_navigation_msgs::Shape shape;
00331 shape.type = arm_navigation_msgs::Shape::BOX;
00332 shape.dimensions.resize(3);
00333 shape.dimensions[0] = collision_size;
00334 shape.dimensions[1] = collision_size;
00335 shape.dimensions[2] = collision_size;
00336 many_boxes.shapes[i]=shape;
00337 geometry_msgs::Pose pose;
00338 pose.position.x = cluster.points[i*point_skip_num_].x;
00339 pose.position.y = cluster.points[i*point_skip_num_].y;
00340 pose.position.z = cluster.points[i*point_skip_num_].z;
00341 pose.orientation.x = 0;
00342 pose.orientation.y = 0;
00343 pose.orientation.z = 0;
00344 pose.orientation.w = 1;
00345 many_boxes.poses[i] = pose;
00346 }
00347
00348 collision_name = getNextObjectName();
00349
00350 many_boxes.id = collision_name;
00351 collision_object_pub_.publish(many_boxes);
00352 }
00353
00354 bool CollisionMapInterface::getMeshFromDatabasePose(const household_objects_database_msgs::DatabaseModelPose &model_pose,
00355 arm_navigation_msgs::Shape& mesh)
00356 {
00357 static bool service_initialized = false;
00358 if (!service_initialized)
00359 {
00360 std::string get_model_mesh_srv_name;
00361 priv_nh_.param<std::string>("get_model_mesh_srv", get_model_mesh_srv_name, "get_model_mesh_srv");
00362 ros::Time start_time = ros::Time::now();
00363 while ( !ros::service::waitForService(get_model_mesh_srv_name, ros::Duration(2.0)) )
00364 {
00365 ROS_INFO("Waiting for %s service to come up", get_model_mesh_srv_name.c_str());
00366 if (!root_nh_.ok() || ros::Time::now() - start_time >= ros::Duration(5.0))
00367 {
00368 return false;
00369 }
00370 }
00371 get_model_mesh_srv_ = root_nh_.serviceClient<household_objects_database_msgs::GetModelMesh>
00372 (get_model_mesh_srv_name, false);
00373 service_initialized = true;
00374 }
00375 household_objects_database_msgs::GetModelMesh get_mesh;
00376 get_mesh.request.model_id = model_pose.model_id;
00377 if ( !get_model_mesh_srv_.call(get_mesh) )
00378 {
00379 ROS_ERROR("Get model mesh service service call failed altogether");
00380 return false;
00381 }
00382 else if (get_mesh.response.return_code.code != get_mesh.response.return_code.SUCCESS )
00383 {
00384 ROS_ERROR("Get model mesh service returned an error");
00385 return false;
00386 }
00387 mesh = get_mesh.response.mesh;
00388 return true;
00389 }
00390
00391 void CollisionMapInterface::getClusterBoundingBox(const sensor_msgs::PointCloud &cluster,
00392 geometry_msgs::PoseStamped &pose_stamped,
00393 geometry_msgs::Vector3 &dimensions)
00394 {
00395 object_manipulation_msgs::FindClusterBoundingBox srv;
00396 srv.request.cluster = cluster;
00397 if (!cluster_bounding_box_client_.call(srv.request, srv.response))
00398 {
00399 ROS_ERROR("Failed to call cluster bounding box client");
00400 throw CollisionMapException("Failed to call cluster bounding box client");
00401 }
00402 pose_stamped = srv.response.pose;
00403 dimensions = srv.response.box_dims;
00404 if (dimensions.x == 0.0 && dimensions.y == 0.0 && dimensions.z == 0.0)
00405 {
00406 ROS_ERROR("Cluster bounding box client returned an error (0.0 bounding box)");
00407 throw CollisionMapException("Bounding box computation failed");
00408 }
00409 }
00410
00411 void CollisionMapInterface::getClusterBoundingBox(const sensor_msgs::PointCloud2 &cluster,
00412 geometry_msgs::PoseStamped &pose_stamped,
00413 geometry_msgs::Vector3 &dimensions)
00414 {
00415 object_manipulation_msgs::FindClusterBoundingBox2 srv;
00416 srv.request.cluster = cluster;
00417 if (!cluster_bounding_box2_client_.call(srv.request, srv.response))
00418 {
00419 ROS_ERROR("Failed to call cluster bounding box client");
00420 throw CollisionMapException("Failed to call cluster bounding box client");
00421 }
00422 pose_stamped = srv.response.pose;
00423 dimensions = srv.response.box_dims;
00424 if (dimensions.x == 0.0 && dimensions.y == 0.0 && dimensions.z == 0.0)
00425 {
00426 ROS_ERROR("Cluster bounding box 2 client returned an error (0.0 bounding box)");
00427 throw CollisionMapException("Bounding box computation failed");
00428 }
00429 }
00430
00431 void CollisionMapInterface::getClusterBoundingBox3D(const sensor_msgs::PointCloud &cluster,
00432 geometry_msgs::PoseStamped &pose_stamped,
00433 geometry_msgs::Vector3 &dimensions)
00434 {
00435 object_manipulation_msgs::FindClusterBoundingBox srv;
00436 srv.request.cluster = cluster;
00437 if (!cluster_bounding_box_3d_client_.call(srv.request, srv.response))
00438 {
00439 ROS_ERROR("Failed to call cluster bounding box client");
00440 throw CollisionMapException("Failed to call cluster bounding box client");
00441 }
00442 pose_stamped = srv.response.pose;
00443 dimensions = srv.response.box_dims;
00444 if (dimensions.x == 0.0 && dimensions.y == 0.0 && dimensions.z == 0.0)
00445 {
00446 ROS_ERROR("Cluster bounding box 3d client returned an error (0.0 bounding box)");
00447 throw CollisionMapException("Bounding box computation failed");
00448 }
00449 }
00450
00451 void CollisionMapInterface::getClusterBoundingBox3D(const sensor_msgs::PointCloud2 &cluster,
00452 geometry_msgs::PoseStamped &pose_stamped,
00453 geometry_msgs::Vector3 &dimensions)
00454 {
00455 object_manipulation_msgs::FindClusterBoundingBox2 srv;
00456 srv.request.cluster = cluster;
00457 if (!cluster_bounding_box2_3d_client_.call(srv.request, srv.response))
00458 {
00459 ROS_ERROR("Failed to call cluster bounding box client");
00460 throw CollisionMapException("Failed to call cluster bounding box client");
00461 }
00462 pose_stamped = srv.response.pose;
00463 dimensions = srv.response.box_dims;
00464 if (dimensions.x == 0.0 && dimensions.y == 0.0 && dimensions.z == 0.0)
00465 {
00466 ROS_ERROR("Cluster bounding box 2 3d client returned an error (0.0 bounding box)");
00467 throw CollisionMapException("Bounding box computation failed");
00468 }
00469 }
00470
00471
00473 bool CollisionMapInterface::extendBoundingBoxZToTable(const tabletop_object_detector::Table &table,
00474 geometry_msgs::PoseStamped &pose_stamped,
00475 geometry_msgs::Vector3 &dimensions)
00476 {
00477 if (table.pose.header.frame_id != pose_stamped.header.frame_id)
00478 {
00479 ROS_INFO("cannot extend bbox to table, they are not in the same frame");
00480 return false;
00481 }
00482
00483
00484 tf::Vector3 table_location(table.pose.pose.position.x,
00485 table.pose.pose.position.y,
00486 table.pose.pose.position.z);
00487 tf::Vector3 bbox_location(pose_stamped.pose.position.x,
00488 pose_stamped.pose.position.y,
00489 pose_stamped.pose.position.z);
00490 tf::Vector3 table_to_bbox = bbox_location - table_location;
00491 tf::Transform table_trans;
00492 tf::poseMsgToTF(table.pose.pose, table_trans);
00493 tf::Vector3 table_z = table_trans.getBasis().getColumn(2);
00494 ROS_INFO("Table z: %f %f %f in frame %s",
00495 table_z.getX(), table_z.getY(), table_z.getZ(), table.pose.header.frame_id.c_str());
00496 double box_to_table_distance = table_to_bbox.dot(table_z);
00497 ROS_INFO("Table distance: %f", box_to_table_distance);
00498
00499
00500
00501 tf::Transform bbox_trans;
00502 tf::poseMsgToTF(pose_stamped.pose, bbox_trans);
00503 tf::Vector3 bbox_z = bbox_trans.getBasis().getColumn(2);
00504 if (fabs(bbox_z.dot(table_z)) < 0.9848)
00505 {
00506 ROS_INFO("cannot extend bbox to table; z axes do not coincide");
00507 return false;
00508 }
00509
00510 double z_to_table = box_to_table_distance;
00511 ROS_INFO("z_to_table: %f", z_to_table);
00512 if ( z_to_table < 0.005 || z_to_table > 0.3)
00513 {
00514 ROS_INFO("cannot extend bbox to table; getting z equal to %f", z_to_table);
00515 return false;
00516 }
00517 ROS_INFO("Old z: %f", dimensions.z);
00518 double new_z = dimensions.z/2.0 + z_to_table;
00519 ROS_INFO("New z: %f", new_z);
00520 pose_stamped.pose.position.z = pose_stamped.pose.position.z + (dimensions.z/2.0) - (new_z/2.0);
00521 dimensions.z = new_z;
00522 return true;
00523 }
00524
00525
00526 }