|
| 1 | +#ifndef ED_SENSOR_INTEGRATION_TOOLS_SNAPSHOT_H_ |
| 2 | +#define ED_SENSOR_INTEGRATION_TOOLS_SNAPSHOT_H_ |
| 3 | + |
| 4 | +#include <ed/models/model_loader.h> |
| 5 | +#include <ed/world_model.h> |
| 6 | +#include <ed/update_request.h> |
| 7 | +#include <ed/serialization/serialization.h> |
| 8 | +#include <ed/io/json_reader.h> |
| 9 | + |
| 10 | +#include <exception> |
| 11 | + |
| 12 | +#include <tue/filesystem/crawler.h> |
| 13 | + |
| 14 | +#include <tue/config/read.h> |
| 15 | +#include <tue/config/reader.h> |
| 16 | +#include <tue/config/data_pointer.h> |
| 17 | + |
| 18 | +#include <rgbd/image.h> |
| 19 | +#include <rgbd/serialization.h> |
| 20 | + |
| 21 | +#include <vector> |
| 22 | + |
| 23 | +namespace ed |
| 24 | +{ |
| 25 | + |
| 26 | +/** |
| 27 | + * Exception thrown when no model with the specified name could be found |
| 28 | + */ |
| 29 | +class ModelNotFoundException : public std::exception { |
| 30 | + std::string model_name_; |
| 31 | + std::string message_; |
| 32 | + |
| 33 | +public: |
| 34 | + ModelNotFoundException(const std::string model_name, const std::string message) |
| 35 | + { |
| 36 | + model_name_ = model_name; |
| 37 | + message_ = message; |
| 38 | + } |
| 39 | + const char * what () const throw () { |
| 40 | + return message_.c_str(); |
| 41 | + } |
| 42 | +}; |
| 43 | + |
| 44 | +/** |
| 45 | + * @brief The Snapshot struct, of a camera image taken at a single point in time. |
| 46 | + */ |
| 47 | +struct Snapshot |
| 48 | +{ |
| 49 | + rgbd::ImagePtr image; |
| 50 | + geo::Pose3D sensor_pose; |
| 51 | +}; |
| 52 | + |
| 53 | +/** |
| 54 | + * read an rgbd image from file |
| 55 | + * |
| 56 | + * @param[in] filename name of the json file that describes the image |
| 57 | + * @param[out] image image to write to |
| 58 | + * @param[out] sensor_pose pose to write to |
| 59 | + * @return bool whether image was successfully loaded |
| 60 | + */ |
| 61 | +bool readImage(const std::string& filename, rgbd::ImagePtr& image, geo::Pose3D& sensor_pose) |
| 62 | +{ |
| 63 | + tue::config::DataPointer meta_data; |
| 64 | + |
| 65 | + try |
| 66 | + { |
| 67 | + meta_data = tue::config::fromFile(filename); |
| 68 | + } |
| 69 | + catch (tue::config::ParseException& e) |
| 70 | + { |
| 71 | + std::cerr << "Could not open '" << filename << "'.\n\n" << e.what() << std::endl; |
| 72 | + return false; |
| 73 | + } |
| 74 | + |
| 75 | + tue::config::Reader r(meta_data); |
| 76 | + |
| 77 | + // Read image |
| 78 | + std::string rgbd_filename; |
| 79 | + if (r.value("rgbd_filename", rgbd_filename)) |
| 80 | + { |
| 81 | + tue::filesystem::Path abs_rgbd_filename = tue::filesystem::Path(filename).parentPath().join(rgbd_filename); |
| 82 | + |
| 83 | + std::ifstream f_rgbd; |
| 84 | + f_rgbd.open(abs_rgbd_filename.string().c_str(), std::ifstream::binary); |
| 85 | + |
| 86 | + if (!f_rgbd.is_open()) |
| 87 | + { |
| 88 | + std::cerr << "Could not open '" << filename << "'." << std::endl; |
| 89 | + return false; |
| 90 | + } |
| 91 | + |
| 92 | + image.reset(new rgbd::Image); |
| 93 | + |
| 94 | + tue::serialization::InputArchive a_in(f_rgbd); |
| 95 | + rgbd::deserialize(a_in, *image); |
| 96 | + } |
| 97 | + |
| 98 | + // Read sensor pose |
| 99 | + if (!ed::deserialize(r, "sensor_pose", sensor_pose)) |
| 100 | + { |
| 101 | + std::cerr << "No field 'sensor_pose' specified." << std::endl; |
| 102 | + return false; |
| 103 | + } |
| 104 | + |
| 105 | + return true; |
| 106 | +} |
| 107 | + |
| 108 | +/** |
| 109 | + * Load a worldmodel from file using its name. |
| 110 | + * |
| 111 | + * @param[in] model_name name of the worldmodel |
| 112 | + * @param[out] world_model worldmodel to write to |
| 113 | + * @return bool whether model is successfully loaded |
| 114 | + */ |
| 115 | +ed::WorldModelPtr loadWorldModel(const std::string& model_name) |
| 116 | +{ |
| 117 | + ed::UpdateRequest req; |
| 118 | + |
| 119 | + ed::models::ModelLoader model_loader; |
| 120 | + |
| 121 | + std::stringstream error; |
| 122 | + if (!model_loader.create("_root", model_name, req, error, true)) |
| 123 | + { |
| 124 | + std::string message = "loadWorldModel: Model '" + model_name + |
| 125 | + "' could not be loaded. ModelLoader error: " + error.str(); |
| 126 | + throw ModelNotFoundException(model_name.c_str(), message.c_str()); |
| 127 | + } |
| 128 | + |
| 129 | + ed::WorldModelPtr world_model_ptr = ed::make_shared<ed::WorldModel>(); |
| 130 | + |
| 131 | + // Update world |
| 132 | + world_model_ptr->update(req); |
| 133 | + |
| 134 | + return world_model_ptr; |
| 135 | +} |
| 136 | + |
| 137 | +class SnapshotCrawler |
| 138 | +{ |
| 139 | + |
| 140 | +public: |
| 141 | + |
| 142 | + SnapshotCrawler(tue::filesystem::Path path) |
| 143 | + { |
| 144 | + if (path.isDirectory()) |
| 145 | + crawler.setRootPath(path); |
| 146 | + else |
| 147 | + crawler.setRootPath(path.parentPath()); |
| 148 | + |
| 149 | + // load first snapshot |
| 150 | + if (path.isRegularFile()) |
| 151 | + loadSnapshot(path); |
| 152 | + else |
| 153 | + loadNewSnapshot(); |
| 154 | + } |
| 155 | + |
| 156 | + inline Snapshot& current() { return snapshots[i_current]; } |
| 157 | + inline Snapshot& getSnapshot(unsigned int i) { return snapshots[i]; } |
| 158 | + |
| 159 | + void previous() |
| 160 | + { |
| 161 | + if (i_current > 0) |
| 162 | + --i_current; |
| 163 | + } |
| 164 | + |
| 165 | + /** |
| 166 | + * @brief next, proceed to next index of the snapshot list. If index is out of bounds, try to load a new snapshot. |
| 167 | + */ |
| 168 | + void next() |
| 169 | + { |
| 170 | + ++i_current; |
| 171 | + |
| 172 | + //load new image if size of vector is exceeded |
| 173 | + if (i_current >= snapshots.size()) |
| 174 | + { |
| 175 | + if (!loadNewSnapshot()) |
| 176 | + { |
| 177 | + i_current = snapshots.size() - 1; |
| 178 | + } |
| 179 | + } |
| 180 | + } |
| 181 | + |
| 182 | + /** |
| 183 | + * @brief loadNewSnapshot, find next file to load snapshot from and load snapshot. |
| 184 | + * @return whether or not loading the new snapshot succeeded. |
| 185 | + */ |
| 186 | + bool loadNewSnapshot() |
| 187 | + { |
| 188 | + bool file_found = false; |
| 189 | + tue::filesystem::Path filename; |
| 190 | + |
| 191 | + while (crawler.nextPath(filename)) |
| 192 | + { |
| 193 | + if (filename.extension() == ".json") |
| 194 | + { |
| 195 | + file_found = true; |
| 196 | + break; |
| 197 | + } |
| 198 | + } |
| 199 | + |
| 200 | + if (!file_found) |
| 201 | + return false; |
| 202 | + |
| 203 | + return loadSnapshot(filename); |
| 204 | + } |
| 205 | + |
| 206 | + /** |
| 207 | + * @brief loadSnapshot, load snapshot data and extend the snapshots list. |
| 208 | + * @param filename: name of the json file to load |
| 209 | + * @return whether or not loading the snapshot was successful. |
| 210 | + */ |
| 211 | + bool loadSnapshot(tue::filesystem::Path filename) |
| 212 | + { |
| 213 | + i_current = snapshots.size(); |
| 214 | + snapshots.push_back(Snapshot()); |
| 215 | + Snapshot& snapshot = snapshots.back(); |
| 216 | + |
| 217 | + std::cout << "Loading " << filename << std::endl; |
| 218 | + if (!readImage(filename.string(), snapshot.image, snapshot.sensor_pose)) |
| 219 | + { |
| 220 | + std::cerr << "Could not read: " << filename << std::endl; |
| 221 | + snapshots.pop_back(); |
| 222 | + return false; |
| 223 | + } |
| 224 | + return true; |
| 225 | + } |
| 226 | + |
| 227 | +private: |
| 228 | + uint i_current; |
| 229 | + std::vector<Snapshot> snapshots; |
| 230 | + |
| 231 | + tue::filesystem::Crawler crawler; |
| 232 | +}; |
| 233 | + |
| 234 | +} |
| 235 | +#endif // ED_SENSOR_INTEGRATION_TOOLS_SNAPSHOT_H_ |
0 commit comments