Go to the documentation of this file.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
00037
00046 #include <Eigen/Core>
00047 #include <Eigen/LU>
00048 #include <Eigen/Geometry>
00049
00050 #include <boost/filesystem.hpp>
00051 #include <boost/thread.hpp>
00052 #include <boost/make_shared.hpp>
00053 #include <ros/ros.h>
00054 #include <ros/callback_queue.h>
00055 #include <nav_msgs/Odometry.h>
00056 #include <tf/tfMessage.h>
00057 #include <roslib/Clock.h>
00058
00059 #include <image_transport/image_transport.h>
00060 #include <image_transport/subscriber_filter.h>
00061 #include <message_filters/subscriber.h>
00062 #include <message_filters/time_synchronizer.h>
00063
00064 #include <model_database/postgresql_model_database.h>
00065 #include <model_database/database_original_model.h>
00066
00067 #include <gazebo_plugins/DeleteModel.h>
00068 #include <gazebo_plugins/SpawnModel.h>
00069 #include <gazebo_plugins/SetPose.h>
00070
00071 using namespace std;
00072 using namespace boost;
00073 using namespace ros;
00074 using namespace roslib;
00075 using namespace tf;
00076 using namespace sensor_msgs;
00077 using namespace nav_msgs;
00078 using namespace image_transport;
00079 using namespace model_database;
00080 using namespace gazebo_plugins;
00081
00082 class ObjectDataAcquisitionGazebo
00083 {
00084 private:
00085
00086 NodeHandle nh_;
00087 ServiceClient gazebo_model_remove_serv_, gazebo_model_spawn_serv_, gazebo_camera_set_pose_serv_;
00088 CallbackQueue tf_queue_, clock_queue_;
00089 thread tf_thread_, clock_thread_;
00090 mutex m_mutex_;
00091
00092
00093 shared_ptr<PostgresqlModelDatabase> database_;
00094 std::string model_dae_path_;
00095
00096
00097 string t_camera_base_, t_ptu_base_, t_pan_tilt_, t_image_raw_l_, t_image_raw_r_, t_cam_info_l_, t_cam_info_r_;
00098
00099
00100 string output_file_;
00101
00102 double scale_factor_;
00103 bool log_file_open_, init_failed_, alternate_mode_, artificial_texture_, alternate_artificial_texture_;
00104
00105
00106 public:
00108 ObjectDataAcquisitionGazebo (int texture, int model_id) : nh_ ("~"),
00109 log_file_open_ (false),
00110 init_failed_ (false), alternate_mode_ (false),
00111 artificial_texture_ (true),
00112 alternate_artificial_texture_ (false)
00113 {
00114
00115 switch (texture)
00116 {
00117 case 0: artificial_texture_ = false; break;
00118 case 1: artificial_texture_ = true; break;
00119 case 2: alternate_artificial_texture_ = true; alternate_mode_ = true; break;
00120 }
00121
00122 nh_.param ("scale_factor", scale_factor_, 1.0);
00123 if (scale_factor_ != 1.0)
00124 ROS_INFO ("Using a scale factor of %f.", scale_factor_);
00125
00126 tf_thread_ = thread (bind (&ObjectDataAcquisitionGazebo::tfThread, this));
00127 clock_thread_ = thread (bind (&ObjectDataAcquisitionGazebo::clockThread, this));
00128
00129
00130 gazebo_model_remove_serv_ = nh_.serviceClient<DeleteModel>("/delete_model");
00131 gazebo_model_spawn_serv_ = nh_.serviceClient<SpawnModel>("/spawn_model");
00132 gazebo_camera_set_pose_serv_ = nh_.serviceClient<SetPose>("/set_pr2_pose");
00133
00134 gazebo_model_remove_serv_.waitForExistence();
00135 gazebo_model_spawn_serv_.waitForExistence();
00136
00137
00138 database_ = make_shared<PostgresqlModelDatabase> ("wgs36", "5432", "willow", "willow", "models");
00139 if (!database_->isConnected ())
00140 {
00141 ROS_ERROR ("Failed to connect to database");
00142 init_failed_ = true;
00143 return;
00144 }
00145 std::string root_path;
00146 if (!database_->getModelRoot (root_path))
00147 {
00148 ROS_ERROR ("Failed to get root path from database");
00149 init_failed_ = true;
00150 return;
00151 }
00152 model_database::DatabaseOriginalModel db_model;
00153 db_model.id_.get() = model_id;
00154
00155 if (! database_->loadFromDatabase(&db_model.model_) || db_model.model_.get().empty())
00156 {
00157 ROS_ERROR("Model with id %d not found in database", model_id);
00158 init_failed_ = true;
00159 return;
00160 }
00161
00162 if (! database_->loadFromDatabase(&db_model.geometry_path_dae_) || db_model.geometry_path_dae_.get().empty())
00163 {
00164 ROS_ERROR("Model with id %d does not have a .dae geometry path", model_id);
00165 init_failed_ = true;
00166 return;
00167 }
00168
00169 model_dae_path_ = root_path + db_model.geometry_path_dae_.get();
00170 if (!boost::filesystem::exists (model_dae_path_))
00171 {
00172 ROS_ERROR("DAE file %s not found", model_dae_path_.c_str());
00173 init_failed_ = true;
00174 return;
00175 }
00176 ROS_INFO("Using dae file %s", model_dae_path_.c_str());
00177
00178 if (artificial_texture_)
00179 ROS_INFO ("Artificial texture enabled.");
00180 else
00181 ROS_INFO ("Using the objects' original texture.");
00182
00183 }
00184
00186 void
00187 clockThread ()
00188 {
00189 static const double timeout = 0.01;
00190 while (nh_.ok ())
00191 clock_queue_.callAvailable (WallDuration (timeout));
00192 }
00193
00195 void
00196 tfThread ()
00197 {
00198 static const double timeout = 0.01;
00199 while (nh_.ok ())
00200 tf_queue_.callAvailable (WallDuration (timeout));
00201 }
00202
00204 virtual ~ObjectDataAcquisitionGazebo ()
00205 {
00206
00207 tf_queue_.clear (); tf_queue_.disable ();
00208 clock_queue_.clear (); clock_queue_.disable ();
00209
00210 requestShutdown ();
00211
00212 tf_thread_.join ();
00213 clock_thread_.join ();
00214
00215 if (init_failed_)
00216 return;
00217 }
00218
00220
00224 string
00225 assembleModelGazebo (string model_path, bool artificial_texture)
00226 {
00227 string model =
00228 "<?xml version=\"1.0\" ?>\n"
00229 "<model:physical name=\"object_1\">\n"
00230 "<xyz> 0.0 0.0 0.0</xyz>\n"
00231 "<rpy> 0.0 0.0 0.0</rpy>\n"
00232 "<static>false</static>\n"
00233 "<body:trimesh name=\"object_body\">\n"
00234 " <turnGravityOff>false</turnGravityOff>\n"
00235 " <massMatrix>true</massMatrix>\n"
00236 " <mass>1.0</mass>\n"
00237 " <ixx>0.1</ixx>\n"
00238 " <ixy>0.0</ixy>\n"
00239 " <ixz>0.0</ixz>\n"
00240 " <iyy>0.1</iyy>\n"
00241 " <iyz>0.0</iyz>\n"
00242 " <izz>0.1</izz>\n"
00243 " <cx>0.0</cx>\n"
00244 " <cy>0.0</cy>\n"
00245 " <cz>0.05</cz>\n"
00246 " <geom:trimesh name=\"object_geom\">\n"
00247 " <xyz>0 0 0</xyz>\n"
00248 " <laserRetro>2000.0</laserRetro>\n"
00249 " <kp>100000000.0</kp>\n"
00250 " <kd>1.0</kd>\n"
00251 " <scale>0.001 0.001 0.001</scale>\n"
00252 " <mesh>"+ model_path + "</mesh>\n"
00253 " <visual>\n"
00254 " <xyz>0 0 0</xyz>\n"
00255 " <scale>0.001 0.001 0.001</scale>\n";
00256 if (artificial_texture)
00257 model += string (" <material>GazeboWorlds/RGBNoise</material>\n");
00258 model += string (
00259 " <mesh>"+ model_path + "</mesh>\n"
00260 " </visual>\n"
00261 " </geom:trimesh>\n"
00262 "</body:trimesh>\n"
00263 "</model:physical>");
00264 return (model);
00265 }
00266
00268 void
00269 spin ()
00270 {
00271 if (init_failed_) return;
00272
00273
00274 DeleteModel dm; dm.request.model_name = "object_1";
00275 gazebo_model_remove_serv_.call (dm);
00276
00277
00278 string gazebo_model = assembleModelGazebo (model_dae_path_, artificial_texture_);
00279
00280
00281 SpawnModel sm;
00282 sm.request.model.model_name = "object_1";
00283 sm.request.model.robot_model = gazebo_model;
00284 sm.request.model.xml_type = 1; sm.request.model.robot_namespace = "/";
00285 sm.request.model.initial_pose.position.x = .7;
00286 sm.request.model.initial_pose.position.z = 0.55;
00287 gazebo_model_spawn_serv_.call (sm);
00288 ROS_INFO ("wait...");
00289 usleep(1000000);
00290 }
00291 };
00292
00293
00294 int
00295 main (int argc, char** argv)
00296 {
00297 ROS_INFO("Syntax is: %s model_id [artificial_texture = 0/1/2 "
00298 "(0 = disabled, use the real object texture / 1 = enabled* / 2 = alternate mode, save both)] ", argv[0]);
00299
00300
00301 int model_i;
00302 if (argc > 1) model_i = atoi (argv[1]);
00303 else
00304 {
00305 ROS_ERROR("Can not spawn database object: model_id not specified");
00306 return (0);
00307 }
00308
00309 int param = 1;
00310 if (argc > 2) param = atoi (argv[2]);
00311
00312
00313 init (argc, argv, "object_data_acquisition_gazebo");
00314
00315 ObjectDataAcquisitionGazebo p (param, model_i);
00316 p.spin ();
00317
00318 return (0);
00319 }
00320