g2o
sensor_pose3d.cpp
Go to the documentation of this file.
1 // g2o - General Graph Optimization
2 // Copyright (C) 2011 G. Grisetti, R. Kuemmerle, W. Burgard
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are
7 // met:
8 //
9 // * Redistributions of source code must retain the above copyright notice,
10 // this list of conditions and the following disclaimer.
11 // * Redistributions in binary form must reproduce the above copyright
12 // notice, this list of conditions and the following disclaimer in the
13 // documentation and/or other materials provided with the distribution.
14 //
15 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
16 // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
17 // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
18 // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
19 // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
20 // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
21 // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
22 // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
23 // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
24 // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 
27 #include "sensor_pose3d.h"
28 
30 
31 namespace g2o {
32  using namespace std;
33  using namespace Eigen;
34 
35  SensorPose3D::SensorPose3D(const std::string& name_): BinarySensor<Robot3D, EdgeSE3, WorldObjectSE3>(name_){
36  _stepsToIgnore = 10;
37  _information.setIdentity();
38  _information*=100;
39  _information(3,3)=10000;
40  _information(4,4)=10000;
41  _information(5,5)=1000;
43  }
44 
48  e->setMeasurement(e->measurement()*n);
50  }
51 
53  if (! _robotPoseObject)
54  return false;
55  if (_posesToIgnore.find(to)!=_posesToIgnore.end())
56  return false;
57 
58  assert(to && to->vertex());
59  VertexType* v=to->vertex();
60  VertexType::EstimateType pose=v->estimate();
61  VertexType::EstimateType delta = _robotPoseObject->vertex()->estimate().inverse()*pose;
62  Vector3d translation=delta.translation();
63  double range2=translation.squaredNorm();
64  if (range2>_maxRange2)
65  return false;
66  if (range2<_minRange2)
67  return false;
68  translation.normalize();
69  double bearing=acos(translation.x());
70  if (fabs(bearing)>_fov)
71  return false;
72  AngleAxisd a(delta.rotation());
73  if (fabs(a.angle())>_maxAngularDifference)
74  return false;
75  return true;
76  }
77 
78 
81  RobotType* r= dynamic_cast<RobotType*>(robot());
82  std::list<PoseObject*>::reverse_iterator it=r->trajectory().rbegin();
83  _posesToIgnore.clear();
84  int count = 0;
85  while (it!=r->trajectory().rend() && count < _stepsToIgnore){
86  if (!_robotPoseObject)
87  _robotPoseObject = *it;
88  _posesToIgnore.insert(*it);
89  it++;
90  count++;
91  }
92  for (std::set<BaseWorldObject*>::iterator it=world()->objects().begin();
93  it!=world()->objects().end(); it++){
94  WorldObjectType* o=dynamic_cast<WorldObjectType*>(*it);
95  if (o && isVisible(o)){
96  EdgeType* e=mkEdge(o);
97  if (e && graph()) {
98  graph()->addEdge(e);
100  addNoise(e);
101  }
102  }
103  }
104  }
105 
106 }
bool isVisible(WorldObjectType *to)
GaussianSampler< typename EdgeType::ErrorVector, InformationType > _sampler
Definition: simulator.h:271
BaseEdge< D, Isometry3D >::ErrorVector ErrorVector
EIGEN_MAKE_ALIGNED_OPERATOR_NEW SensorPose3D(const std::string &name_)
SampleType generateSample()
Definition: sampler.h:67
BaseEdge< D, Isometry3D >::Measurement Measurement
Edge between two 3D pose vertices.
Definition: edge_se3.h:18
virtual bool setMeasurementFromState()
Definition: edge_se3.cpp:59
World * world()
Definition: simulator.cpp:69
void addNoise(EdgeType *e)
virtual void setMeasurement(const Isometry3D &m)
Definition: edge_se3.h:27
EIGEN_STRONG_INLINE void setInformation(const InformationType &information)
Definition: base_edge.h:69
TrajectoryType & trajectory()
Definition: simulator.h:119
OptimizableGraph * graph()
Definition: simulator.cpp:75
BaseRobot * robot()
Definition: simulator.h:129
std::set< BaseWorldObject * > & objects()
Definition: simulator.h:284
std::set< PoseObject * > _posesToIgnore
Definition: sensor_pose3d.h:49
virtual bool addEdge(HyperGraph::Edge *e)
virtual void sense()
Isometry3D fromVectorMQT(const Vector6d &v)
VertexType * vertex()
Definition: simulator.h:72
void setInformation(const InformationType &information_)
Definition: simulator.h:221
EdgeType * mkEdge(WorldObjectType *object)
Definition: simulator.h:263
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
Definition: base_edge.h:75