Skip to content

Commit b490827

Browse files
authored
Merge pull request #49 from tue-robotics/feature/incorporate_victor_BEP
Incorporate BEP victor
2 parents fa926e9 + 92d211b commit b490827

File tree

10 files changed

+672
-269
lines changed

10 files changed

+672
-269
lines changed

ed_sensor_integration/CMakeLists.txt

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,7 @@ find_package(catkin REQUIRED COMPONENTS
55
ed
66
ed_sensor_integration_msgs
77
geolib2
8+
image_geometry
89
sensor_msgs
910
tue_config
1011
tue_filesystem
@@ -110,6 +111,9 @@ add_dependencies(ed_image_saver ${catkin_EXPORTED_TARGETS})
110111
add_executable(ed_segmenter tools/segmenter.cpp)
111112
target_link_libraries(ed_segmenter ed_kinect)
112113

114+
add_executable(ed_fitter tools/fitter_viz.cpp)
115+
target_link_libraries(ed_fitter ed_kinect)
116+
113117
# ------------------------------------------------------------------------------------------------
114118
# TESTS
115119
# ------------------------------------------------------------------------------------------------

ed_sensor_integration/include/ed/kinect/beam_model.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,7 @@ class BeamModel
4343
std::vector<double>& ranges, std::vector<int>& identifiers) const;
4444

4545
inline unsigned int num_beams() const { return rays_.size(); }
46+
inline float fx() const {return fx_;}
4647

4748
inline const std::vector<geo::Vec2>& rays() const { return rays_; }
4849

ed_sensor_integration/include/ed/kinect/fitter.h

Lines changed: 29 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99
#include <geolib/datatypes.h>
1010

1111
#include <rgbd/types.h>
12+
#include <image_geometry/pinhole_camera_model.h>
1213

1314
#include "beam_model.h"
1415

@@ -67,6 +68,7 @@ struct EntityRepresentation2D
6768
struct FitterData
6869
{
6970
std::vector<double> sensor_ranges;
71+
float fx;
7072
geo::Pose3D sensor_pose;
7173
geo::Pose3D sensor_pose_xya;
7274
geo::Pose3D sensor_pose_zrp;
@@ -93,27 +95,41 @@ struct EstimationInputData
9395
// ----------------------------------------------------------------------------------------------------
9496

9597
/**
96-
* @brief The Fitter class contains the algorithm to do the 2D fit
98+
* @brief The Fitter class contains the algorithm to do the 2D fit of an entity.
9799
*/
98100
class Fitter
99101
{
100102

101103
public:
102104

105+
/**
106+
* @brief Fitter default constructor, must be configured later.
107+
*/
108+
Fitter();
109+
103110
/**
104111
* @brief Fitter constructor
105-
* @param nr_data_points nr_data_points for the beam model
112+
* @param nr_data_points Number of data points for the beam model
113+
* @param fx focal length for the beam model
106114
*/
107-
Fitter(uint nr_data_points = 200); // TODO: remove hard-coded values
115+
Fitter(unsigned int nr_data_points, float fx);
116+
117+
/**
118+
* @brief Fitter constructor
119+
* @param cammodel Cameramodel used to configure the fitter
120+
*/
121+
Fitter(const image_geometry::PinholeCameraModel& cammodel) { configureBeamModel(cammodel); }
108122

109123
~Fitter();
110124

125+
inline bool isConfigured() { return configured_; };
126+
111127
/**
112128
* @brief processSensorData pre-processes sensor data, i.e., performs a downprojection of the input
113129
* depth image based on the provided sensor pose and stores the result in the FitterData struct
114-
* @param image input (depth) image
115-
* @param sensor_pose pose of the sensor in the world while taking the image
116-
* @param data processed data is stored here
130+
* @param[in] image input (depth) image
131+
* @param[in] sensor_pose pose of the sensor in the world while taking the image
132+
* @param[out] data processed data is stored here
117133
*/
118134
void processSensorData(const rgbd::Image& image, const geo::Pose3D& sensor_pose, FitterData& data) const;
119135

@@ -148,6 +164,12 @@ class Fitter
148164
*/
149165
EntityRepresentation2D GetOrCreateEntity2D(const ed::EntityConstPtr& e) const;
150166

167+
/**
168+
* @brief configure the beam model (nr of data points and focal length) according to the camera you are using.
169+
* @param cammodel camera model
170+
*/
171+
void configureBeamModel(const image_geometry::PinholeCameraModel& cammodel);
172+
151173
private:
152174

153175
/**
@@ -239,6 +261,7 @@ class Fitter
239261
ed::models::ModelLoader model_loader_;
240262

241263
uint nr_data_points_;
264+
bool configured_ = false;
242265

243266
};
244267

Lines changed: 235 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,235 @@
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_

ed_sensor_integration/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616
<depend>ed</depend>
1717
<depend>ed_sensor_integration_msgs</depend>
1818
<depend>geolib2</depend>
19+
<depend>image_geometry</depend>
1920
<depend>sensor_msgs</depend>
2021
<depend>tue_config</depend>
2122
<depend>tue_filesystem</depend>

0 commit comments

Comments
 (0)