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 <mapping_msgs/CollisionObject.h>
00043 #include <mapping_msgs/AttachedCollisionObject.h>
00044
00045 #include <object_manipulation_msgs/FindClusterBoundingBox.h>
00046
00047 #include <household_objects_database_msgs/DatabaseModelPose.h>
00048 #include <household_objects_database_msgs/GetModelMesh.h>
00049
00050 namespace tabletop_collision_map_processing {
00051
00052 static const std::string RESET_COLLISION_MAP_NAME = "collision_map_self_occ_node/reset";
00053 static const std::string MAKE_STATIC_COLLISION_MAP_ACTION_NAME = "make_static_collision_map";
00054 static const std::string CLUSTER_BOUNDING_BOX_NAME = "find_cluster_bounding_box";
00055
00056 CollisionMapInterface::CollisionMapInterface() :
00057 root_nh_(""),
00058 priv_nh_("~"),
00059 connections_established_(false),
00060 collision_object_current_id_(0),
00061 make_static_collision_map_client_(root_nh_, MAKE_STATIC_COLLISION_MAP_ACTION_NAME, true)
00062 {
00063 collision_object_pub_ = root_nh_.advertise<mapping_msgs::CollisionObject>("collision_object", 10);
00064 attached_object_pub_ = root_nh_.advertise<mapping_msgs::AttachedCollisionObject>("attached_collision_object", 10);
00065 }
00066
00067 void CollisionMapInterface::connectServices()
00068 {
00069 collision_map_reset_client_ = root_nh_.serviceClient<std_srvs::Empty>(RESET_COLLISION_MAP_NAME, true);
00070 cluster_bounding_box_client_ = root_nh_.serviceClient<object_manipulation_msgs::FindClusterBoundingBox>
00071 (CLUSTER_BOUNDING_BOX_NAME, true);
00072 priv_nh_.param<std::string>("static_map_cloud_name", static_map_cloud_name_, "full_cloud_filtered");
00073 priv_nh_.param<int>("point_skip_num", point_skip_num_, 1);
00074 priv_nh_.param<int>("collision_box_size", collision_box_size_, 0.003);
00075 }
00076
00077 bool CollisionMapInterface::connectionsPresent()
00078 {
00079 if ( !ros::service::exists(RESET_COLLISION_MAP_NAME, true) ) return false;
00080 if ( !ros::service::exists(CLUSTER_BOUNDING_BOX_NAME, true) ) return false;
00081 if (!make_static_collision_map_client_.waitForServer(ros::Duration(0.1)) )
00082 {
00083 ROS_INFO("Make static collision map action server is not connected");
00084 return false;
00085 }
00086 return true;
00087 }
00088
00089 bool CollisionMapInterface::connectionsEstablished(ros::Duration timeout)
00090 {
00091 if (connections_established_) return true;
00092 ros::Time start_time = ros::Time::now();
00093 ros::Duration ping_time = ros::Duration(1.0);
00094 if (timeout >= ros::Duration(0) && ping_time > timeout) ping_time = timeout;
00095 while (!connectionsPresent())
00096 {
00097 ping_time.sleep();
00098 if (!root_nh_.ok()) return false;
00099 if (timeout >= ros::Duration(0) &&
00100 ros::Time::now() - start_time >= timeout) return false;
00101 }
00102 connectServices();
00103 connections_established_ = true;
00104 return true;
00105 }
00106
00107 void CollisionMapInterface::resetCollisionModels()
00108 {
00109 mapping_msgs::CollisionObject reset_object;
00110 reset_object.operation.operation = mapping_msgs::CollisionObjectOperation::REMOVE;
00111 reset_object.header.frame_id = "base_link";
00112 reset_object.header.stamp = ros::Time::now();
00113 reset_object.id = "all";
00114 collision_object_pub_.publish(reset_object);
00115
00116 }
00117
00118 void CollisionMapInterface::resetAttachedModels()
00119 {
00120 mapping_msgs::CollisionObject reset_object;
00121 reset_object.operation.operation = mapping_msgs::CollisionObjectOperation::REMOVE;
00122 reset_object.header.frame_id = "base_link";
00123 reset_object.header.stamp = ros::Time::now();
00124 reset_object.id = "all";
00125 mapping_msgs::AttachedCollisionObject reset_attached_objects;
00126 reset_attached_objects.object.header.frame_id = "base_link";
00127 reset_attached_objects.object.header.stamp = ros::Time::now();
00128 reset_attached_objects.link_name = "all";
00129 reset_attached_objects.object = reset_object;
00130 attached_object_pub_.publish(reset_attached_objects);
00131 }
00132
00133 void CollisionMapInterface::resetStaticMap()
00134 {
00135 std_srvs::Empty srv;
00136 if (!collision_map_reset_client_.call(srv))
00137 {
00138 ROS_ERROR("Collision map reset call failed");
00139 throw CollisionMapException("reset failed");
00140 }
00141 }
00142
00143 std::string CollisionMapInterface::getNextObjectName()
00144 {
00145 std::ostringstream iss;
00146 iss << collision_object_current_id_++;
00147 if (collision_object_current_id_ > 10000) collision_object_current_id_ = 0;
00148 return "graspable_object_" + iss.str();
00149 }
00150
00151 void CollisionMapInterface::takeStaticMap()
00152 {
00153 collision_environment_msgs::MakeStaticCollisionMapGoal static_map_goal;
00154 static_map_goal.cloud_source = static_map_cloud_name_;
00155 static_map_goal.number_of_clouds = 2;
00156
00157 make_static_collision_map_client_.sendGoal(static_map_goal);
00158
00159 if ( !make_static_collision_map_client_.waitForResult(ros::Duration(30.0)) )
00160 {
00161 ROS_ERROR("Collision map was not formed in allowed time");
00162 throw CollisionMapException("static make was not formed in allowed time");
00163 }
00164
00165 if(make_static_collision_map_client_.getState() != actionlib::SimpleClientGoalState::SUCCEEDED)
00166 {
00167 ROS_ERROR("Some non-success state was reached for static collision map. Proceed with caution");
00168 throw CollisionMapException(" static collision map failed");
00169 }
00170 }
00171
00172 void CollisionMapInterface::processCollisionGeometryForTable(const tabletop_object_detector::Table &table,
00173 std::string table_collision_name)
00174 {
00175 mapping_msgs::CollisionObject table_object;
00176 table_object.operation.operation = mapping_msgs::CollisionObjectOperation::ADD;
00177 table_object.header.frame_id = table.pose.header.frame_id;
00178 table_object.header.stamp = ros::Time::now();
00179 table_object.shapes.resize(1);
00180 table_object.shapes[0].type = geometric_shapes_msgs::Shape::BOX;
00181 table_object.shapes[0].dimensions.resize(3);
00182 table_object.shapes[0].dimensions[0] = fabs(table.x_max-table.x_min);
00183 table_object.shapes[0].dimensions[1] = fabs(table.y_max-table.y_min);
00184 table_object.shapes[0].dimensions[2] = 0.01;
00185
00186
00187 tf::Transform table_trans;
00188 tf::poseMsgToTF(table.pose.pose, table_trans);
00189 tf::Transform table_translation;
00190 table_translation.setIdentity();
00191 table_translation.setOrigin( btVector3( (table.x_min + table.x_max)/2.0, (table.y_min + table.y_max)/2.0, 0.0) );
00192 table_trans = table_trans * table_translation;
00193 table_object.poses.resize(1);
00194 tf::poseTFToMsg(table_trans, table_object.poses[0]);
00195
00196 table_object.id = table_collision_name;
00197 collision_object_pub_.publish(table_object);
00198 }
00199
00200 void CollisionMapInterface::processCollisionGeometryForObject
00201 (const household_objects_database_msgs::DatabaseModelPose &model_pose,
00202 std::string &collision_name)
00203 {
00204 mapping_msgs::CollisionObject collision_object;
00205 collision_object.shapes.resize(1);
00206
00207 if (!getMeshFromDatabasePose(model_pose, collision_object.shapes[0]))
00208 {
00209 throw CollisionMapException("Loading mesh for database object failed");
00210 }
00211 collision_object.header.frame_id = model_pose.pose.header.frame_id;
00212 collision_object.header.stamp = ros::Time::now();
00213 collision_object.poses.push_back(model_pose.pose.pose);
00214
00215 collision_object.shapes[0].type = geometric_shapes_msgs::Shape::MESH;
00216 collision_object.operation.operation = mapping_msgs::CollisionObjectOperation::ADD;
00217 collision_name = getNextObjectName();
00218 collision_object.id = collision_name;
00219 collision_object_pub_.publish(collision_object);
00220 }
00221
00222 void
00223 CollisionMapInterface::processCollisionGeometryForBoundingBox(const object_manipulation_msgs::ClusterBoundingBox &box,
00224 std::string &collision_name)
00225 {
00226 ROS_INFO("Adding bounding box with dimensions %f %f %f to collision map",
00227 box.dimensions.x, box.dimensions.y, box.dimensions.z);
00228
00229 mapping_msgs::CollisionObject collision_object;
00230 collision_object.operation.operation = mapping_msgs::CollisionObjectOperation::ADD;
00231
00232 collision_name = getNextObjectName();
00233 collision_object.id = collision_name;
00234
00235 collision_object.header.frame_id = box.pose_stamped.header.frame_id;
00236 collision_object.header.stamp = ros::Time::now();
00237
00238 geometric_shapes_msgs::Shape shape;
00239 shape.type = geometric_shapes_msgs::Shape::BOX;
00240 shape.dimensions.resize(3);
00241 shape.dimensions[0] = box.dimensions.x;
00242 shape.dimensions[1] = box.dimensions.y;
00243 shape.dimensions[2] = box.dimensions.z;
00244 collision_object.shapes.push_back(shape);
00245 collision_object.poses.push_back(box.pose_stamped.pose);
00246
00247 collision_object_pub_.publish(collision_object);
00248 }
00249
00250 void CollisionMapInterface::processCollisionGeometryForCluster(const sensor_msgs::PointCloud &cluster,
00251 std::string &collision_name, float collision_size)
00252 {
00253 ROS_INFO("Adding cluster with %u points to collision map", (unsigned int)cluster.points.size());
00254
00255 mapping_msgs::CollisionObject many_boxes;
00256 many_boxes.operation.operation = mapping_msgs::CollisionObjectOperation::ADD;
00257 many_boxes.header = cluster.header;
00258 many_boxes.header.stamp = ros::Time::now();
00259 unsigned int num_to_use = (unsigned int)(cluster.points.size()/point_skip_num_);
00260 many_boxes.shapes.resize(num_to_use);
00261 many_boxes.poses.resize(num_to_use);
00262
00263 if(collision_size < 0)
00264 collision_size = collision_box_size_;
00265
00266 for(unsigned int i = 0; i < num_to_use; i++) {
00267 geometric_shapes_msgs::Shape shape;
00268 shape.type = geometric_shapes_msgs::Shape::BOX;
00269 shape.dimensions.resize(3);
00270 shape.dimensions[0] = collision_size;
00271 shape.dimensions[1] = collision_size;
00272 shape.dimensions[2] = collision_size;
00273 many_boxes.shapes[i]=shape;
00274 geometry_msgs::Pose pose;
00275 pose.position.x = cluster.points[i*point_skip_num_].x;
00276 pose.position.y = cluster.points[i*point_skip_num_].y;
00277 pose.position.z = cluster.points[i*point_skip_num_].z;
00278 pose.orientation.x = 0;
00279 pose.orientation.y = 0;
00280 pose.orientation.z = 0;
00281 pose.orientation.w = 1;
00282 many_boxes.poses[i] = pose;
00283 }
00284
00285 collision_name = getNextObjectName();
00286
00287 many_boxes.id = collision_name;
00288 collision_object_pub_.publish(many_boxes);
00289 }
00290
00291 bool CollisionMapInterface::getMeshFromDatabasePose(const household_objects_database_msgs::DatabaseModelPose &model_pose,
00292 geometric_shapes_msgs::Shape& mesh)
00293 {
00294 static bool service_initialized = false;
00295 if (!service_initialized)
00296 {
00297 std::string get_model_mesh_srv_name;
00298 priv_nh_.param<std::string>("get_model_mesh_srv", get_model_mesh_srv_name, "get_model_mesh_srv");
00299 while ( !ros::service::waitForService(get_model_mesh_srv_name, ros::Duration(2.0)) && root_nh_.ok() )
00300 {
00301 ROS_INFO("Waiting for %s service to come up", get_model_mesh_srv_name.c_str());
00302 }
00303 if (!root_nh_.ok()) return false;
00304 get_model_mesh_srv_ = root_nh_.serviceClient<household_objects_database_msgs::GetModelMesh>
00305 (get_model_mesh_srv_name, true);
00306 service_initialized = true;
00307 }
00308 household_objects_database_msgs::GetModelMesh get_mesh;
00309 get_mesh.request.model_id = model_pose.model_id;
00310 if ( !get_model_mesh_srv_.call(get_mesh) ||
00311 get_mesh.response.return_code.code != get_mesh.response.return_code.SUCCESS )
00312 {
00313 return false;
00314 }
00315 mesh = get_mesh.response.mesh;
00316 return true;
00317 }
00318
00319 void CollisionMapInterface::getClusterBoundingBox(const sensor_msgs::PointCloud &cluster,
00320 geometry_msgs::PoseStamped &pose_stamped,
00321 geometry_msgs::Vector3 &dimensions)
00322 {
00323 object_manipulation_msgs::FindClusterBoundingBox srv;
00324 srv.request.cluster = cluster;
00325 if (!cluster_bounding_box_client_.call(srv.request, srv.response))
00326 {
00327 ROS_ERROR("Failed to call cluster bounding box client");
00328 throw CollisionMapException("Failed to call cluster bounding box client");
00329 }
00330 pose_stamped = srv.response.pose;
00331 dimensions = srv.response.box_dims;
00332 if (dimensions.x == 0.0 && dimensions.y == 0.0 && dimensions.z == 0.0)
00333 {
00334 ROS_ERROR("Cluster bounding box client returned an error (0.0 bounding box)");
00335 throw CollisionMapException("Bounding box computation failed");
00336 }
00337 }
00338
00340 bool CollisionMapInterface::extendBoundingBoxZToTable(const tabletop_object_detector::Table &table,
00341 geometry_msgs::PoseStamped &pose_stamped,
00342 geometry_msgs::Vector3 &dimensions)
00343 {
00344 if (table.pose.header.frame_id != pose_stamped.header.frame_id)
00345 {
00346 ROS_INFO("cannot extend bbox to table, they are not in the same frame");
00347 return false;
00348 }
00349
00350
00351 btVector3 table_location(table.pose.pose.position.x,
00352 table.pose.pose.position.y,
00353 table.pose.pose.position.z);
00354 btVector3 bbox_location(pose_stamped.pose.position.x,
00355 pose_stamped.pose.position.y,
00356 pose_stamped.pose.position.z);
00357 btVector3 table_to_bbox = bbox_location - table_location;
00358 btTransform table_trans;
00359 tf::poseMsgToTF(table.pose.pose, table_trans);
00360 btVector3 table_z = table_trans.getBasis().getColumn(2);
00361 ROS_INFO("Table z: %f %f %f in frame %s", table_z.getX(), table_z.getY(), table_z.getZ(), table.pose.header.frame_id.c_str());
00362 double box_to_table_distance = table_to_bbox.dot(table_z);
00363 ROS_INFO("Table distance: %f", box_to_table_distance);
00364
00365
00366
00367 btTransform bbox_trans;
00368 tf::poseMsgToTF(pose_stamped.pose, bbox_trans);
00369 btVector3 bbox_z = bbox_trans.getBasis().getColumn(2);
00370 if (fabs(bbox_z.dot(table_z)) < 0.9848)
00371 {
00372 ROS_INFO("cannot extend bbox to table; z axes do not coincide");
00373 return false;
00374 }
00375
00376 double z_to_table = box_to_table_distance;
00377 ROS_INFO("z_to_table: %f", z_to_table);
00378 if ( z_to_table < 0.005 || z_to_table > 0.3)
00379 {
00380 ROS_INFO("cannot extend bbox to table; getting z equal to %f", z_to_table);
00381 return false;
00382 }
00383 ROS_INFO("Old z: %f", dimensions.z);
00384 double new_z = dimensions.z/2.0 + z_to_table;
00385 ROS_INFO("New z: %f", new_z);
00386 pose_stamped.pose.position.z = pose_stamped.pose.position.z + (dimensions.z/2.0) - (new_z/2.0);
00387 dimensions.z = new_z;
00388 return true;
00389 }
00390
00391
00392 }