12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576 |
- // g2o - General Graph Optimization
- // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard
- // All rights reserved.
- //
- // Redistribution and use in source and binary forms, with or without
- // modification, are permitted provided that the following conditions are
- // met:
- //
- // * Redistributions of source code must retain the above copyright notice,
- // this list of conditions and the following disclaimer.
- // * Redistributions in binary form must reproduce the above copyright
- // notice, this list of conditions and the following disclaimer in the
- // documentation and/or other materials provided with the distribution.
- //
- // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
- // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
- // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
- // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
- // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
- // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
- // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
- // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
- // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
- // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
- // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
- #ifndef KKL_G2O_EDGE_SE3_PRIORVEC_HPP
- #define KKL_G2O_EDGE_SE3_PRIORVEC_HPP
- #include <g2o/types/slam3d/types_slam3d.h>
- #include <g2o/types/slam3d_addons/types_slam3d_addons.h>
- namespace g2o {
- class EdgeSE3PriorVec : public g2o::BaseUnaryEdge<3, Eigen::Matrix<double, 6, 1>, g2o::VertexSE3> {
- public:
- EIGEN_MAKE_ALIGNED_OPERATOR_NEW
- EdgeSE3PriorVec() : g2o::BaseUnaryEdge<3, Eigen::Matrix<double, 6, 1>, g2o::VertexSE3>() {}
- void computeError() override {
- const g2o::VertexSE3* v1 = static_cast<const g2o::VertexSE3*>(_vertices[0]);
- Eigen::Vector3d direction = _measurement.head<3>();
- Eigen::Vector3d measurement = _measurement.tail<3>();
- Eigen::Vector3d estimate = (v1->estimate().linear().inverse() * direction);
- _error = estimate - measurement;
- }
- void setMeasurement(const Eigen::Matrix<double, 6, 1>& m) override {
- _measurement.head<3>() = m.head<3>().normalized();
- _measurement.tail<3>() = m.tail<3>().normalized();
- }
- virtual bool read(std::istream& is) override {
- Eigen::Matrix<double, 6, 1> v;
- is >> v[0] >> v[1] >> v[2] >> v[3] >> v[4] >> v[5];
- setMeasurement(v);
- for(int i = 0; i < information().rows(); ++i)
- for(int j = i; j < information().cols(); ++j) {
- is >> information()(i, j);
- if(i != j) information()(j, i) = information()(i, j);
- }
- return true;
- }
- virtual bool write(std::ostream& os) const override {
- Eigen::Matrix<double, 6, 1> v = _measurement;
- os << v[0] << " " << v[1] << " " << v[2] << " " << v[3] << " " << v[4] << " " << v[5];
- for(int i = 0; i < information().rows(); ++i)
- for(int j = i; j < information().cols(); ++j) os << " " << information()(i, j);
- return os.good();
- }
- };
- } // namespace g2o
- #endif
|