g2o
Loading...
Searching...
No Matches
Public Member Functions | Public Attributes | List of all members
PlaneSensor Struct Reference
Inheritance diagram for PlaneSensor:
Inheritance graph
[legend]
Collaboration diagram for PlaneSensor:
Collaboration graph
[legend]

Public Member Functions

 PlaneSensor (Robot *r, int offsetId, const Isometry3d &offset_)
 
virtual bool isVisible (const WorldItem *wi) const
 
virtual bool sense (WorldItem *wi, const Isometry3d &position)
 
- Public Member Functions inherited from Sensor
 Sensor (Robot *robot_)
 
Robotrobot ()
 
virtual ~Sensor ()
 
 Sensor (Robot *robot_)
 
Robotrobot ()
 
virtual ~Sensor ()
 

Public Attributes

 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
VertexSE3_offsetVertex
 
Vector3d _nplane
 

Additional Inherited Members

- Protected Attributes inherited from Sensor
Robot_robot
 

Detailed Description

Definition at line 207 of file simulator_3d_plane.cpp.

Constructor & Destructor Documentation

◆ PlaneSensor()

PlaneSensor::PlaneSensor ( Robot r,
int  offsetId,
const Isometry3d &  offset_ 
)
inline

Definition at line 210 of file simulator_3d_plane.cpp.

210 : Sensor(r) {
211 _offsetVertex = new VertexSE3();
212 _offsetVertex->setId(offsetId);
213 _offsetVertex->setEstimate(offset_);
215 };
OptimizableGraph * graph() const
Definition simulator.cpp:46
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
3D pose Vertex, represented as an Isometry3
Definition vertex_se3.h:50
VertexSE3 * _offsetVertex
Robot * robot()
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)

References _offsetVertex, g2o::OptimizableGraph::addVertex(), g2o::BaseRobot::graph(), Sensor::robot(), g2o::BaseVertex< D, T >::setEstimate(), and g2o::OptimizableGraph::Vertex::setId().

Member Function Documentation

◆ isVisible()

virtual bool PlaneSensor::isVisible ( const WorldItem wi) const
inlinevirtual

Reimplemented from Sensor.

Definition at line 217 of file simulator_3d_plane.cpp.

217 {
218 if (!wi) return false;
219 const PlaneItem* pi = dynamic_cast<const PlaneItem*>(wi);
220 if (!pi) return false;
221 return true;
222 }

◆ sense()

virtual bool PlaneSensor::sense ( WorldItem wi,
const Isometry3d &  position 
)
inlinevirtual

Reimplemented from Sensor.

Definition at line 224 of file simulator_3d_plane.cpp.

224 {
225 if (!wi) return false;
226 PlaneItem* pi = dynamic_cast<PlaneItem*>(wi);
227 if (!pi) return false;
228 OptimizableGraph::Vertex* rv = robot()->vertex();
229 if (!rv) {
230 return false;
231 }
232 VertexSE3* robotVertex = dynamic_cast<VertexSE3*>(rv);
233 if (!robotVertex) {
234 return false;
235 }
236 const Isometry3d& robotPose = position;
237 Isometry3d sensorPose = robotPose * _offsetVertex->estimate();
238 VertexPlane* planeVertex = dynamic_cast<VertexPlane*>(pi->vertex());
239 Plane3D worldPlane = planeVertex->estimate();
240
241 Plane3D measuredPlane = sensorPose.inverse() * worldPlane;
242
244 e->vertices()[0] = robotVertex;
245 e->vertices()[1] = planeVertex;
246 e->vertices()[2] = _offsetVertex;
247 Vector3d noise = sample_noise_from_plane(_nplane);
248 measuredPlane.oplus(noise);
249 e->setMeasurement(measuredPlane);
250 Matrix3d m = Matrix3d::Zero();
251 m(0, 0) = 1. / (_nplane(0));
252 m(1, 1) = 1. / (_nplane(1));
253 m(2, 2) = 1. / (_nplane(2));
254 e->setInformation(m);
255 robot()->graph()->addEdge(e);
256 return true;
257 }
void setInformation(const InformationType &information)
Definition base_edge.h:111
const EstimateType & estimate() const
return the current estimate of the vertex
plane measurement that also calibrates an offset for the sensor
void setMeasurement(const Plane3D &m)
const VertexContainer & vertices() const
A general case Vertex for optimization.
void oplus(const Vector3 &v)
Definition plane3d.h:75
Vector3d sample_noise_from_plane(const Vector3d &cov)
OptimizableGraph::Vertex * vertex()
virtual bool addEdge(HyperGraph::Edge *e)

References _nplane, _offsetVertex, g2o::OptimizableGraph::addEdge(), g2o::BaseVertex< D, T >::estimate(), g2o::BaseRobot::graph(), g2o::Plane3D::oplus(), Sensor::robot(), sample_noise_from_plane(), g2o::BaseEdge< D, E >::setInformation(), g2o::EdgeSE3PlaneSensorCalib::setMeasurement(), WorldItem::vertex(), and g2o::HyperGraph::Edge::vertices().

Member Data Documentation

◆ _nplane

Vector3d PlaneSensor::_nplane

Definition at line 260 of file simulator_3d_plane.cpp.

Referenced by main(), and sense().

◆ _offsetVertex

VertexSE3* PlaneSensor::_offsetVertex

Definition at line 259 of file simulator_3d_plane.cpp.

Referenced by main(), PlaneSensor(), and sense().

◆ EIGEN_MAKE_ALIGNED_OPERATOR_NEW

PlaneSensor::EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Definition at line 208 of file simulator_3d_plane.cpp.


The documentation for this struct was generated from the following file: