00001 #include <interactive_world_parser/interactive_world_parser.hpp>
00002 #include <geometry_msgs/Point.h>
00003 #include <fstream>
00004 #include <pwd.h>
00005
00006 using namespace std;
00007
00008 interactive_world_parser::interactive_world_parser() :
00009 private_("~")
00010 {
00011
00012 private_.param("host", host_, string(RMS_DEFAULT_SERVER));
00013 private_.param("port", port_, RMS_DEFAULT_PORT);
00014 private_.param("user", user_, string(RMS_DEFAULT_USER));
00015 private_.param("password", password_, string(RMS_DEFAULT_PASSWORD));
00016 private_.param("database", database_, string(RMS_DEFAULT_DATABASE));
00017 private_.param("study_id", study_id_, DEFAULT_STUDY_ID);
00018
00019
00020 client_ = new librms::rms(host_, (unsigned int) port_, user_, password_, database_);
00021
00022
00023 if (!client_->connect())
00024 {
00025 ROS_ERROR("Fatal: could not connect to the RMS database.");
00026 exit(EXIT_FAILURE);
00027 }
00028
00029
00030 parse_and_store_ = private_.advertiseService("parse_and_store", &interactive_world_parser::parse_and_store_cb, this);
00031 parse_and_save_ = private_.advertiseService("parse_and_save", &interactive_world_parser::parse_and_save_cb, this);
00032
00033
00034 learn_hypotheses_ = private_.serviceClient<interactive_world_msgs::LearnModels>("/interactive_world_learner/learn_hypotheses");
00035 ROS_INFO("Waiting for /interactive_world_learner/learn_hypotheses...");
00036 learn_hypotheses_.waitForExistence(ros::DURATION_MAX);
00037
00038 ROS_INFO("Interactive World Parser Initialized");
00039 }
00040
00041
00042 interactive_world_parser::~interactive_world_parser()
00043 {
00044 delete client_;
00045 }
00046
00047 static int __limit__ = 0;
00048
00049 static bool cond(const interactive_world_msgs::PlacementSet &set)
00050 {
00051 return set.placements.size() < __limit__;
00052 }
00053
00054
00055 void interactive_world_parser::parse()
00056 {
00057 ROS_INFO("=== BEGINING PARSE ===");
00058 data_.clear();
00059 librms::study study = client_->get_study((unsigned int) study_id_);
00060 ROS_INFO("Running over study \"%s\"...", study.get_name().c_str());
00061
00062
00063 vector<librms::condition> &conditions = study.get_conditions();
00064 ROS_INFO("+ Found %d conditions.", (int) conditions.size());
00065 for (uint i = 0; i < conditions.size(); i++)
00066 {
00067 librms::condition &condition = conditions[i];
00068 ROS_INFO("+ Parsing condition \"%s\"...", condition.get_name().c_str());
00069 int num_experiments = 0;
00070 int num_completed = 0;
00071 int num_placements = 0;
00072
00073 vector<librms::slot> &slots = condition.get_slots();
00074 for (uint j = 0; j < slots.size(); j++)
00075 {
00076 ROS_INFO("++ Parsing slot %d/%d...", j + 1, (int) slots.size());
00077 librms::slot &slot = slots[j];
00078 if (slot.has_appointment())
00079 {
00080
00081 librms::appointment &appointment = slot.get_appointment();
00082 vector<librms::log> &logs = appointment.get_logs();
00083 if (logs.size() > 1)
00084 {
00085 bool completion = false;
00086 num_experiments++;
00087 interactive_world_msgs::Configuration config;
00088 for (uint k = 0; k < logs.size(); k++)
00089 {
00090 librms::log &log = logs[k];
00091
00092
00093 Json::Value json;
00094 Json::Reader reader;
00095 reader.parse(log.get_entry(), json, false);
00096
00097
00098 if (log.get_label().compare("config") == 0)
00099 {
00100 config = parse_json_config(json);
00101 } else if (log.get_label().compare("completion") == 0)
00102 {
00103 if (!completion)
00104 {
00105 completion = true;
00106 num_completed++;
00107 }
00108 } else
00109 {
00110
00111 num_placements++;
00112 parse_json_placement(json, config, condition.get_id(), logs);
00113 }
00114 }
00115 }
00116 }
00117 }
00118 ROS_INFO("++ %d/%d completed sessions with %d placements.", num_completed, num_experiments, num_placements);
00119 __limit__ = (int) (num_placements * 0.05);
00120 ROS_INFO("++ Removing data sets with less than %d placements...", __limit__);
00121 vector<interactive_world_msgs::PlacementSet> &v = data_[condition.get_id()].data;
00122 v.erase(remove_if(v.begin(), v.end(), cond), v.end());
00123 }
00124
00125 ROS_INFO("=== PARSE FINISHED ===");
00126 }
00127
00128 void interactive_world_parser::save()
00129 {
00130 ROS_INFO("Writing data...");
00131
00132 for (map<uint, interactive_world_msgs::TaskTrainingData>::iterator it = data_.begin(); it != data_.end(); ++it)
00133 {
00134 uint condition_id = it->first;
00135 interactive_world_msgs::TaskTrainingData &training = it->second;
00136 for (uint i = 0; i < training.data.size(); i++)
00137 {
00138 interactive_world_msgs::PlacementSet &placements = training.data[i];
00139 stringstream ss;
00140 ss << (getpwuid(getuid()))->pw_dir << "/" << condition_id << "-" << placements.item.name << "-in-" << placements.room.name << "-on-" << placements.surface.name << "-wrt-" << placements.reference_frame_id << ".csv";
00141 ofstream file;
00142 file.open(ss.str().c_str());
00143 for (uint j = 0; j < placements.placements.size(); j++)
00144 {
00145 interactive_world_msgs::Placement &placement = placements.placements[j];
00146 file << placement.position.x << "," << placement.position.y << "," << placement.position.z << "," << placement.rotation << endl;
00147 }
00148 file.close();
00149 }
00150 }
00151 ROS_INFO("Finished!");
00152 }
00153
00154 void interactive_world_parser::learn()
00155 {
00156 ROS_INFO("=== BEGINING MODEL LEARNING ===");
00157
00158 for (map<uint, interactive_world_msgs::TaskTrainingData>::iterator it = data_.begin(); it != data_.end(); ++it)
00159 {
00160 uint condition_id = it->first;
00161 interactive_world_msgs::TaskTrainingData &training = it->second;
00162 ROS_INFO("Sending condition %d data off to jinteractiveworld...", condition_id);
00163
00164 interactive_world_msgs::LearnModels srv;
00165 srv.request.host = host_;
00166 srv.request.port = port_;
00167 srv.request.user = user_;
00168 srv.request.password = password_;
00169 srv.request.database = database_;
00170 srv.request.condition_id = condition_id;
00171 srv.request.data = it->second;
00172 learn_hypotheses_.call(srv);
00173 ROS_INFO("Condition %d models learned.", condition_id);
00174 }
00175 ROS_INFO("=== MODEL LEARNING FINISHED ===");
00176 }
00177
00178 bool interactive_world_parser::parse_and_store_cb(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
00179 {
00180 this->parse();
00181 this->learn();
00182 return true;
00183 }
00184
00185
00186 bool interactive_world_parser::parse_and_save_cb(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
00187 {
00188 this->parse();
00189 this->save();
00190 return true;
00191 }
00192
00193
00194 interactive_world_msgs::Configuration interactive_world_parser::parse_json_config(Json::Value &config)
00195 {
00196 interactive_world_msgs::Configuration configuration;
00197
00198
00199 configuration.task = config["task"].asString();
00200
00201 Json::Value objects = config["objects"];
00202 for (uint i = 0; i < objects.size(); i++)
00203 {
00204 Json::Value cur_object = objects[i];
00205 interactive_world_msgs::Item item;
00206 item.name = cur_object["name"].asString();
00207 item.width = cur_object["width"].asDouble();
00208 item.height = cur_object["height"].asDouble();
00209 configuration.items.push_back(item);
00210 }
00211
00212 Json::Value rooms = config["rooms"];
00213 for (uint i = 0; i < rooms.size(); i++)
00214 {
00215 Json::Value cur_room = rooms[i];
00216 interactive_world_msgs::Room room;
00217 room.name = cur_room["name"].asString();
00218 room.width = cur_room["width"].asDouble();
00219 room.height = cur_room["height"].asDouble();
00220 room.pose = parse_json_pose(cur_room["position"], cur_room["rotation"].asDouble());
00221
00222 Json::Value surfaces = cur_room["furniture"];
00223 for (uint j = 0; j < surfaces.size(); j++)
00224 {
00225 Json::Value cur_surface = surfaces[j];
00226 interactive_world_msgs::Surface surface;
00227 surface.name = cur_surface["name"].asString();
00228 surface.width = cur_surface["width"].asDouble();
00229 surface.height = cur_surface["height"].asDouble();
00230 surface.pose = parse_json_pose(cur_surface["position"], cur_surface["rotation"].asDouble());
00231
00232 Json::Value pois = cur_surface["poi"];
00233 for (uint k = 0; k < pois.size(); k++)
00234 {
00235 Json::Value cur_poi = pois[k];
00236 interactive_world_msgs::PointOfInterest poi;
00237 poi.name = cur_poi["name"].asString();
00238 poi.width = cur_poi["width"].asDouble();
00239 poi.height = cur_poi["height"].asDouble();
00240 poi.pose = parse_json_pose(cur_poi["position"], cur_poi["rotation"].asDouble());
00241 surface.pois.push_back(poi);
00242 }
00243 room.surfaces.push_back(surface);
00244 }
00245 configuration.rooms.push_back(room);
00246 }
00247
00248 return configuration;
00249 }
00250
00251 void interactive_world_parser::parse_json_placement(Json::Value &placement, interactive_world_msgs::Configuration &config, unsigned int condition_id, vector<librms::log> logs)
00252 {
00253
00254 Json::Value json_furniture = placement["furniture"];
00255 Json::Value json_furniture_position = json_furniture["position"];
00256 Json::Value json_furniture_surface = json_furniture["surface"];
00257 Json::Value json_furniture_surface_position = json_furniture_surface["position"];
00258 Json::Value json_object = json_furniture_surface["object"];
00259 Json::Value json_object_position = json_object["position"];
00260
00261 string room_name = placement["name"].asString();
00262 string surface_name = json_furniture["name"].asString();
00263 string object_name = json_object["name"].asString();
00264
00265 interactive_world_msgs::Item item_msg;
00266 interactive_world_msgs::Room room_msg;
00267 interactive_world_msgs::Surface surface_msg;
00268
00269
00270 vector<interactive_world_msgs::PointOfInterest> pois;
00271 for (uint i = 0; i < config.rooms.size(); i++)
00272 {
00273 interactive_world_msgs::Room &room = config.rooms[i];
00274 if (room.name.compare(room_name) == 0)
00275 {
00276 room_msg = config.rooms[i];
00277 for (uint j = 0; j < room.surfaces.size(); j++)
00278 {
00279 interactive_world_msgs::Surface &surface = room.surfaces[j];
00280 if (surface.name.compare(surface_name) == 0)
00281 {
00282 surface_msg = room.surfaces[j];
00283 pois = surface.pois;
00284 break;
00285 }
00286 }
00287 break;
00288 }
00289 }
00290 for (uint i = 0; i < config.items.size(); i++)
00291 {
00292 interactive_world_msgs::Item &item = config.items[i];
00293 if (item.name.compare(object_name) == 0)
00294 {
00295 item_msg = config.items[i];
00296 break;
00297 }
00298 }
00299
00300
00301 tf2::Transform t_room_surface = parse_json_tf(json_furniture_position, json_furniture["rotation"].asDouble());
00302
00303
00304 tf2::Transform t_surface_psurface = parse_json_tf(json_furniture_surface_position, json_furniture_surface["rotation"].asDouble());
00305
00306
00307 tf2::Transform t_psurface_object = parse_json_tf(json_object_position, json_object["rotation"].asDouble());
00308
00309
00310 tf2::Transform t_surface_object = t_surface_psurface * t_psurface_object;
00311 tf2::Transform t_room_object = t_room_surface * t_surface_psurface * t_psurface_object;
00312
00313
00314 add_placement_to_data(condition_id, t_surface_object, item_msg, room_msg, surface_msg, surface_name);
00315
00316
00317 vector<string> used_names;
00318 for (uint i = 0; i < pois.size(); i++)
00319 {
00320
00321 string cur_poi_name = pois[i].name;
00322 if (find(used_names.begin(), used_names.end(), cur_poi_name) == used_names.end())
00323 {
00324 used_names.push_back(cur_poi_name);
00325
00326
00327 double closest_dist = numeric_limits<double>::infinity();
00328 tf2::Transform closest_t;
00329 for (uint j = 0; j < pois.size(); j++)
00330 {
00331 interactive_world_msgs::PointOfInterest cur_poi = pois[j];
00332 if (cur_poi_name.compare(cur_poi.name) == 0)
00333 {
00334 double distance = t_surface_object.getOrigin().distance(tf2::Vector3(cur_poi.pose.position.x, cur_poi.pose.position.y, cur_poi.pose.position.z));
00335 if (distance < closest_dist)
00336 {
00337 closest_dist = distance;
00338 closest_t = pose_to_tf(cur_poi.pose);
00339 }
00340 }
00341 }
00342
00343 tf2::Transform t_poi_object = closest_t.inverseTimes(t_surface_object);
00344
00345 add_placement_to_data(condition_id, t_poi_object, item_msg, room_msg, surface_msg, cur_poi_name);
00346 }
00347 }
00348
00349
00350 for (int i = 0; i < config.items.size(); i++)
00351 {
00352 interactive_world_msgs::Item &item = config.items[i];
00353 if (item.name.compare(object_name) != 0)
00354 {
00355
00356 double closest_dist = numeric_limits<double>::infinity();
00357 tf2::Transform closest_t;
00358 for (int j = 0; j < logs.size(); j++)
00359 {
00360 librms::log &log = logs[j];
00361
00362 if (log.get_label().compare("config") != 0 && log.get_label().compare("completion") != 0)
00363 {
00364
00365 Json::Value json;
00366 Json::Reader reader;
00367 reader.parse(log.get_entry(), json, false);
00368
00369 Json::Value json_furniture2 = json["furniture"];
00370 Json::Value json_furniture_position2 = json_furniture2["position"];
00371 Json::Value json_furniture_surface2 = json_furniture2["surface"];
00372 Json::Value json_furniture_surface_position2 = json_furniture_surface2["position"];
00373 Json::Value json_object2 = json_furniture_surface2["object"];
00374 Json::Value json_object_position2 = json_object2["position"];
00375
00376 if (json["name"].asString().compare(room_name) == 0 && json_furniture2["name"].asString().compare(surface_name) == 0 && json_object2["name"].asString().compare(item.name) == 0)
00377 {
00378
00379 tf2::Transform t_surface_psurface2 = parse_json_tf(json_furniture_surface_position2, json_furniture_surface2["rotation"].asDouble());
00380 tf2::Transform t_psurface_object2 = parse_json_tf(json_object_position2, json_object2["rotation"].asDouble());
00381 tf2::Transform t_surface_object2 = t_surface_psurface2 * t_psurface_object2;
00382
00383 double distance = t_surface_object.getOrigin().distance(t_surface_object2.getOrigin());
00384 if (distance < closest_dist)
00385 {
00386 closest_dist = distance;
00387 closest_t = t_surface_object2;
00388 }
00389 }
00390 }
00391 }
00392
00393 if (closest_dist < numeric_limits<double>::infinity())
00394 {
00395
00396 tf2::Transform t_object2_object = closest_t.inverseTimes(t_surface_object);
00397
00398 add_placement_to_data(condition_id, t_object2_object, item_msg, room_msg, surface_msg, item.name);
00399 }
00400 }
00401 }
00402 }
00403
00404 tf2::Transform interactive_world_parser::parse_json_tf(Json::Value &position, double rotation)
00405 {
00406 tf2::Quaternion q(Z_AXIS_TF2, rotation);
00407 tf2::Vector3 v(position["x"].asDouble(), position["y"].asDouble(), position["z"].asDouble());
00408 tf2::Transform tf(q, v);
00409 return tf;
00410 }
00411
00412 tf2::Transform interactive_world_parser::pose_to_tf(geometry_msgs::Pose &pose)
00413 {
00414 tf2::Quaternion q(pose.orientation.x, pose.orientation.y, pose.orientation.z, pose.orientation.w);
00415 tf2::Vector3 v(pose.position.x, pose.position.y, pose.position.z);
00416 tf2::Transform tf(q, v);
00417 return tf;
00418 }
00419
00420 geometry_msgs::Pose interactive_world_parser::parse_json_pose(Json::Value &position, double rotation)
00421 {
00422 geometry_msgs::Pose p;
00423 p.position.x = position["x"].asDouble();
00424 p.position.y = position["y"].asDouble();
00425 p.position.z = position["z"].asDouble();
00426
00427
00428 tf2::Quaternion q(Z_AXIS_TF2, rotation);
00429 p.orientation.x = q.x();
00430 p.orientation.y = q.y();
00431 p.orientation.z = q.z();
00432 p.orientation.w = q.w();
00433
00434 return p;
00435 }
00436
00437 void interactive_world_parser::add_placement_to_data(uint condition_id, tf2::Transform &tf, interactive_world_msgs::Item item, interactive_world_msgs::Room room, interactive_world_msgs::Surface surface, string reference_frame_id)
00438 {
00439 if (data_.find(condition_id) == data_.end())
00440 {
00441 data_[condition_id] = interactive_world_msgs::TaskTrainingData();
00442 }
00443 interactive_world_msgs::TaskTrainingData &training = data_[condition_id];
00444
00445
00446 interactive_world_msgs::Placement placement;
00447 placement.item = item;
00448 placement.room = room;
00449 placement.surface = surface;
00450 placement.reference_frame_id = reference_frame_id;
00451 placement.rotation = tf.getRotation().getAngle();
00452 placement.position.x = tf.getOrigin().x();
00453 placement.position.y = tf.getOrigin().y();
00454 placement.position.z = tf.getOrigin().z();
00455
00456
00457 for (uint i = 0; i < training.data.size(); i++)
00458 {
00459 interactive_world_msgs::PlacementSet &placements = training.data[i];
00460 if (placements.item.name.compare(item.name) == 0 && placements.room.name.compare(room.name) == 0 && placements.surface.name.compare(surface.name) == 0 && placements.reference_frame_id.compare(reference_frame_id) == 0)
00461 {
00462 placements.placements.push_back(placement);
00463 return;
00464 }
00465 }
00466
00467
00468 interactive_world_msgs::PlacementSet set;
00469 set.reference_frame_id = reference_frame_id;
00470 set.item = item;
00471 set.room = room;
00472 set.surface = surface;
00473 set.placements.push_back(placement);
00474 training.data.push_back(set);
00475 }
00476
00477 int main(int argc, char **argv)
00478 {
00479
00480 ros::init(argc, argv, "interactive_world_parser");
00481
00482 interactive_world_parser parser;
00483
00484 ros::spin();
00485 }