g2o
sensor_pose3d_offset.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_offset.h"
28 
30 
31 namespace g2o {
32  using namespace std;
33  using namespace Eigen;
34 
35  SensorPose3DOffset::SensorPose3DOffset(const std::string& name_):
38  _stepsToIgnore = 10;
39  _information.setIdentity();
40  _information*=100;
41  _information(3,3)=10000;
42  _information(4,4)=10000;
43  _information(5,5)=1000;
45  }
46 
48  if (!_offsetParam1)
50  if (!_offsetParam2)
52  assert(world());
55  }
56 
60  e->setMeasurement(e->measurement()*n);
62  }
63 
65  if (! _robotPoseObject)
66  return false;
67  if (_posesToIgnore.find(to)!=_posesToIgnore.end())
68  return false;
69 
70  assert(to && to->vertex());
71  VertexType* v=to->vertex();
72  VertexType::EstimateType pose=v->estimate();
73  VertexType::EstimateType delta = _robotPoseObject->vertex()->estimate().inverse()*pose;
74  Vector3d translation=delta.translation();
75  double range2=translation.squaredNorm();
76  if (range2>_maxRange2)
77  return false;
78  if (range2<_minRange2)
79  return false;
80  translation.normalize();
81  double bearing=acos(translation.x());
82  if (fabs(bearing)>_fov)
83  return false;
84  AngleAxisd a(delta.rotation());
85  if (fabs(a.angle())>_maxAngularDifference)
86  return false;
87  return true;
88  }
89 
90 
93  RobotType* r= dynamic_cast<RobotType*>(robot());
94  std::list<PoseObject*>::reverse_iterator it=r->trajectory().rbegin();
95  _posesToIgnore.clear();
96  int count = 0;
97  while (it!=r->trajectory().rend() && count < _stepsToIgnore){
98  if (!_robotPoseObject)
99  _robotPoseObject = *it;
100  _posesToIgnore.insert(*it);
101  it++;
102  count++;
103  }
104  for (std::set<BaseWorldObject*>::iterator it=world()->objects().begin();
105  it!=world()->objects().end(); it++){
106  WorldObjectType* o=dynamic_cast<WorldObjectType*>(*it);
107  if (o && isVisible(o)){
108  EdgeType* e=mkEdge(o);
109  if (e && graph()) {
112  graph()->addEdge(e);
114  addNoise(e);
115  }
116  }
117  }
118  }
119 
120 }
bool addParameter(Parameter *p)
Definition: simulator.cpp:102
bool isVisible(WorldObjectType *to)
std::set< PoseObject * > _posesToIgnore
GaussianSampler< typename EdgeType::ErrorVector, InformationType > _sampler
Definition: simulator.h:271
BaseEdge< D, Isometry3D >::ErrorVector ErrorVector
SampleType generateSample()
Definition: sampler.h:67
BaseEdge< D, Isometry3D >::Measurement Measurement
virtual bool setMeasurementFromState()
ParameterSE3Offset * _offsetParam1
bool setParameterId(int argNum, int paramId)
World * world()
Definition: simulator.cpp:69
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
int id() const
Definition: parameter.h:45
ParameterSE3Offset * _offsetParam2
EIGEN_MAKE_ALIGNED_OPERATOR_NEW SensorPose3DOffset(const std::string &name_)
OptimizableGraph * graph()
Definition: simulator.cpp:75
BaseRobot * robot()
Definition: simulator.h:129
std::set< BaseWorldObject * > & objects()
Definition: simulator.h:284
virtual bool addEdge(HyperGraph::Edge *e)
Isometry3D fromVectorMQT(const Vector6d &v)
VertexType * vertex()
Definition: simulator.h:72
void setInformation(const InformationType &information_)
Definition: simulator.h:221
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
Definition: base_edge.h:75