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


interactive_world_parser
Author(s): Russell Toris
autogenerated on Sun Dec 14 2014 11:27:10