37 is_initialized =
false;
38 memset(prev, 0, 3*
sizeof(
double));
43 double trad[3]; CvMat tra = cvMat(3, 1, CV_64F, trad);
47 if(is_initialized ==
false)
49 memcpy(prev, trad, 3*
sizeof(
double));
50 is_initialized =
true;
53 double dist = (prev[0]-trad[0])*(prev[0]-trad[0]) +
54 (prev[1]-trad[1])*(prev[1]-trad[1]) +
55 (prev[2]-trad[2])*(prev[2]-trad[2]);
58 memcpy(prev, trad, 3*
sizeof(
double));
68 container = container_reset_point;
69 if (reset_also_triangulated) {
70 container_triangulated = container_triangulated_reset_point;
72 pose_difference.Reset();
73 pose_difference.Mirror(
false,
true,
true);
77 container_reset_point = container;
78 container_triangulated_reset_point = container_triangulated;
91 return mm.
Load(container, fname, format, 0, 0,1023);
99 marker_detector.MarkerToEC(container, marker_id, edge_length, pose, 0, 0, 1023);
103 double pd[16], v[4] = {0,0,0,1};
104 CvMat Pi = cvMat(4, 4, CV_64F, pd);
105 CvMat V = cvMat(4, 1, CV_64F, v);
110 cvMatMul(&Pi, &V, &V);
116 p3d_vec.x = float(p3d.x - v[0]);
117 p3d_vec.y = float(p3d.y - v[1]);
118 p3d_vec.z = float(p3d.z - v[2]);
120 return std::sqrt(p3d_vec.x*p3d_vec.x + p3d_vec.y*p3d_vec.y + p3d_vec.z*p3d_vec.z);
131 p2d.x += parallax_length;
136 float pl = std::sqrt(p3d2.x*p3d2.x + p3d2.y*p3d2.y + p3d2.z*p3d2.z);
137 float shadow_point_dist = float(pl / std::abs(tan(triangulate_angle*3.1415926535/180.)));
143 p3d_sh.x *= shadow_point_dist;
144 p3d_sh.y *= shadow_point_dist;
145 p3d_sh.z *= shadow_point_dist;
154 bool SimpleSfM::Update(IplImage *
image,
bool assume_plane,
bool triangulate,
float reproj_err_limit,
float triangulate_angle) {
155 const int min_triangulate=50, max_triangulate=150;
156 const float plane_dist_limit = 100.f;
157 const bool remember_3d_points =
true;
158 const float parallax_length = 10.f;
159 const float parallax_length_sq = parallax_length*parallax_length;
160 float reproj_err_limit_sq = reproj_err_limit*reproj_err_limit;
161 std::map<int, Feature>::iterator iter;
162 std::map<int, Feature>::iterator iter_end = container.end();
167 tf.Track(image, 0, container, 1);
169 tf.EraseNonTracked(container, 1);
172 if (!pose_ok) pose_ok =
cam.CalcExteriorOrientation(container, &pose);
173 pose_ok =
cam.UpdatePose(container, &pose);
174 if (!pose_ok) pose_ok =
cam.UpdatePose(container, &pose, 0);
175 if (!pose_ok)
return false;
178 double err_markers =
cam.Reproject(container, &pose, 0,
true,
false, 100);
179 if (err_markers > reproj_err_limit*2) { Reset(
false);
return false;}
180 double err_features =
cam.Reproject(container, &pose, 1,
false,
false, 100);
181 if ((err_markers == 0) && (err_features > reproj_err_limit*2)) {
188 if (remember_3d_points) {
189 IplImage *mask =
tf.NewFeatureMask();
190 iter = container_triangulated.begin();
191 while(iter != container_triangulated.end()) {
192 if (container.find(iter->first) == container.end()) {
194 c->
ProjectPoint(iter->second.p3d, &pose, iter->second.projected_p2d);
195 if ((iter->second.projected_p2d.x >= 0) &&
196 (iter->second.projected_p2d.y >= 0) &&
197 (iter->second.projected_p2d.x < image->width) &&
198 (iter->second.projected_p2d.y < image->height))
200 CvScalar
s = cvGet2D(mask,
int(iter->second.projected_p2d.y),
int(iter->second.projected_p2d.x));
202 container[iter->first] = iter->second;
203 container[iter->first].estimation_type = 3;
204 container[iter->first].p2d = container[iter->first].projected_p2d;
214 tf.AddFeatures(container, 1, 1024, 0xffffff);
216 for (iter = container.begin(); iter != iter_end; iter++) {
225 cam.Get3dOnDepth(&pose, f.
p2d, plane_dist_limit, f.
p3d);
241 for (iter = container.begin(); iter != iter_end; iter++) {
248 cam.Get3dOnDepth(&pose, f.
p2d, 8, f.
p3d);
254 if (dist_sh_sq > parallax_length_sq) {
255 CvPoint2D32f u1 = f.
p2d1;
256 CvPoint2D32f u2 = f.
p2d;
257 cam.Camera::Undistort(u1);
258 cam.Camera::Undistort(u2);
259 if(
cam.ReconstructFeature(&f.
pose1, &pose, &u1, &u2, &f.
p3d, 10e-6)) {
271 cam.Reproject(container, &pose, 1,
false,
false, 100);
272 iter = container.begin();
273 while(iter != container.end()) {
274 bool iter_inc =
true;
275 if (iter->second.type_id > 0) {
284 if (dist_sq > (reproj_err_limit_sq)) f.
has_p3d =
false;
286 if (dist_sq > (reproj_err_limit_sq)) {
287 container.erase(iter++);
291 if (container_triangulated.size() < min_triangulate) {
292 if (dist_sq > (reproj_err_limit_sq)) {
293 container.erase(iter++);
297 if (dist_sq > (reproj_err_limit_sq)) f.
has_p3d =
false;
298 if (dist_sq > (reproj_err_limit_sq*2)) {
299 std::map<int, Feature>::iterator iter_tmp;
300 iter_tmp = container_triangulated.find(iter->first);
301 if (iter_tmp != container_triangulated.end()) {
302 container_triangulated.erase(iter_tmp);
304 container.erase(iter++);
311 if (iter_inc) iter++;
315 if (remember_3d_points && (container_triangulated.size() < max_triangulate)) {
316 iter = container.begin();
317 while(iter != container.end()) {
318 if ((iter->second.type_id > 0) &&
319 (container_triangulated.find(iter->first) == container_triangulated.end()))
326 if ((dist_sq < reproj_err_limit_sq) && (dist_sh_sq > parallax_length_sq)) {
327 container_triangulated[iter->first] = iter->second;
332 if (container_triangulated.size() >= max_triangulate)
break;
342 tf.Track(image, 0, container, 1, 1024, 65535);
343 tf.EraseNonTracked(container, 1);
344 if (!pose_ok) pose_ok =
cam.CalcExteriorOrientation(container, &pose);
345 else pose_ok =
cam.UpdatePose(container, &pose);
347 std::map<int,Feature>::iterator iter = container.begin();
348 std::map<int,Feature>::iterator iter_end = container.end();
349 for(;iter != iter_end; iter++) {
350 if (pose_ok && (iter->second.type_id == 1) && (!iter->second.has_stored_pose) && (!iter->second.has_p3d)) {
351 iter->second.pose1 = pose;
352 iter->second.p2d1 = iter->second.p2d;
353 iter->second.has_stored_pose =
true;
356 iter = container.begin();
357 for(;iter != iter_end; iter++)
364 CvPoint2D32f u1 = f.
p2d1;
365 CvPoint2D32f u2 = f.
p2d;
366 cam.Camera::Undistort(u1);
367 cam.Camera::Undistort(u2);
368 if(
cam.ReconstructFeature(&f.
pose1, &pose, &u1, &u2, &f.
p3d, 10e-6))
376 double err_markers =
cam.Reproject(container, &pose, 0,
true,
false, 100);
377 if(err_markers > 30) { Reset(
false);
return false;}
378 double err_features =
cam.Reproject(container, &pose, 1,
false,
false, 100);
379 cam.EraseUsingReprojectionError(container, 30, 1);
386 static int n_markers_prev = 0;
388 tf.Track(image, 0, container, 1, 1024, 65535);
389 tf.EraseNonTracked(container, 1);
391 if(n_markers>=1) type_id = 0;
394 pose_ok =
cam.CalcExteriorOrientation(container, &pose, 0);
395 if(pose_ok) pose_original = pose;
400 pose_ok =
cam.UpdatePose(container, &pose, 0);
402 pose_ok =
cam.CalcExteriorOrientation(container, &pose, 0);
403 if(pose_ok) pose_original = pose;
407 if (n_markers_prev > 0) {
408 pose_difference.Reset();
409 pose_difference.Mirror(
false,
true,
true);
410 std::map<int,Feature>::iterator iter = container.begin();
411 std::map<int,Feature>::iterator iter_end = container.end();
412 for(;iter != iter_end; iter++) {
413 if ((iter->second.type_id == 1) && (iter->second.has_p2d)) {
414 CvPoint2D32f _p2d = iter->second.p2d;
415 cam.Get3dOnDepth(&pose_difference, _p2d, 1, iter->second.p3d);
416 iter->second.has_p3d =
true;
420 cam.UpdateRotation(container, &pose_difference, 1);
425 pose_difference.GetMatrixGL(rot_mat);
426 pose_original.GetMatrixGL(gl_mat);
427 CvMat rot = cvMat(4, 4, CV_64F, rot_mat);
428 CvMat mod = cvMat(4, 4, CV_64F, gl_mat);
429 cvMatMul(&mod, &rot, &rot);
430 pose.SetMatrixGL(rot_mat);
437 std::map<int,Feature>::iterator iter = container.begin();
438 std::map<int,Feature>::iterator iter_end = container.end();
439 for(;iter != iter_end; iter++) {
440 if ((iter->second.type_id == 1) && (!iter->second.has_p3d) && (iter->second.has_p2d)) {
441 CvPoint2D32f _p2d = iter->second.p2d;
442 cam.Get3dOnDepth(&pose_difference, _p2d, 1, iter->second.p3d);
443 iter->second.has_p3d =
true;
448 double err_markers =
cam.Reproject(container, &pose, 0,
true,
false, 100);
449 if(err_markers > 10) { Reset(
false);
return false;}
450 double err_features =
cam.Reproject(container, &pose_difference, 1,
false,
false, 100);
451 cam.EraseUsingReprojectionError(container, 10, 1);
457 if(markers_found)
return;
458 std::map<int,Feature>::iterator iter = container.begin();
459 std::map<int,Feature>::iterator iter_end = container.end();
460 for(;iter != iter_end;iter++) {
463 int r=0, g=0, b=0,
rad=1;
464 if (f.
type_id == 0) {r=255; g=0; b=0;}
467 else {r=0; g=255; b=255;}
475 cvCircle(rgba, cvPointFrom32f(f.
p2d),
rad, CV_RGB(r,g,b));
483 cvLine(rgba, cvPointFrom32f(f.
p2d), cvPointFrom32f(f.
projected_p2d), CV_RGB(255,0,255));
float PointVectorFromCamera(CvPoint3D32f p3d, CvPoint3D32f &p3d_vec, Pose *camera_pose)
void AddMarker(int marker_id, double edge_length, Pose &pose)
Add an marker to be a basis for tracking. It is good idea to call SetResetPoint after these...
void CreateShadowPoint(CvPoint3D32f &p3d_sh, CvPoint3D32f p3d, CameraEC *cam, Pose *camera_pose, float parallax_length, float triangulate_angle)
void Clear()
Clear all tracked features.
void GetTranslation(CvMat *tra) const
void SetResetPoint()
Remember the current state and return here when the Reset is called.
bool UpdateDistance(Pose *pose, double limit=10)
This file implements structure from motion.
Version of Camera using external container.
bool AddMultiMarker(const char *fname, FILE_FORMAT format=FILE_FORMAT_XML)
Add MultiMarker from file as a basis for tracking. It is good idea to call SetResetPoint after these...
CameraEC * GetCamera()
Get the camera used internally. You need to use this to set correct camera calibration (see SamplePoi...
Simple Camera class for calculating distortions, orientation or projections with pre-calibrated camer...
Version of MultiMarker using external container.
CvPoint2D32f projected_p2d_sh
bool UpdateTriangulateOnly(IplImage *image)
Update camera 6-DOF position using triangulated points only (This is the old version of Update) ...
void ProjectPoint(const CvPoint3D64f pw, const Pose *pose, CvPoint2D64f &pi) const
Project one point.
bool Update(IplImage *image, bool assume_plane=true, bool triangulate=true, float reproj_err_limit=5.f, float triangulate_angle=15.f)
Update position assuming that camera is moving with 6-DOF.
Pose representation derived from the Rotation class
void Get3dOnDepth(const Pose *pose, CvPoint2D32f p2d, float depth, CvPoint3D32f &p3d)
Get 3D-coordinate for 2D feature assuming certain depth.
void Draw(IplImage *rgba)
Draw debug information about the tracked features and detected markers.
MarkerDetector< MarkerData > marker_detector
Pose * GetPose()
Get the estimated pose.
bool UpdateRotationsOnly(IplImage *image)
Update position assuming that user is more standing still and viewing the environment.
void GetMatrix(CvMat *mat) const
Extended version of ExternalContainer structure used internally in SimpleSfM.
bool Load(std::map< int, T > &container, const char *fname, FILE_FORMAT format=FILE_FORMAT_DEFAULT, int type_id=0, int first_id=0, int last_id=65535)
Fill in 3D-coordinates for marker corners to the given container using save MultiMarker file...
bool MarkersToEC(std::map< int, T > &container, int type_id=0, int first_id=0, int last_id=65535)
Fill in 3D-coordinates for marker corners to the given container.
CvPoint2D32f projected_p2d
void Reset(bool reset_also_triangulated=true)
Reset the situation back to the point it was when SetResetPoint was called.