$search
00001 /* 00002 * Copyright (c) 2009 Radu Bogdan Rusu <rusu -=- cs.tum.edu> 00003 * 00004 * All rights reserved. 00005 * 00006 * Redistribution and use in source and binary forms, with or without 00007 * modification, are permitted provided that the following conditions are met: 00008 * 00009 * * Redistributions of source code must retain the above copyright 00010 * notice, this list of conditions and the following disclaimer. 00011 * * Redistributions in binary form must reproduce the above copyright 00012 * notice, this list of conditions and the following disclaimer in the 00013 * documentation and/or other materials provided with the distribution. 00014 * 00015 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00016 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00017 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00018 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00019 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00020 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00021 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00022 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00023 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00024 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00025 * POSSIBILITY OF SUCH DAMAGE. 00026 * 00027 * $Id: rotating_unit.cpp 90 2009-08-24 09:44:53Z veedee $ 00028 * 00029 */ 00030 00042 // ROS core 00043 #include <ros/ros.h> 00044 // ROS messages 00045 #include <sensor_msgs/PointCloud.h> 00046 #include <sensor_msgs/LaserScan.h> 00047 #include <geometry_msgs/Point32.h> 00048 #include <boost/algorithm/string.hpp> 00049 #include <boost/thread/mutex.hpp> 00050 #include <Eigen/Core> 00051 #include <point_cloud_mapping/geometry/nearest.h> 00052 00053 #include <mapping_srvs/RotatePTU.h> 00054 #include <mapping_srvs/TriggerSweep.h> 00055 #include <perception_srvs/David.h> 00056 using namespace std; 00057 using namespace ros; 00058 using namespace sensor_msgs; 00059 using namespace geometry_msgs; 00060 00061 #define ANGLE -180.0 00062 #define S_ANGLE -180.0 00063 00064 class RotatingDPPTU 00065 { 00066 protected: 00067 NodeHandle nh_; 00068 boost::mutex s_lock_, a_lock_; 00069 bool david_connect_, spin_; 00070 int total_laser_scans_; 00071 public: 00072 // ROS messages 00073 list<LaserScanConstPtr> scans_; 00074 double first_act_stamp_; 00075 00076 PointCloud cloud_; 00077 00078 Publisher cloud_pub_; 00079 00080 ServiceClient ptu_serv_, scan_serv_, david_scan_, save_images_serv_; 00081 00082 // Parameters 00083 double min_distance_, max_distance_, laser_min_angle_, laser_max_angle_; 00084 double angle_step_; 00085 string object_; 00086 bool left_arm_; 00087 //do we use david 00088 int is_david_; 00089 //do we want to rotate with PTU 00090 int is_ptu_; 00091 //do we want to take snapshots 00092 int is_image_; 00093 //do we sweep with laser (e.g. LMS400) 00094 int is_laser_; 00095 //how many times do we sweep the laser 00096 int sweeps_; 00097 00099 RotatingDPPTU () : total_laser_scans_ (0), 00100 left_arm_ (true) 00101 { 00102 david_connect_ = true, spin_ = true; 00103 nh_.param ("~min_distance", min_distance_, .7); // minimum distance range to be considered 00104 nh_.param ("~max_distance", max_distance_, 3.01); // maximum distance range to be considered 00105 nh_.param ("~angle_step", angle_step_, 30.0); // ptu rotating angle 00106 nh_.param ("~object", object_, string("mug")); // name of object to be scanned 00107 nh_.param ("~sweeps", sweeps_, 1); // number of sweeps of the laser arm per scan 00108 nh_.param ("~is_ptu", is_ptu_, 0); 00109 nh_.param ("~is_image", is_image_, 0); 00110 nh_.param ("~is_laser", is_laser_, 0); 00111 nh_.param("~is_david", is_david_, 0); 00112 00113 cloud_pub_ = nh_.advertise<PointCloud> ("/tilt_laser_cloud", 1); 00114 00115 ptu_serv_ = nh_.serviceClient<mapping_srvs::RotatePTU>("get_angle_service"); 00116 scan_serv_ = nh_.serviceClient<mapping_srvs::TriggerSweep>("amtec_sweep"); 00117 david_scan_ = nh_.serviceClient<perception_srvs::David>("david"); 00118 save_images_serv_ = nh_.serviceClient<mapping_srvs::TriggerSweep>("save_images_service"); 00119 } 00120 00122 virtual ~RotatingDPPTU () { } 00123 00124 00126 Eigen::Matrix3f 00127 assembleRotationMatrixZ (float angle) 00128 { 00129 double cz = cos (angle), sz = sin (angle); 00130 Eigen::Matrix3f rot_mat; 00131 rot_mat << 00132 cz, -sz, 0, 00133 sz, cz, 0, 00134 0 , 0, 1; 00135 return (rot_mat); 00136 } 00137 00139 // Rotate a PointCloud relative to the angle of the turning table 00140 void 00141 rotateCloudRelative (float relative_angle, const PointCloud &cloud_in, PointCloud &cloud_out) 00142 { 00143 cloud_out.header = cloud_in.header; 00144 cloud_out.channels = cloud_in.channels; 00145 cloud_out.points.resize (cloud_in.points.size ()); 00146 00147 // Demean the point cloud 00148 Point32 centroid; 00149 cloud_geometry::nearest::computeCentroid (cloud_in, centroid); 00150 00151 // Rotate it around Z with the given angle 00152 Eigen::Matrix3f rot_mat = assembleRotationMatrixZ (relative_angle); 00153 00154 for (unsigned int i = 0; i < cloud_in.points.size (); i++) 00155 { 00156 double cx = cloud_in.points[i].x - centroid.x; 00157 double cy = cloud_in.points[i].y - centroid.y; 00158 double cz = cloud_in.points[i].z - centroid.z; 00159 00160 cloud_out.points[i].x = rot_mat (0, 0) * cx + rot_mat (0, 1) * cy + rot_mat (0, 2) * cz; 00161 cloud_out.points[i].y = rot_mat (1, 0) * cx + rot_mat (1, 1) * cy + rot_mat (1, 2) * cz; 00162 cloud_out.points[i].x = rot_mat (2, 0) * cx + rot_mat (2, 1) * cy + rot_mat (2, 2) * cz; 00163 } 00164 } 00165 00166 00168 bool 00169 spin () 00170 { 00171 //update parameters on the fly 00172 00173 00174 float s_angle = S_ANGLE, angle = ANGLE; //roslaunch takes double only 00175 mapping_srvs::RotatePTU p_s; 00176 mapping_srvs::TriggerSweep s_s; 00177 mapping_srvs::TriggerSweep i_s; 00178 perception_srvs::David d_s; 00179 ros::Duration tictoc (1, 0); 00180 ros::Duration wait_grab_texture (3, 0); 00181 ros::Duration david_wait (0.1); 00182 ros::Rate loop_rate(5); 00183 PointCloud cloud_r; 00184 bool home; 00185 home = true; 00186 00187 while (nh_.ok ()) 00188 { 00189 update_parameters_from_server(); 00190 ROS_INFO("is_image %d", is_image_); 00191 ROS_INFO("is_laser %d", is_laser_); 00192 if(spin_) 00193 { 00194 ROS_INFO("New Spin----------------------------------------------"); 00195 ROS_INFO("------------------------------------------------------"); 00196 ROS_INFO("------------------------------------------------------"); 00197 //send PTU to 0 position 00198 // if (home) 00199 // { 00200 // p_s.request.angle = 30.0; 00201 // ptu_serv_.call (p_s); 00202 // ROS_INFO ("Homing ____PTU______ "); 00203 // tictoc.sleep (); 00204 // home = false; 00205 // } 00206 // Send a request to the PTU to move 00207 if (is_ptu_) 00208 { 00209 p_s.request.angle = angle; 00210 ROS_INFO ("Setting ____PTU______ angle to %f. Sleeping for %f seconds.", angle, tictoc.toSec ()); 00211 ptu_serv_.call (p_s); 00212 tictoc.sleep (); 00213 } 00214 00215 if (is_david_) 00216 { 00217 //ROS_WARN("In is_david"); 00218 // Start david scanning system 00219 if(david_connect_){ 00220 ROS_WARN("Connecting to DAVID server"); 00221 //connect only once per node cycle 00222 d_s.request.david_method = "connect"; 00223 david_connect_ = false; 00224 } 00225 david_scan_.call(d_s); 00226 david_wait.sleep(); 00227 d_s.request.david_method = "erase"; 00228 david_scan_.call(d_s); 00229 david_wait.sleep(); 00230 d_s.request.david_method = "eraseTexture"; 00231 david_scan_.call(d_s); 00232 david_wait.sleep(); 00233 d_s.request.david_method = "start"; 00234 david_scan_.call(d_s); 00235 ROS_INFO ("David started. Sleeping for %f seconds.", tictoc.toSec ()); 00236 tictoc.sleep(); 00237 } 00238 // Trigger the LMS400 to sweep 00239 // or 00240 // only rotate one joint if scanning with David system 00241 if (is_laser_) 00242 { 00243 tictoc.sleep (); 00244 for (int i = 0; i < sweeps_; i++) 00245 { 00246 s_s.request.object = object_; 00247 s_s.request.angle_filename = angle; 00248 scan_serv_.call (s_s); 00249 ROS_INFO ("___Sweeping___ %d times. Setting angle to %f, object to %s. ", i, angle, object_.c_str()); 00250 } 00251 } 00252 // Rotate the point cloud and publish it 00253 //rotateCloudRelative (angle - s_angle, s_s.response.cloud, cloud_r); 00254 00255 // if (cloud_r.points.size () > 0) 00256 // { 00257 // cloud_pub_.publish (cloud_r); 00258 // ROS_INFO ("Publishing cloud with %d points and %d channels on topic %s.", 00259 // (int)cloud_r.points.size (), (int)cloud_r.channels.size (), cloud_r.header.frame_id.c_str ()); 00260 // } 00261 00262 // Stop David system 00263 if (is_david_) 00264 { 00265 d_s.request.david_method = "stop"; 00266 david_scan_.call(d_s); 00267 david_wait.sleep(); 00268 d_s.request.david_method = "grabTexture"; 00269 david_scan_.call(d_s); 00270 david_wait.sleep(); 00271 //david save name 00272 char angle_tmp[100]; 00273 int angle_int = round(angle); 00274 sprintf (angle_tmp, "%d", angle_int); 00275 string david_save = "save_" + object_ + "_" + string(angle_tmp) + "_" + ".obj"; 00276 ROS_INFO("Saving David scan to %s", david_save.c_str()); 00277 d_s.request.david_method = david_save; 00278 david_scan_.call(d_s); 00279 ROS_INFO("Sleeping for %f seconds.", wait_grab_texture.toSec ()); 00280 wait_grab_texture.sleep(); 00281 //added temporarily to avoid save being called twice 00282 d_s.request.david_method = "erase"; 00283 david_scan_.call(d_s); 00284 ROS_INFO ("David stopped. Sleeping for %f seconds.", tictoc.toSec ()); 00285 tictoc.sleep(); 00286 } 00287 00288 if (is_image_) 00289 { 00290 i_s.request.object = object_; 00291 i_s.request.angle_filename = angle; 00292 ROS_INFO ("Capturing Images!"); 00293 save_images_serv_.call (i_s); 00294 tictoc.sleep (); 00295 } 00296 // Increase angle and repeat 00297 angle += angle_step_; 00298 if (angle > 180.0) 00299 { 00300 spin_ = false; 00301 s_angle = S_ANGLE, angle = ANGLE; 00302 home = true; 00303 //break; 00304 } 00305 } 00306 ROS_WARN("Looping!!!!"); 00307 ros::spinOnce (); 00308 if(!spin_) 00309 loop_rate.sleep(); 00310 } 00311 00312 ROS_INFO ("Another Scanning completed."); 00313 return (true); 00314 } 00315 00317 // //update parameters on the fly 00319 void 00320 update_parameters_from_server() 00321 { 00322 if (nh_.hasParam("~object")) 00323 { 00324 string object_tmp_ = object_; 00325 nh_.getParam("~object", object_); 00326 if (object_tmp_ != object_) 00327 { 00328 spin_ = true; 00329 } 00330 ROS_INFO("Updating parameters from server"); 00331 } 00332 } 00333 00334 }; 00335 00336 /* ---[ */ 00337 int 00338 main (int argc, char** argv) 00339 { 00340 init (argc, argv, "rotating_dp_ptu"); 00341 00342 RotatingDPPTU p; 00343 p.spin (); 00344 00345 return (0); 00346 } 00347 /* ]--- */