add more files msgs
This commit is contained in:
@@ -23,6 +23,19 @@ struct Accel
|
||||
: linear(linear_), angular(angular_) {}
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::Accel &lhs, const geometry_msgs::Accel &rhs)
|
||||
{
|
||||
return lhs.linear == rhs.linear &&
|
||||
lhs.angular == rhs.angular;
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::Accel &lhs, const geometry_msgs::Accel &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif // ACCEL_H
|
||||
|
||||
@@ -19,6 +19,18 @@ struct AccelStamped
|
||||
AccelStamped() = default;
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::AccelStamped &lhs, const geometry_msgs::AccelStamped &rhs)
|
||||
{
|
||||
return lhs.header == rhs.header &&
|
||||
lhs.accel == rhs.accel;
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::AccelStamped &lhs, const geometry_msgs::AccelStamped &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif // ACCEL_STAMPED_H
|
||||
|
||||
@@ -22,9 +22,27 @@ struct AccelWithCovariance
|
||||
Accel accel;
|
||||
std::array<double, 36> covariance;
|
||||
// Constructor mặc định
|
||||
AccelWithCovariance() = default;
|
||||
AccelWithCovariance() : accel(), covariance{{0.0}} {};
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::AccelWithCovariance &lhs, const geometry_msgs::AccelWithCovariance &rhs)
|
||||
{
|
||||
for(size_t i = 0; i < 36; ++i)
|
||||
{
|
||||
if (isEqual(lhs.covariance[i], rhs.covariance[i]) == false)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return lhs.accel == rhs.accel;
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::AccelWithCovariance &lhs, const geometry_msgs::AccelWithCovariance &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif // ACCEL_WITH_COVARIANCE_H
|
||||
|
||||
@@ -19,6 +19,18 @@ struct AccelWithCovarianceStamped
|
||||
AccelWithCovarianceStamped() = default;
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::AccelWithCovarianceStamped &lhs, const geometry_msgs::AccelWithCovarianceStamped &rhs)
|
||||
{
|
||||
return lhs.header == rhs.header &&
|
||||
lhs.accel == rhs.accel;
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::AccelWithCovarianceStamped &lhs, const geometry_msgs::AccelWithCovarianceStamped &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif // ACCEL_WITH_COVARIANCE_STAMPED_H
|
||||
|
||||
@@ -1,20 +1,3 @@
|
||||
// # Mass [kg]
|
||||
// float64 m
|
||||
|
||||
// # Center of mass [m]
|
||||
// geometry_msgs/Vector3 com
|
||||
|
||||
// # Inertia Tensor [kg-m^2]
|
||||
// # | ixx ixy ixz |
|
||||
// # I = | ixy iyy iyz |
|
||||
// # | ixz iyz izz |
|
||||
// float64 ixx
|
||||
// float64 ixy
|
||||
// float64 ixz
|
||||
// float64 iyy
|
||||
// float64 iyz
|
||||
// float64 izz
|
||||
|
||||
#ifndef INERTIA_H
|
||||
#define INERTIA_H
|
||||
|
||||
@@ -33,8 +16,46 @@ struct Inertia
|
||||
double iyy;
|
||||
double iyz;
|
||||
double izz;
|
||||
|
||||
Inertia() :
|
||||
m(0.0),
|
||||
com(),
|
||||
ixx(0.0),
|
||||
ixy(0.0),
|
||||
ixz(0.0),
|
||||
iyy(0.0),
|
||||
iyz(0.0),
|
||||
izz(0.0) {};
|
||||
Inertia(double m_, Vector3 com_, double ixx_, double ixy_, double ixz_,
|
||||
double iyy_, double iyz_, double izz_) :
|
||||
m(m_),
|
||||
com(com_),
|
||||
ixx(ixx_),
|
||||
ixy(ixy_),
|
||||
ixz(ixz_),
|
||||
iyy(iyy_),
|
||||
iyz(iyz_),
|
||||
izz(izz_) {};
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::Inertia &lhs, const geometry_msgs::Inertia &rhs)
|
||||
{
|
||||
return isEqual(lhs.m, rhs.m) &&
|
||||
lhs.com == rhs.com &&
|
||||
isEqual(lhs.ixx, rhs.ixx) &&
|
||||
isEqual(lhs.ixy, rhs.ixy) &&
|
||||
isEqual(lhs.ixz, rhs.ixz) &&
|
||||
isEqual(lhs.iyy, rhs.iyy) &&
|
||||
isEqual(lhs.iyz, rhs.iyz) &&
|
||||
isEqual(lhs.izz, rhs.izz);
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::Inertia &lhs, const geometry_msgs::Inertia &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif // INERTIA_H
|
||||
|
||||
@@ -18,6 +18,18 @@ struct InertiaStamped
|
||||
InertiaStamped() = default;
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::InertiaStamped &lhs, const geometry_msgs::InertiaStamped &rhs)
|
||||
{
|
||||
return lhs.header == rhs.header &&
|
||||
lhs.inertia == rhs.inertia;
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::InertiaStamped &lhs, const geometry_msgs::InertiaStamped &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif // INERTIA_STAMPED_H
|
||||
@@ -3,6 +3,7 @@
|
||||
|
||||
#include <cmath>
|
||||
#include <iostream>
|
||||
#include "utils.h"
|
||||
|
||||
namespace geometry_msgs
|
||||
{
|
||||
@@ -21,6 +22,20 @@ struct Point
|
||||
: x(x_), y(y_), z(z_) {}
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::Point &lhs, const geometry_msgs::Point &rhs)
|
||||
{
|
||||
return isEqual(lhs.x, rhs.x) &&
|
||||
isEqual(lhs.y, rhs.y) &&
|
||||
isEqual(lhs.z, rhs.z);
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::Point &lhs, const geometry_msgs::Point &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif // POINT_H
|
||||
@@ -1,6 +1,8 @@
|
||||
#ifndef POINT_32_H
|
||||
#define POINT_32_H
|
||||
|
||||
#include "utils.h"
|
||||
|
||||
namespace geometry_msgs
|
||||
{
|
||||
struct Point32
|
||||
@@ -8,7 +10,25 @@ struct Point32
|
||||
float x;
|
||||
float y;
|
||||
float z;
|
||||
|
||||
Point32() : x(0.0f), y(0.0f), z(0.0f) {}
|
||||
Point32(float x_, float y_, float z_)
|
||||
: x(x_), y(y_), z(z_) {}
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::Point32 &lhs, const geometry_msgs::Point32 &rhs)
|
||||
{
|
||||
return isEqual(lhs.x, rhs.x) &&
|
||||
isEqual(lhs.y, rhs.y) &&
|
||||
isEqual(lhs.z, rhs.z);
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::Point32 &lhs, const geometry_msgs::Point32 &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif //POINT_32_H
|
||||
@@ -16,6 +16,19 @@ struct PointStamped
|
||||
PointStamped() = default;
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::PointStamped &lhs, const geometry_msgs::PointStamped &rhs)
|
||||
{
|
||||
return lhs.header == rhs.header &&
|
||||
lhs.point == rhs.point;
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::PointStamped &lhs, const geometry_msgs::PointStamped &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif //POINT_STAMPED_H
|
||||
@@ -11,6 +11,23 @@ struct Polygon
|
||||
std::vector<geometry_msgs::Point32> points;
|
||||
};
|
||||
|
||||
inline bool operator==(const geometry_msgs::Polygon &lhs, const geometry_msgs::Polygon &rhs)
|
||||
{
|
||||
if(lhs.points.size() != rhs.points.size())
|
||||
return false;
|
||||
for(int i = 0; i < lhs.points.size(); i++)
|
||||
{
|
||||
if(!(lhs.points[i] == rhs.points[i]))
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::Polygon &lhs, const geometry_msgs::Polygon &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif //POLYGON_H
|
||||
|
||||
@@ -16,6 +16,17 @@ struct PolygonStamped
|
||||
Polygon polygon;
|
||||
};
|
||||
|
||||
inline bool operator==(const geometry_msgs::PolygonStamped &lhs, const geometry_msgs::PolygonStamped &rhs)
|
||||
{
|
||||
return lhs.header == rhs.header &&
|
||||
lhs.polygon == rhs.polygon;
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::PolygonStamped &lhs, const geometry_msgs::PolygonStamped &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif //POLYGON_STAMPED_H
|
||||
|
||||
@@ -15,8 +15,23 @@ struct Pose
|
||||
Quaternion orientation;
|
||||
|
||||
Pose() = default;
|
||||
|
||||
Pose(Point position_, Quaternion orientation_)
|
||||
: position(position_), orientation(orientation_) {};
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::Pose &lhs, const geometry_msgs::Pose &rhs)
|
||||
{
|
||||
return lhs.position == rhs.position &&
|
||||
lhs.orientation == rhs.orientation;
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::Pose &lhs, const geometry_msgs::Pose &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif // POSE_H
|
||||
@@ -15,6 +15,8 @@
|
||||
#ifndef POSE2D_H
|
||||
#define POSE2D_H
|
||||
|
||||
#include "utils.h"
|
||||
|
||||
namespace geometry_msgs
|
||||
{
|
||||
|
||||
@@ -23,8 +25,25 @@ struct Pose2D
|
||||
double x;
|
||||
double y;
|
||||
double theta;
|
||||
|
||||
Pose2D() : x(0.0), y(0.0), theta(0.0) {}
|
||||
Pose2D(double x_, double y_, double theta_)
|
||||
: x(x_), y(y_), theta(theta_) {}
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::Pose2D &lhs, const geometry_msgs::Pose2D &rhs)
|
||||
{
|
||||
return isEqual(lhs.x, rhs.x) &&
|
||||
isEqual(lhs.y, rhs.y) &&
|
||||
isEqual(lhs.theta, rhs.theta);
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::Pose2D &lhs, const geometry_msgs::Pose2D &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif // POSE2D_H
|
||||
|
||||
@@ -23,6 +23,24 @@ struct PoseArray
|
||||
PoseArray() = default;
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::PoseArray &lhs, const geometry_msgs::PoseArray &rhs)
|
||||
{
|
||||
if(lhs.poses.size() != rhs.poses.size())
|
||||
return false;
|
||||
for(int i = 0; i < lhs.poses.size(); i++)
|
||||
{
|
||||
if(!(lhs.poses[i] == rhs.poses[i]))
|
||||
return false;
|
||||
}
|
||||
return lhs.header == rhs.header;
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::PoseArray &lhs, const geometry_msgs::PoseArray &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif // POSE_ARRAY_H
|
||||
@@ -20,6 +20,18 @@ struct PoseStamped
|
||||
PoseStamped() = default;
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::PoseStamped &lhs, const geometry_msgs::PoseStamped &rhs)
|
||||
{
|
||||
return lhs.header == rhs.header &&
|
||||
lhs.pose == rhs.pose;
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::PoseStamped &lhs, const geometry_msgs::PoseStamped &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif // POSE_STAMPED_H
|
||||
@@ -23,9 +23,27 @@ struct PoseWithCovariance
|
||||
Pose pose;
|
||||
std::array<double, 36> covariance;
|
||||
|
||||
PoseWithCovariance() = default;
|
||||
PoseWithCovariance() : pose(), covariance{{0.0}} {};
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::PoseWithCovariance &lhs, const geometry_msgs::PoseWithCovariance &rhs)
|
||||
{
|
||||
for(size_t i = 0; i < 36; ++i)
|
||||
{
|
||||
if (isEqual(lhs.covariance[i], rhs.covariance[i]) == false)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return lhs.pose == rhs.pose;
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::PoseWithCovariance &lhs, const geometry_msgs::PoseWithCovariance &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif // POSE_WITH_COVARIANCE_H
|
||||
@@ -22,6 +22,19 @@ struct PoseWithCovarianceStamped
|
||||
PoseWithCovarianceStamped() = default;
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::PoseWithCovarianceStamped &lhs, const geometry_msgs::PoseWithCovarianceStamped &rhs)
|
||||
{
|
||||
return lhs.header == rhs.header &&
|
||||
lhs.pose == rhs.pose;
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::PoseWithCovarianceStamped &lhs, const geometry_msgs::PoseWithCovarianceStamped &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif // POSE_WITH_COVARIANCE_STAMPED_H
|
||||
|
||||
@@ -1,6 +1,8 @@
|
||||
#ifndef QUATERNION_H
|
||||
#define QUATERNION_H
|
||||
|
||||
#include "utils.h"
|
||||
|
||||
namespace geometry_msgs
|
||||
{
|
||||
|
||||
@@ -19,6 +21,20 @@ struct Quaternion
|
||||
: x(x_), y(y_), z(z_), w(w_) {}
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::Quaternion &lhs, const geometry_msgs::Quaternion &rhs)
|
||||
{
|
||||
return isEqual(lhs.x, rhs.x) &&
|
||||
isEqual(lhs.y, rhs.y) &&
|
||||
isEqual(lhs.z, rhs.z) &&
|
||||
isEqual(lhs.w, rhs.w);
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::Quaternion &lhs, const geometry_msgs::Quaternion &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif // QUATERNION_H
|
||||
@@ -20,6 +20,18 @@ struct QuaternionStamped
|
||||
QuaternionStamped() = default;
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::QuaternionStamped &lhs, const geometry_msgs::QuaternionStamped &rhs)
|
||||
{
|
||||
return lhs.header == rhs.header &&
|
||||
lhs.quaternion == rhs.quaternion;
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::QuaternionStamped &lhs, const geometry_msgs::QuaternionStamped &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif // QUATERNION_STAMPED_H
|
||||
|
||||
@@ -11,8 +11,25 @@ struct Transform
|
||||
{
|
||||
Vector3 translation;
|
||||
Quaternion rotation;
|
||||
|
||||
Transform() = default;
|
||||
Transform(Vector3 translation_, Quaternion rotation_)
|
||||
: translation(translation_), rotation(rotation_) {}
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::Transform &lhs, const geometry_msgs::Transform &rhs)
|
||||
{
|
||||
return lhs.translation == rhs.translation &&
|
||||
lhs.rotation == rhs.rotation;
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::Transform &lhs, const geometry_msgs::Transform &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif // TRANSFORM_H
|
||||
@@ -15,6 +15,19 @@ struct TransformStamped
|
||||
Transform transform;
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::TransformStamped &lhs, const geometry_msgs::TransformStamped &rhs)
|
||||
{
|
||||
return lhs.header == rhs.header &&
|
||||
lhs.child_frame_id == rhs.child_frame_id &&
|
||||
lhs.transform == rhs.transform;
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::TransformStamped &lhs, const geometry_msgs::TransformStamped &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif // TRANSFORM_STAMPED_H
|
||||
@@ -23,6 +23,18 @@ struct Twist
|
||||
: linear(linear_), angular(angular_) {}
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::Twist &lhs, const geometry_msgs::Twist &rhs)
|
||||
{
|
||||
return lhs.linear == rhs.linear &&
|
||||
lhs.angular == rhs.angular;
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::Twist &lhs, const geometry_msgs::Twist &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif // ACCEL_H
|
||||
@@ -19,6 +19,18 @@ struct TwistStamped
|
||||
TwistStamped() = default;
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::TwistStamped &lhs, const geometry_msgs::TwistStamped &rhs)
|
||||
{
|
||||
return lhs.header == rhs.header &&
|
||||
lhs.twist == rhs.twist;
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::TwistStamped &lhs, const geometry_msgs::TwistStamped &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif // TWIST_STAMPED_H
|
||||
|
||||
@@ -23,9 +23,28 @@ struct TwistWithCovariance
|
||||
Twist twist;
|
||||
std::array<double, 36> covariance;
|
||||
|
||||
TwistWithCovariance() = default;
|
||||
TwistWithCovariance() : twist(), covariance{{0.0}} {};
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::TwistWithCovariance &lhs, const geometry_msgs::TwistWithCovariance &rhs)
|
||||
{
|
||||
for(size_t i = 0; i < 36; ++i)
|
||||
{
|
||||
if (isEqual(lhs.covariance[i], rhs.covariance[i]) == false)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return lhs.twist == rhs.twist;
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::TwistWithCovariance &lhs, const geometry_msgs::TwistWithCovariance &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif // TWIST_WITH_COVARIANCE_H
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
#define TWIST_WITH_COVARIANCE_STAMPED_H
|
||||
|
||||
#include <std_msgs/Header.h>
|
||||
#include <geometry_msgs/PoseWithCovariance.h>
|
||||
#include <geometry_msgs/TwistWithCovariance.h>
|
||||
|
||||
|
||||
|
||||
@@ -21,6 +21,18 @@ struct TwistWithCovarianceStamped
|
||||
TwistWithCovarianceStamped() = default;
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::TwistWithCovarianceStamped &lhs, const geometry_msgs::TwistWithCovarianceStamped &rhs)
|
||||
{
|
||||
return lhs.header == rhs.header &&
|
||||
lhs.twist == rhs.twist;
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::TwistWithCovarianceStamped &lhs, const geometry_msgs::TwistWithCovarianceStamped &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif // TWIST_WITH_COVARIANCE_STAMPED_H
|
||||
@@ -1,6 +1,8 @@
|
||||
#ifndef VECTOR_3_H
|
||||
#define VECTOR_3_H
|
||||
|
||||
#include "utils.h"
|
||||
|
||||
namespace geometry_msgs
|
||||
{
|
||||
|
||||
@@ -18,6 +20,20 @@ struct Vector3
|
||||
: x(x_), y(y_), z(z_) {}
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::Vector3 &lhs, const geometry_msgs::Vector3 &rhs)
|
||||
{
|
||||
return isEqual(lhs.x, rhs.x) &&
|
||||
isEqual(lhs.y, rhs.y) &&
|
||||
isEqual(lhs.z, rhs.z);
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::Vector3 &lhs, const geometry_msgs::Vector3 &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif // VECTOR_3_H
|
||||
@@ -19,6 +19,19 @@ struct Vector3Stamped
|
||||
Vector3Stamped() = default;
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::Vector3Stamped &lhs, const geometry_msgs::Vector3Stamped &rhs)
|
||||
{
|
||||
return lhs.header == rhs.header &&
|
||||
lhs.vector == rhs.vector;
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::Vector3Stamped &lhs, const geometry_msgs::Vector3Stamped &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif // VECTOR_3_STAMPED_H
|
||||
|
||||
@@ -17,8 +17,22 @@ struct Wrench
|
||||
Vector3 torque;
|
||||
// Constructor mặc định
|
||||
Wrench() = default;
|
||||
|
||||
Wrench(Vector3 force_, Vector3 torque_) : force(force_), torque(torque_) {};
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::Wrench &lhs, const geometry_msgs::Wrench &rhs)
|
||||
{
|
||||
return lhs.force == rhs.force &&
|
||||
lhs.torque == rhs.torque;
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::Wrench &lhs, const geometry_msgs::Wrench &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif // WRENCH_H
|
||||
|
||||
@@ -19,6 +19,18 @@ struct WrenchStamped
|
||||
WrenchStamped() = default;
|
||||
};
|
||||
|
||||
// constants requiring out of line definition
|
||||
inline bool operator==(const geometry_msgs::WrenchStamped &lhs, const geometry_msgs::WrenchStamped &rhs)
|
||||
{
|
||||
return lhs.header == rhs.header &&
|
||||
lhs.wrench == rhs.wrench;
|
||||
}
|
||||
|
||||
inline bool operator!=(const geometry_msgs::WrenchStamped &lhs, const geometry_msgs::WrenchStamped &rhs)
|
||||
{
|
||||
return !(lhs == rhs);
|
||||
}
|
||||
|
||||
} // namespace geometry_msgs
|
||||
|
||||
#endif // WRENCH_STAMPED_H
|
||||
|
||||
Reference in New Issue
Block a user