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