Skip to content

Commit a336830

Browse files
committed
Proper forwarding of messages (Code C4099)
1 parent 988635e commit a336830

File tree

1 file changed

+19
-19
lines changed

1 file changed

+19
-19
lines changed

tf2/include/tf2/impl/stamped_traits.h

Lines changed: 19 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -41,43 +41,43 @@ namespace geometry_msgs
4141
namespace msg
4242
{
4343
template<typename Alloc>
44-
class Point_;
44+
struct Point_;
4545
template<typename Alloc>
46-
class Vector_;
46+
struct Vector_;
4747
template<typename Alloc>
48-
class Quaternion_;
48+
struct Quaternion_;
4949
template<typename Alloc>
50-
class Pose_;
50+
struct Pose_;
5151
template<typename Alloc>
52-
class Twist_;
52+
struct Twist_;
5353
template<typename Alloc>
54-
class PoseWithCovariance_;
54+
struct PoseWithCovariance_;
5555
template<typename Alloc>
56-
class Wrench_;
56+
struct Wrench_;
5757
template<typename Alloc>
58-
class PointStamped_;
58+
struct PointStamped_;
5959
template<typename Alloc>
60-
class VectorStamped_;
60+
struct VectorStamped_;
6161
template<typename Alloc>
62-
class QuaternionStamped_;
62+
struct QuaternionStamped_;
6363
template<typename Alloc>
64-
class PoseStamped_;
64+
struct PoseStamped_;
6565
template<typename Alloc>
66-
class TwistStamped_;
66+
struct TwistStamped_;
6767
template<typename Alloc>
68-
class PoseWithCovarianceStamped_;
68+
struct PoseWithCovarianceStamped_;
6969
template<typename Alloc>
70-
class WrenchStamped_;
70+
struct WrenchStamped_;
7171
template<typename Alloc>
72-
class TransformStamped_;
72+
struct TransformStamped_;
7373
template<typename Alloc>
74-
class Transform_;
74+
struct Transform_;
7575
template<typename Alloc>
76-
class Vector3_;
76+
struct Vector3_;
7777
template<typename Alloc>
78-
class Vector3Stamped_;
78+
struct Vector3Stamped_;
7979
template<typename Alloc>
80-
class TwistWithCovarianceStamped_;
80+
struct TwistWithCovarianceStamped_;
8181
} // namespace msg
8282
} // namespace geometry_msgs
8383

0 commit comments

Comments
 (0)