-
Notifications
You must be signed in to change notification settings - Fork 112
/
position_2d_stamped.h
148 lines (128 loc) · 4.88 KB
/
position_2d_stamped.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
/*
* 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_POSITION_2D_STAMPED_H
#define FUSE_VARIABLES_POSITION_2D_STAMPED_H
#include <fuse_core/ceres_macros.h>
#include <fuse_core/manifold.h>
#include <fuse_core/serialization.h>
#include <fuse_core/uuid.h>
#include <fuse_core/variable.h>
#include <fuse_variables/fixed_size_variable.h>
#include <fuse_variables/stamped.h>
#include <ros/time.h>
#include <boost/serialization/access.hpp>
#include <boost/serialization/base_object.hpp>
#include <boost/serialization/export.hpp>
#include <ostream>
namespace fuse_variables
{
/**
* @brief Variable representing a 2D position (x, y) at a specific time, with a specific piece of hardware.
*
* This is commonly used to represent a robot's position within a map. The UUID of this class is static after
* construction. As such, the timestamp and device id cannot be modified. The value of the position can be modified.
*/
class Position2DStamped : public FixedSizeVariable<2>, public Stamped
{
public:
FUSE_VARIABLE_DEFINITIONS(Position2DStamped);
/**
* @brief Can be used to directly index variables in the data array
*/
enum : size_t
{
X = 0,
Y = 1
};
/**
* @brief Default constructor
*/
Position2DStamped() = default;
/**
* @brief Construct a 2D position at a specific point in time.
*
* @param[in] stamp The timestamp attached to this position.
* @param[in] device_id An optional device id, for use when variables originate from multiple robots or devices
*
*/
explicit Position2DStamped(const ros::Time& stamp, const fuse_core::UUID& device_id = fuse_core::uuid::NIL);
/**
* @brief Read-write access to the X-axis position.
*/
double& x() { return data_[X]; }
/**
* @brief Read-only access to the X-axis position.
*/
const double& x() const { return data_[X]; }
/**
* @brief Read-write access to the Y-axis position.
*/
double& y() { return data_[Y]; }
/**
* @brief Read-only access to the Y-axis position.
*/
const double& y() const { return data_[Y]; }
/**
* @brief Print a human-readable description of the variable to the provided stream.
*
* @param[out] stream The stream to write to. Defaults to stdout.
*/
void print(std::ostream& stream = std::cout) const override;
#if CERES_SUPPORTS_MANIFOLDS
/**
* @brief Create a null Ceres manifold
*
* Overriding the manifold() method prevents additional processing with the ManifoldAdapter
*/
fuse_core::Manifold* manifold() const override { return nullptr; }
#endif
private:
// Allow Boost Serialization access to private methods
friend class boost::serialization::access;
/**
* @brief The Boost Serialize method that serializes all of the data members in to/out of the archive
*
* @param[in/out] archive - The archive object that holds the serialized class members
* @param[in] version - The version of the archive being read/written. Generally unused.
*/
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::Position2DStamped);
#endif // FUSE_VARIABLES_POSITION_2D_STAMPED_H