$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2011, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00037 #include <planning_environment/monitors/monitor_utils.h> 00038 #include <planning_environment/util/construct_object.h> 00039 #include <robot_self_filter/self_mask.h> 00040 #include <pcl_ros/transforms.h> 00041 #include <angles/angles.h> 00042 00043 bool planning_environment::getLatestIdentityTransform(const std::string& to_frame, 00044 const std::string& from_frame, 00045 tf::TransformListener& tf, 00046 btTransform& pose) 00047 { 00048 geometry_msgs::PoseStamped temp_pose; 00049 temp_pose.pose.orientation.w = 1.0; 00050 temp_pose.header.frame_id = from_frame; 00051 geometry_msgs::PoseStamped trans_pose; 00052 ros::Time tm; 00053 std::string err_string; 00054 if (tf.getLatestCommonTime(to_frame, temp_pose.header.frame_id, tm, &err_string) == tf::NO_ERROR) { 00055 temp_pose.header.stamp = tm; 00056 try { 00057 tf.transformPose(to_frame, temp_pose, trans_pose); 00058 } catch(tf::TransformException& ex) { 00059 ROS_ERROR_STREAM("Unable to transform object from frame " << temp_pose.header.frame_id << " to " << to_frame << " error is " << ex.what()); 00060 return false; 00061 } 00062 } else { 00063 ROS_ERROR_STREAM("No latest time for transforming " << from_frame << " to " << to_frame); 00064 return false; 00065 } 00066 tf::poseMsgToTF(trans_pose.pose, pose); 00067 return true; 00068 } 00069 00070 bool planning_environment::createAndPoseShapes(tf::TransformListener& tf, 00071 const std::vector<arm_navigation_msgs::Shape>& orig_shapes, 00072 const std::vector<geometry_msgs::Pose>& orig_poses, 00073 const std_msgs::Header& header, 00074 const std::string& frame_to, 00075 std::vector<shapes::Shape*>& conv_shapes, 00076 std::vector<btTransform>& conv_poses) 00077 { 00078 conv_shapes.clear(); 00079 conv_poses.clear(); 00080 bool shapes_ok = true; 00081 btTransform ident_trans; 00082 if(!getLatestIdentityTransform(frame_to, header.frame_id, tf, ident_trans)) { 00083 ROS_WARN_STREAM("Can't get identity pose to transform shapes"); 00084 return false; 00085 } 00086 for(unsigned int i = 0; i < orig_shapes.size(); i++) { 00087 shapes::Shape *shape = constructObject(orig_shapes[i]); 00088 if(shape == NULL) { 00089 shapes_ok = false; 00090 break; 00091 } 00092 conv_shapes.push_back(shape); 00093 btTransform shape_pose; 00094 tf::poseMsgToTF(orig_poses[i], shape_pose); 00095 conv_poses.push_back(ident_trans*shape_pose); 00096 } 00097 if(!shapes_ok) { 00098 for(unsigned int i=0; i < conv_shapes.size(); i++) { 00099 delete conv_shapes[i]; 00100 } 00101 conv_shapes.clear(); 00102 conv_poses.clear(); 00103 return false; 00104 } 00105 return true; 00106 } 00107 00108 bool planning_environment::processCollisionObjectMsg(const arm_navigation_msgs::CollisionObjectConstPtr &collision_object, 00109 tf::TransformListener& tf, 00110 planning_environment::CollisionModels* cm) 00111 { 00112 if (collision_object->operation.operation == arm_navigation_msgs::CollisionObjectOperation::ADD) { 00113 std::vector<shapes::Shape*> shapes; 00114 std::vector<btTransform> poses; 00115 bool shapes_ok = createAndPoseShapes(tf, 00116 collision_object->shapes, 00117 collision_object->poses, 00118 collision_object->header, 00119 cm->getWorldFrameId(), 00120 shapes, 00121 poses); 00122 if(!shapes_ok) { 00123 ROS_INFO_STREAM("Not adding attached object " << collision_object->id 00124 << " to collision space because something's wrong with the shapes"); 00125 return false; 00126 } else { 00127 double padding = cm->getDefaultObjectPadding(); 00128 if(collision_object->padding < 0.0) { 00129 padding = 0.0; 00130 } else if(collision_object->padding > 0.0) { 00131 padding = collision_object->padding; 00132 } 00133 cm->addStaticObject(collision_object->id, 00134 shapes, 00135 poses, 00136 padding); 00137 ROS_INFO("Added %u object to namespace %s in collision space", (unsigned int)shapes.size(),collision_object->id.c_str()); 00138 } 00139 } else { 00140 if(collision_object->id == "all") { 00141 cm->deleteAllStaticObjects(); 00142 ROS_INFO("Cleared all collision objects"); 00143 } else { 00144 cm->deleteStaticObject(collision_object->id); 00145 ROS_INFO("Removed object '%s' from collision space", collision_object->id.c_str()); 00146 } 00147 } 00148 return true; 00149 } 00150 00151 bool planning_environment::processAttachedCollisionObjectMsg(const arm_navigation_msgs::AttachedCollisionObjectConstPtr &attached_object, 00152 tf::TransformListener& tf, 00153 planning_environment::CollisionModels* cm) 00154 { 00155 if(attached_object->link_name == "all") { //attached_object->REMOVE_ALL_ATTACHED_OBJECTS) { 00156 if(attached_object->object.operation.operation != arm_navigation_msgs::CollisionObjectOperation::REMOVE) { 00157 ROS_WARN("Can't perform any action for all attached bodies except remove"); 00158 return false; 00159 } 00160 cm->deleteAllAttachedObjects(); 00161 ROS_INFO_STREAM("Cleared all attached objects"); 00162 return true; 00163 } 00164 00165 //if there are no objects in the map, clear everything 00166 unsigned int n = attached_object->object.shapes.size(); 00167 00168 const arm_navigation_msgs::CollisionObject& obj = attached_object->object; 00169 00170 if(n == 0) { 00171 if(obj.operation.operation == arm_navigation_msgs::CollisionObjectOperation::REMOVE) { 00172 cm->deleteAllAttachedObjects(attached_object->link_name); 00173 return true; 00174 } else if (obj.operation.operation == arm_navigation_msgs::CollisionObjectOperation::ADD){ 00175 ROS_INFO("Remove must also be specified to delete all attached bodies"); 00176 return false; 00177 } 00178 } 00179 00180 if(obj.operation.operation == arm_navigation_msgs::CollisionObjectOperation::DETACH_AND_ADD_AS_OBJECT 00181 || obj.operation.operation == arm_navigation_msgs::CollisionObjectOperation::ATTACH_AND_REMOVE_AS_OBJECT) { 00182 //getting link pose in the world frame 00183 btTransform link_pose; 00184 if(!getLatestIdentityTransform(cm->getWorldFrameId(), attached_object->link_name, tf, link_pose)) { 00185 ROS_WARN_STREAM("Can't get transform for link " << attached_object->link_name); 00186 return false; 00187 } 00188 if(obj.operation.operation == arm_navigation_msgs::CollisionObjectOperation::DETACH_AND_ADD_AS_OBJECT) { 00189 cm->convertAttachedObjectToStaticObject(obj.id, 00190 attached_object->link_name, 00191 link_pose); 00192 } else { 00193 cm->convertStaticObjectToAttachedObject(obj.id, 00194 attached_object->link_name, 00195 link_pose, 00196 attached_object->touch_links); 00197 } 00198 } else if(obj.operation.operation == arm_navigation_msgs::CollisionObjectOperation::REMOVE) { 00199 cm->deleteAttachedObject(obj.id, 00200 attached_object->link_name); 00201 } else { 00202 std::vector<shapes::Shape*> shapes; 00203 std::vector<btTransform> poses; 00204 bool shapes_ok = createAndPoseShapes(tf, 00205 obj.shapes, 00206 obj.poses, 00207 obj.header, 00208 attached_object->link_name, 00209 shapes, 00210 poses); 00211 if(!shapes_ok) { 00212 for(unsigned int i = 0; i < shapes.size(); i++) { 00213 delete shapes[i]; 00214 } 00215 ROS_WARN_STREAM("Not adding attached object " << obj.id 00216 << " to collision space because something's wrong with the shapes"); 00217 return true; 00218 } 00219 double padding = cm->getDefaultObjectPadding(); 00220 if(attached_object->object.padding < 0.0) { 00221 padding = 0.0; 00222 } else if(attached_object->object.padding > 0.0){ 00223 padding = attached_object->object.padding; 00224 } 00225 cm->addAttachedObject(obj.id, 00226 attached_object->link_name, 00227 shapes, 00228 poses, 00229 attached_object->touch_links, 00230 padding); 00231 } 00232 return true; 00233 } 00234 00235 void planning_environment::updateAttachedObjectBodyPoses(planning_environment::CollisionModels* cm, 00236 planning_models::KinematicState& state, 00237 tf::TransformListener& tf) 00238 { 00239 cm->bodiesLock(); 00240 00241 const std::map<std::string, std::map<std::string, bodies::BodyVector*> >& link_att_objects = cm->getLinkAttachedObjects(); 00242 00243 if(link_att_objects.empty()) { 00244 cm->bodiesUnlock(); 00245 return; 00246 } 00247 00248 //this gets all the attached bodies in their correct current positions according to tf 00249 geometry_msgs::PoseStamped ps; 00250 ps.pose.orientation.w = 1.0; 00251 for(std::map<std::string, std::map<std::string, bodies::BodyVector*> >::const_iterator it = link_att_objects.begin(); 00252 it != link_att_objects.end(); 00253 it++) { 00254 ps.header.frame_id = it->first; 00255 std::string es; 00256 if (tf.getLatestCommonTime(cm->getWorldFrameId(), it->first, ps.header.stamp, &es) != tf::NO_ERROR) { 00257 ROS_INFO_STREAM("Problem transforming into fixed frame from " << it->first << ". Error string " << es); 00258 continue; 00259 } 00260 geometry_msgs::PoseStamped psout; 00261 tf.transformPose(cm->getWorldFrameId(), ps, psout); 00262 btTransform link_trans; 00263 tf::poseMsgToTF(psout.pose, link_trans); 00264 state.updateKinematicStateWithLinkAt(it->first, link_trans); 00265 cm->updateAttachedBodyPosesForLink(state, it->first); 00266 } 00267 cm->bodiesUnlock(); 00268 } 00269 00270 //assumes that the point is in the world frame 00271 //and that state has been set 00272 int planning_environment::computeAttachedObjectPointMask(const planning_environment::CollisionModels* cm, 00273 const btVector3 &pt, 00274 const btVector3 &sensor_pos) 00275 { 00276 cm->bodiesLock(); 00277 const std::map<std::string, std::map<std::string, bodies::BodyVector*> > link_att_objects = cm->getLinkAttachedObjects(); 00278 00279 btVector3 dir(sensor_pos - pt); 00280 dir.normalize(); 00281 00282 for(std::map<std::string, std::map<std::string, bodies::BodyVector*> >::const_iterator it = link_att_objects.begin(); 00283 it != link_att_objects.end(); 00284 it++) { 00285 for(std::map<std::string, bodies::BodyVector*>::const_iterator it2 = it->second.begin(); 00286 it2 != it->second.end(); 00287 it2++) { 00288 for(unsigned int k = 0; k < it2->second->getSize(); k++) { 00289 //ROS_INFO_STREAM("Sphere distance " << it2->second->getBoundingSphere(k).center.distance2(pt) 00290 // << " squared " << it2->second->getBoundingSphereRadiusSquared(k)); 00291 if(it2->second->getPaddedBoundingSphere(k).center.distance2(pt) < it2->second->getPaddedBoundingSphereRadiusSquared(k)) { 00292 if(it2->second->getPaddedBody(k)->containsPoint(pt)) { 00293 cm->bodiesUnlock(); 00294 return robot_self_filter::INSIDE; 00295 } 00296 } 00297 if(it2->second->getPaddedBody(k)->intersectsRay(pt, dir)) { 00298 cm->bodiesUnlock(); 00299 return robot_self_filter::SHADOW; 00300 } 00301 } 00302 } 00303 } 00304 cm->bodiesUnlock(); 00305 return robot_self_filter::OUTSIDE; 00306 } 00307 00308 bool planning_environment::configureForAttachedBodyMask(planning_models::KinematicState& state, 00309 planning_environment::CollisionModels* cm, 00310 tf::TransformListener& tf, 00311 const std::string& sensor_frame, 00312 const ros::Time& sensor_time, 00313 btVector3& sensor_pos) 00314 { 00315 state.setKinematicStateToDefault(); 00316 00317 cm->bodiesLock(); 00318 00319 const std::map<std::string, std::map<std::string, bodies::BodyVector*> >& link_att_objects = cm->getLinkAttachedObjects(); 00320 00321 if(link_att_objects.empty()) { 00322 cm->bodiesUnlock(); 00323 return false; 00324 } 00325 00326 planning_environment::updateAttachedObjectBodyPoses(cm, 00327 state, 00328 tf); 00329 00330 sensor_pos.setValue(0.0,0.0,0.0); 00331 00332 // compute the origin of the sensor in the frame of the cloud 00333 if (!sensor_frame.empty()) { 00334 std::string err; 00335 try { 00336 tf::StampedTransform transf; 00337 tf.lookupTransform(cm->getWorldFrameId(), sensor_frame, sensor_time, transf); 00338 sensor_pos = transf.getOrigin(); 00339 } catch(tf::TransformException& ex) { 00340 ROS_ERROR("Unable to lookup transform from %s to %s. Exception: %s", sensor_frame.c_str(), cm->getWorldFrameId().c_str(), ex.what()); 00341 sensor_pos.setValue(0, 0, 0); 00342 } 00343 } 00344 cm->bodiesUnlock(); 00345 return true; 00346 } 00347 00348 bool planning_environment::computeAttachedObjectPointCloudMask(const pcl::PointCloud<pcl::PointXYZ>& pcl_cloud, 00349 const std::string& sensor_frame, 00350 planning_environment::CollisionModels* cm, 00351 tf::TransformListener& tf, 00352 std::vector<int> &mask) 00353 { 00354 00355 // compute mask for cloud 00356 int n = pcl_cloud.points.size(); 00357 mask.resize(n, robot_self_filter::OUTSIDE); 00358 00359 //state lock before body lock 00360 planning_models::KinematicState state(cm->getKinematicModel()); 00361 00362 btVector3 sensor_pos; 00363 00364 planning_environment::configureForAttachedBodyMask(state, 00365 cm, 00366 tf, 00367 sensor_frame, 00368 pcl_cloud.header.stamp, 00369 sensor_pos); 00370 00371 // transform pointcloud into fixed frame, if needed 00372 if (cm->getWorldFrameId() != pcl_cloud.header.frame_id) { 00373 pcl::PointCloud<pcl::PointXYZ> trans_cloud = pcl_cloud; 00374 pcl_ros::transformPointCloud(cm->getWorldFrameId(), pcl_cloud, trans_cloud,tf); 00375 for (int i = 0 ; i < n ; ++i) { 00376 btVector3 pt = btVector3(trans_cloud.points[i].x, trans_cloud.points[i].y, trans_cloud.points[i].z); 00377 mask[i] = computeAttachedObjectPointMask(cm, pt, sensor_pos); 00378 } 00379 } else { 00380 for (int i = 0 ; i < n ; ++i) { 00381 btVector3 pt = btVector3(pcl_cloud.points[i].x, pcl_cloud.points[i].y, pcl_cloud.points[i].z); 00382 mask[i] = computeAttachedObjectPointMask(cm, pt, sensor_pos); 00383 } 00384 } 00385 return true; 00386 } 00387 00388 int planning_environment::closestStateOnTrajectory(const boost::shared_ptr<urdf::Model> &model, 00389 const trajectory_msgs::JointTrajectory &trajectory, 00390 const sensor_msgs::JointState &joint_state, 00391 unsigned int start, 00392 unsigned int end) 00393 { 00394 double dist = 0.0; 00395 int pos = -1; 00396 00397 std::map<std::string, double> current_state_map; 00398 std::map<std::string, bool> continuous; 00399 for(unsigned int i = 0; i < joint_state.name.size(); i++) { 00400 current_state_map[joint_state.name[i]] = joint_state.position[i]; 00401 } 00402 00403 for(unsigned int j = 0; j < trajectory.joint_names.size(); j++) { 00404 std::string name = trajectory.joint_names[j]; 00405 boost::shared_ptr<const urdf::Joint> joint = model->getJoint(name); 00406 if (joint.get() == NULL) 00407 { 00408 ROS_ERROR("Joint name %s not found in urdf model", name.c_str()); 00409 return false; 00410 } 00411 if (joint->type == urdf::Joint::CONTINUOUS) { 00412 continuous[name] = true; 00413 } else { 00414 continuous[name] = false; 00415 } 00416 00417 } 00418 00419 for (unsigned int i = start ; i <= end ; ++i) 00420 { 00421 double d = 0.0; 00422 for(unsigned int j = 0; j < trajectory.joint_names.size(); j++) { 00423 double diff; 00424 if(!continuous[trajectory.joint_names[j]]) { 00425 diff = fabs(trajectory.points[i].positions[j] - current_state_map[trajectory.joint_names[j]]); 00426 } else { 00427 diff = angles::shortest_angular_distance(trajectory.points[i].positions[j],current_state_map[trajectory.joint_names[j]]); 00428 } 00429 d += diff * diff; 00430 } 00431 00432 if (pos < 0 || d < dist) 00433 { 00434 pos = i; 00435 dist = d; 00436 } 00437 } 00438 00439 // if(pos == 0) { 00440 // for(unsigned int i = 0; i < joint_state.name.size(); i++) { 00441 // ROS_INFO_STREAM("Current state for joint " << joint_state.name[i] << " is " << joint_state.position[i]); 00442 // } 00443 // for(unsigned int j = 0; j < trajectory.joint_names.size(); j++) { 00444 // ROS_INFO_STREAM("Trajectory zero has " << trajectory.points[0].positions[j] << " for joint " << trajectory.joint_names[j]); 00445 // } 00446 // } 00447 00448 return pos; 00449 } 00450 00451 bool planning_environment::removeCompletedTrajectory(const boost::shared_ptr<urdf::Model> &model, 00452 const trajectory_msgs::JointTrajectory &trajectory_in, 00453 const sensor_msgs::JointState& current_state, 00454 trajectory_msgs::JointTrajectory &trajectory_out, 00455 bool zero_vel_acc) 00456 { 00457 00458 trajectory_out = trajectory_in; 00459 trajectory_out.points.clear(); 00460 00461 if(trajectory_in.points.empty()) 00462 { 00463 ROS_WARN("No points in input trajectory"); 00464 return true; 00465 } 00466 00467 int current_position_index = 0; 00468 //Get closest state in given trajectory 00469 current_position_index = closestStateOnTrajectory(model, 00470 trajectory_in, 00471 current_state, 00472 current_position_index, 00473 trajectory_in.points.size() - 1); 00474 if (current_position_index < 0) 00475 { 00476 ROS_ERROR("Unable to identify current state in trajectory"); 00477 return false; 00478 } else { 00479 ROS_DEBUG_STREAM("Closest state is " << current_position_index << " of " << trajectory_in.points.size()); 00480 } 00481 00482 // Start one ahead of returned closest state index to make sure first trajectory point is not behind current state 00483 for(unsigned int i = current_position_index+1; i < trajectory_in.points.size(); ++i) 00484 { 00485 trajectory_out.points.push_back(trajectory_in.points[i]); 00486 } 00487 00488 if(trajectory_out.points.empty()) 00489 { 00490 ROS_DEBUG("No points in output trajectory"); 00491 return false; 00492 } 00493 00494 ros::Duration first_time = trajectory_out.points[0].time_from_start; 00495 00496 if(first_time < ros::Duration(.1)) { 00497 first_time = ros::Duration(0.0); 00498 } else { 00499 first_time -= ros::Duration(.1); 00500 } 00501 00502 for(unsigned int i=0; i < trajectory_out.points.size(); ++i) 00503 { 00504 if(trajectory_out.points[i].time_from_start > first_time) { 00505 trajectory_out.points[i].time_from_start -= first_time; 00506 } else { 00507 ROS_INFO_STREAM("Not enough time in time from start for trajectory point " << i); 00508 } 00509 } 00510 00511 if(zero_vel_acc) { 00512 for(unsigned int i=0; i < trajectory_out.joint_names.size(); ++i) { 00513 for(unsigned int j=0; j < trajectory_out.points.size(); ++j) { 00514 trajectory_out.points[j].velocities[i] = 0; 00515 trajectory_out.points[j].accelerations[i] = 0; 00516 } 00517 } 00518 } 00519 return true; 00520 } 00521