NDEVR
API Documentation
vertex_se3_expmap.h
1// g2o - General Graph Optimization
2// Copyright (C) 2011 H. Strasdat
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#pragma once
27#include "base_vertex.h"
28#include "se3quat.h"
29#include "misc.h"
30namespace NDEVR {
31
36
37
38 class VertexSE3Expmap : public BaseVertex<6, SE3Quat>
39 {
40 public:
41 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
42
47
49 void oplusImpl(const g_type* update_) override
50 {
51 Eigen::Map<const Vector6d> update(update_);
53 }
54 };
55
56}
const EstimateType & estimate() const
void setEstimate(const EstimateType &et)
SE(3) rigid body transformation represented by a unit quaternion and translation vector.
Definition se3quat.h:42
static SE3Quat exp(const Vector6d &update)
Computes the exponential map from a 6D tangent vector to SE3.
Definition se3quat.h:272
void oplusImpl(const g_type *update_) override
Applies an SE3 exponential map update to the current estimate.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW VertexSE3Expmap()
Default constructor.
some general case utility functions
The primary namespace for the NDEVR SDK.