interactive_world_parser.hpp
Go to the documentation of this file.
00001 #ifndef INTERACTIVE_WORLD_PARSER_HPP_
00002 #define INTERACTIVE_WORLD_PARSER_HPP_
00003 
00004 #include <ros/ros.h>
00005 #include <rms/rms.hpp>
00006 #include <jsoncpp/json/json.h>
00007 #include <geometry_msgs/Pose.h>
00008 #include <interactive_world_msgs/Configuration.h>
00009 #include <interactive_world_msgs/TaskTrainingData.h>
00010 #include <interactive_world_msgs/LearnModels.h>
00011 #include <interactive_world_msgs/Parse.h>
00012 #include <tf2/LinearMath/Transform.h>
00013 #include <map>
00014 
00015 #define Z_AXIS_TF2 tf2::Vector3(0, 0, 1)
00016 
00017 class interactive_world_parser
00018 {
00019 public:
00020   interactive_world_parser();
00021 
00022   ~interactive_world_parser();
00023 
00024   void parse(int study_id);
00025 
00026   void learn();
00027 
00028   void save();
00029 
00030   void store();
00031 
00032   bool parse_and_save_cb(interactive_world_msgs::Parse::Request &req, interactive_world_msgs::Parse::Response &resp);
00033 
00034   bool parse_and_store_cb(interactive_world_msgs::Parse::Request &req, interactive_world_msgs::Parse::Response &resp);
00035 
00036 private:
00037   interactive_world_msgs::Configuration parse_json_config(Json::Value &config);
00038 
00039   geometry_msgs::Pose parse_json_pose(Json::Value &position, double rotation);
00040 
00041   tf2::Transform parse_json_tf(Json::Value &position, double rotation);
00042 
00043   tf2::Transform pose_to_tf(geometry_msgs::Pose &pose);
00044 
00045   void parse_json_placement(Json::Value &placement, interactive_world_msgs::Configuration &config, unsigned int condition_id, std::vector<librms::log> logs);
00046 
00047   void 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, std::string reference_frame_id);
00048 
00049   ros::NodeHandle private_;
00050 
00051   librms::rms *client_;
00052   std::string host_, user_, password_, database_;
00053   int port_;
00054   std::map<uint, interactive_world_msgs::TaskTrainingData> data_;
00055   ros::ServiceServer parse_and_store_, parse_and_save_;
00056   ros::ServiceClient learn_hypotheses_;
00057 };
00058 
00059 int main(int argc, char **argv);
00060 
00061 #endif


interactive_world_parser
Author(s): Russell Toris
autogenerated on Thu Jun 6 2019 21:34:25