Go to the documentation of this file.00001
00011 #ifndef SPATIAL_TEMPORAL_LEARNING_WORLDLIB_WORLD_WORLD_H_
00012 #define SPATIAL_TEMPORAL_LEARNING_WORLDLIB_WORLD_WORLD_H_
00013
00014
00015 #include "Item.h"
00016 #include "Room.h"
00017
00018
00019 #include <tf2_ros/buffer.h>
00020
00021
00022 #include <yaml-cpp/yaml.h>
00023
00024
00025 #include <string>
00026 #include <vector>
00027
00028 namespace rail
00029 {
00030 namespace spatial_temporal_learning
00031 {
00032 namespace worldlib
00033 {
00034 namespace world
00035 {
00036
00043 class World
00044 {
00045 public:
00053 World(const std::string &fixed_frame_id = "");
00054
00064 bool loadFromYaml(const std::string &file);
00065
00066 #ifdef YAMLCPP_GT_0_5_0
00067
00075 Object parseObject(const YAML::Node &object) const;
00076 #endif
00077
00085 const std::string &getFixedFrameID() const;
00086
00094 void setFixedFrameID(const std::string &fixed_frame_id);
00095
00103 const std::vector<Room> &getRooms() const;
00104
00112 std::vector<Room> &getRooms();
00113
00121 size_t getNumRooms() const;
00122
00132 const Room &getRoom(const size_t index) const;
00133
00143 Room &getRoom(const size_t index);
00144
00152 void addRoom(const Room &room);
00153
00162 void removeRoom(const size_t index);
00163
00172 bool roomExists(const std::string &name) const;
00173
00183 const Room &findRoom(const std::string &name) const;
00184
00194 Room &findRoom(const std::string &name);
00195
00203 const std::vector<Item> &getItems() const;
00204
00212 std::vector<Item> &getItems();
00213
00221 size_t getNumItems() const;
00222
00232 const Item &getItem(const size_t index) const;
00233
00243 Item &getItem(const size_t index);
00244
00252 void addItem(const Item &item);
00253
00262 void removeItem(const size_t index);
00263
00273 bool itemExists(const std::string &name) const;
00274
00285 const Item &findItem(const std::string &name) const;
00286
00297 Item &findItem(const std::string &name);
00298
00309 void findClosestSurface(const geometry::Position &position, size_t &room_index, size_t &surface_index) const;
00310
00325 bool findPlacementSurface(const geometry::Position &position, size_t &room_index, size_t &surface_index,
00326 size_t &placement_surface_index) const;
00327
00328 private:
00330 std::string fixed_frame_id_;
00332 std::vector<Room> rooms_;
00334 std::vector<Item> items_;
00335 };
00336
00337 }
00338 }
00339 }
00340 }
00341
00342 #endif