14 #include <geometry_msgs/Pose.h> 15 #include <geometry_msgs/PoseStamped.h> 23 template <
typename T> std::string
nb2str(T x)
25 return static_cast<std::ostringstream*
>( &(std::ostringstream() << x) )->str();
28 template <
typename T> T
median(
const std::vector<T>& v) {
31 std::nth_element(c.begin(), c.begin() + c.size()/2, c.end());
35 template <
typename T> T
mean(
const std::vector<T>& v)
38 for (
unsigned int i = 0; i < v.size(); i++)
43 template <
typename T> T
variance(
const std::vector<T>& v)
47 for (
unsigned int i = 0; i < v.size(); i++)
48 acc += std::pow(v[i] - avg, 2);
49 return acc/(v.size() - 1);
52 template <
typename T> T
std_dev(
const std::vector<T>& v)
58 template <
typename T> T
sign(T x)
60 return x > 0.0 ? +1.0 : x < 0.0 ? -1.0 : 0.0;
71 std::string
vector2str3D(
const geometry_msgs::Vector3& vector);
72 std::string
vector2str3D(
const geometry_msgs::Vector3Stamped& vector);
73 std::string
point2str2D(
const geometry_msgs::Point& point);
74 std::string
point2str2D(
const geometry_msgs::PointStamped& point);
75 std::string
point2str3D(
const geometry_msgs::Point& point);
76 std::string
point2str3D(
const geometry_msgs::PointStamped& point);
77 std::string
pose2str2D(
const geometry_msgs::Pose& pose);
78 std::string
pose2str2D(
const geometry_msgs::PoseStamped& pose);
79 std::string
pose2str3D(
const geometry_msgs::Pose& pose);
80 std::string
pose2str3D(
const geometry_msgs::PoseStamped& pose);
T median(const std::vector< T > &v)
void pose2tf(const geometry_msgs::Pose &pose, tf::Transform &tf)
T mean(const std::vector< T > &v)
T variance(const std::vector< T > &v)
std::string pose2str2D(const geometry_msgs::Pose &pose)
std::string pose2str3D(const geometry_msgs::Pose &pose)
std::string vector2str3D(const geometry_msgs::Vector3 &vector)
std::string point2str3D(const geometry_msgs::Point &point)
T std_dev(const std::vector< T > &v)
void tf2pose(const tf::Transform &tf, geometry_msgs::Pose &pose)
ECL_DEPRECATED const char * pose2str(const geometry_msgs::Pose &pose)
ECL_DEPRECATED const char * point2str(const geometry_msgs::Point &point)
std::string point2str2D(const geometry_msgs::Point &point)