00001 00012 #ifndef SPATIAL_TEMPORAL_LEARNING_WORLDLIB_REMOTE_NODE_H_ 00013 #define SPATIAL_TEMPORAL_LEARNING_WORLDLIB_REMOTE_NODE_H_ 00014 00015 // worldlib 00016 #include "InteractiveWorldModelClient.h" 00017 #include "SpatialWorldClient.h" 00018 #include "../geometry/Pose.h" 00019 #include "../world/World.h" 00020 00021 // ROS 00022 #include <ros/node_handle.h> 00023 #include <tf2_ros/transform_listener.h> 00024 00025 namespace rail 00026 { 00027 namespace spatial_temporal_learning 00028 { 00029 namespace worldlib 00030 { 00031 namespace remote 00032 { 00033 00040 class Node 00041 { 00042 public: 00048 Node(); 00049 00057 bool okay() const; 00058 00059 protected: 00068 bool loadWorldYamlFile(const bool verbose = true); 00069 00078 InteractiveWorldModelClient *createInteractiveWorldModelClient(const bool verbose = true) const; 00079 00088 SpatialWorldClient *createSpatialWorldClient(const bool verbose = true) const; 00089 00099 geometry::Pose transformToWorld(const geometry::Pose &pose, const std::string &pose_frame_id) const; 00100 00102 bool okay_; 00104 worldlib::world::World world_; 00106 ros::NodeHandle node_, private_node_; 00108 tf2_ros::Buffer tfs_; 00110 tf2_ros::TransformListener tf_listener_; 00111 }; 00112 00113 } 00114 } 00115 } 00116 } 00117 00118 #endif