Program Listing for File acceleration_linear_3d_stamped.hpp
↰ Return to documentation for file (include/fuse_variables/acceleration_linear_3d_stamped.hpp
)
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2018, Locus Robotics
* 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.
* * Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* 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 FUSE_VARIABLES__ACCELERATION_LINEAR_3D_STAMPED_HPP_
#define FUSE_VARIABLES__ACCELERATION_LINEAR_3D_STAMPED_HPP_
#include <ostream>
#include <fuse_core/ceres_macros.hpp>
#include <fuse_core/manifold.hpp>
#include <fuse_core/serialization.hpp>
#include <fuse_core/uuid.hpp>
#include <fuse_core/variable.hpp>
#include <fuse_variables/fixed_size_variable.hpp>
#include <fuse_variables/stamped.hpp>
#include <boost/serialization/access.hpp>
#include <boost/serialization/base_object.hpp>
#include <boost/serialization/export.hpp>
#include <rclcpp/time.hpp>
namespace fuse_variables
{
class AccelerationLinear3DStamped : public FixedSizeVariable<3>, public Stamped
{
public:
FUSE_VARIABLE_DEFINITIONS(AccelerationLinear3DStamped)
enum : size_t
{
X = 0,
Y = 1,
Z = 2
};
AccelerationLinear3DStamped() = default;
explicit AccelerationLinear3DStamped(
const rclcpp::Time & stamp,
const fuse_core::UUID & device_id = fuse_core::uuid::NIL);
double & x() {return data_[X];}
const double & x() const {return data_[X];}
double & y() {return data_[Y];}
const double & y() const {return data_[Y];}
double & z() {return data_[Z];}
const double & z() const {return data_[Z];}
void print(std::ostream & stream = std::cout) const override;
#if CERES_SUPPORTS_MANIFOLDS
fuse_core::Manifold * manifold() const override {return nullptr;}
#endif
private:
// Allow Boost Serialization access to private methods
friend class boost::serialization::access;
template<class Archive>
void serialize(Archive & archive, const unsigned int /* version */)
{
archive & boost::serialization::base_object<FixedSizeVariable<SIZE>>(*this);
archive & boost::serialization::base_object<Stamped>(*this);
}
};
} // namespace fuse_variables
BOOST_CLASS_EXPORT_KEY(fuse_variables::AccelerationLinear3DStamped);
#endif // FUSE_VARIABLES__ACCELERATION_LINEAR_3D_STAMPED_HPP_