#include <interactive_world_parser.hpp>
| Public Member Functions | |
| interactive_world_parser () | |
| void | learn () | 
| void | parse () | 
| bool | parse_and_save_cb (std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp) | 
| bool | parse_and_store_cb (std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp) | 
| void | save () | 
| void | store () | 
| ~interactive_world_parser () | |
| Private Member Functions | |
| 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) | 
| interactive_world_msgs::Configuration | parse_json_config (Json::Value &config) | 
| void | parse_json_placement (Json::Value &placement, interactive_world_msgs::Configuration &config, unsigned int condition_id, std::vector< librms::log > logs) | 
| geometry_msgs::Pose | parse_json_pose (Json::Value &position, double rotation) | 
| tf2::Transform | parse_json_tf (Json::Value &position, double rotation) | 
| tf2::Transform | pose_to_tf (geometry_msgs::Pose &pose) | 
| Private Attributes | |
| librms::rms * | client_ | 
| std::map< uint, interactive_world_msgs::TaskTrainingData > | data_ | 
| std::string | database_ | 
| std::string | host_ | 
| ros::ServiceClient | learn_hypotheses_ | 
| ros::ServiceServer | parse_and_save_ | 
| ros::ServiceServer | parse_and_store_ | 
| std::string | password_ | 
| int | port_ | 
| ros::NodeHandle | private_ | 
| int | study_id_ | 
| std::string | user_ | 
Definition at line 19 of file interactive_world_parser.hpp.
Definition at line 8 of file interactive_world_parser.cpp.
Definition at line 42 of file interactive_world_parser.cpp.
| 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, | ||
| std::string | reference_frame_id | ||
| ) |  [private] | 
Definition at line 437 of file interactive_world_parser.cpp.
| void interactive_world_parser::learn | ( | ) | 
Definition at line 154 of file interactive_world_parser.cpp.
| void interactive_world_parser::parse | ( | ) | 
Definition at line 55 of file interactive_world_parser.cpp.
| bool interactive_world_parser::parse_and_save_cb | ( | std_srvs::Empty::Request & | req, | 
| std_srvs::Empty::Response & | resp | ||
| ) | 
Definition at line 186 of file interactive_world_parser.cpp.
| bool interactive_world_parser::parse_and_store_cb | ( | std_srvs::Empty::Request & | req, | 
| std_srvs::Empty::Response & | resp | ||
| ) | 
Definition at line 178 of file interactive_world_parser.cpp.
| interactive_world_msgs::Configuration interactive_world_parser::parse_json_config | ( | Json::Value & | config | ) |  [private] | 
Definition at line 194 of file interactive_world_parser.cpp.
| void interactive_world_parser::parse_json_placement | ( | Json::Value & | placement, | 
| interactive_world_msgs::Configuration & | config, | ||
| unsigned int | condition_id, | ||
| std::vector< librms::log > | logs | ||
| ) |  [private] | 
Definition at line 251 of file interactive_world_parser.cpp.
| geometry_msgs::Pose interactive_world_parser::parse_json_pose | ( | Json::Value & | position, | 
| double | rotation | ||
| ) |  [private] | 
Definition at line 420 of file interactive_world_parser.cpp.
| tf2::Transform interactive_world_parser::parse_json_tf | ( | Json::Value & | position, | 
| double | rotation | ||
| ) |  [private] | 
Definition at line 404 of file interactive_world_parser.cpp.
| tf2::Transform interactive_world_parser::pose_to_tf | ( | geometry_msgs::Pose & | pose | ) |  [private] | 
Definition at line 412 of file interactive_world_parser.cpp.
| void interactive_world_parser::save | ( | ) | 
Definition at line 128 of file interactive_world_parser.cpp.
| void interactive_world_parser::store | ( | ) | 
| librms::rms* interactive_world_parser::client_  [private] | 
Definition at line 53 of file interactive_world_parser.hpp.
| std::map<uint, interactive_world_msgs::TaskTrainingData> interactive_world_parser::data_  [private] | 
Definition at line 56 of file interactive_world_parser.hpp.
| std::string interactive_world_parser::database_  [private] | 
Definition at line 54 of file interactive_world_parser.hpp.
| std::string interactive_world_parser::host_  [private] | 
Definition at line 54 of file interactive_world_parser.hpp.
Definition at line 58 of file interactive_world_parser.hpp.
Definition at line 57 of file interactive_world_parser.hpp.
Definition at line 57 of file interactive_world_parser.hpp.
| std::string interactive_world_parser::password_  [private] | 
Definition at line 54 of file interactive_world_parser.hpp.
| int interactive_world_parser::port_  [private] | 
Definition at line 55 of file interactive_world_parser.hpp.
Definition at line 51 of file interactive_world_parser.hpp.
| int interactive_world_parser::study_id_  [private] | 
Definition at line 55 of file interactive_world_parser.hpp.
| std::string interactive_world_parser::user_  [private] | 
Definition at line 54 of file interactive_world_parser.hpp.