Public Member Functions | Private Member Functions | Private Attributes
interactive_world_parser Class Reference

#include <interactive_world_parser.hpp>

List of all members.

Public Member Functions

 interactive_world_parser ()
void learn ()
void parse (int study_id)
bool parse_and_save_cb (interactive_world_msgs::Parse::Request &req, interactive_world_msgs::Parse::Response &resp)
bool parse_and_store_cb (interactive_world_msgs::Parse::Request &req, interactive_world_msgs::Parse::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::rmsclient_
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_
std::string user_

Detailed Description

Definition at line 17 of file interactive_world_parser.hpp.


Constructor & Destructor Documentation

Definition at line 8 of file interactive_world_parser.cpp.

Definition at line 41 of file interactive_world_parser.cpp.


Member Function Documentation

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 438 of file interactive_world_parser.cpp.

Definition at line 153 of file interactive_world_parser.cpp.

void interactive_world_parser::parse ( int  study_id)

Definition at line 54 of file interactive_world_parser.cpp.

bool interactive_world_parser::parse_and_save_cb ( interactive_world_msgs::Parse::Request &  req,
interactive_world_msgs::Parse::Response &  resp 
)

Definition at line 185 of file interactive_world_parser.cpp.

bool interactive_world_parser::parse_and_store_cb ( interactive_world_msgs::Parse::Request &  req,
interactive_world_msgs::Parse::Response &  resp 
)

Definition at line 177 of file interactive_world_parser.cpp.

interactive_world_msgs::Configuration interactive_world_parser::parse_json_config ( Json::Value &  config) [private]

Definition at line 193 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 250 of file interactive_world_parser.cpp.

geometry_msgs::Pose interactive_world_parser::parse_json_pose ( Json::Value &  position,
double  rotation 
) [private]

Definition at line 421 of file interactive_world_parser.cpp.

tf2::Transform interactive_world_parser::parse_json_tf ( Json::Value &  position,
double  rotation 
) [private]

Definition at line 405 of file interactive_world_parser.cpp.

tf2::Transform interactive_world_parser::pose_to_tf ( geometry_msgs::Pose &  pose) [private]

Definition at line 413 of file interactive_world_parser.cpp.

Definition at line 127 of file interactive_world_parser.cpp.


Member Data Documentation

Definition at line 51 of file interactive_world_parser.hpp.

std::map<uint, interactive_world_msgs::TaskTrainingData> interactive_world_parser::data_ [private]

Definition at line 54 of file interactive_world_parser.hpp.

std::string interactive_world_parser::database_ [private]

Definition at line 52 of file interactive_world_parser.hpp.

std::string interactive_world_parser::host_ [private]

Definition at line 52 of file interactive_world_parser.hpp.

Definition at line 56 of file interactive_world_parser.hpp.

Definition at line 55 of file interactive_world_parser.hpp.

Definition at line 55 of file interactive_world_parser.hpp.

std::string interactive_world_parser::password_ [private]

Definition at line 52 of file interactive_world_parser.hpp.

Definition at line 53 of file interactive_world_parser.hpp.

Definition at line 49 of file interactive_world_parser.hpp.

std::string interactive_world_parser::user_ [private]

Definition at line 52 of file interactive_world_parser.hpp.


The documentation for this class was generated from the following files:


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