17 #include <geometry_msgs/Quaternion.h>    18 #include <geometry_msgs/Pose.h>    19 #include <geometry_msgs/Vector3.h>    20 #include <sensor_msgs/CameraInfo.h>    21 #include <opencv2/opencv.hpp>    27         if (!nh.
getParam(param_name, param_val)) {
    28                 ROS_FATAL(
"Required param %s is not defined", param_name.c_str());
    33 static void parseCameraInfo(
const sensor_msgs::CameraInfoConstPtr& cinfo, cv::Mat& matrix, cv::Mat& dist)
    35         for (
unsigned int i = 0; i < 3; ++i)
    36                 for (
unsigned int j = 0; j < 3; ++j)
    37                         matrix.at<
double>(i, j) = cinfo->K[3 * i + j];
    38         dist = cv::Mat(cinfo->D, 
true);
    41 inline void rotatePoint(cv::Point3f& p, cv::Point3f origin, 
float angle)
    51         float xnew = p.x * c - p.y * s;
    52         float ynew = p.x * s + p.y * c;
    55         p.x = xnew + origin.x;
    56         p.y = ynew + origin.y;
    59 inline void fillPose(geometry_msgs::Pose& pose, 
const cv::Vec3d& rvec, 
const cv::Vec3d& tvec)
    61         pose.position.x = tvec[0];
    62         pose.position.y = tvec[1];
    63         pose.position.z = tvec[2];
    65         double angle = norm(rvec);
    66         cv::Vec3d axis = rvec / angle;
    69         q.
setRotation(tf2::Vector3(axis[0], axis[1], axis[2]), angle);
    71         pose.orientation.w = q.w();
    72         pose.orientation.x = q.x();
    73         pose.orientation.y = q.y();
    74         pose.orientation.z = q.z();
    77 inline void fillTransform(geometry_msgs::Transform& transform, 
const cv::Vec3d& rvec, 
const cv::Vec3d& tvec)
    79         transform.translation.x = tvec[0];
    80         transform.translation.y = tvec[1];
    81         transform.translation.z = tvec[2];
    83         double angle = norm(rvec);
    84         cv::Vec3d axis = rvec / angle;
    87         q.
setRotation(tf2::Vector3(axis[0], axis[1], axis[2]), angle);
    89         transform.rotation.w = q.w();
    90         transform.rotation.x = q.x();
    91         transform.rotation.y = q.y();
    92         transform.rotation.z = q.z();
    95 inline void fillTranslation(geometry_msgs::Vector3& translation, 
const cv::Vec3d& tvec)
    97         translation.x = tvec[0];
    98         translation.y = tvec[1];
    99         translation.z = tvec[2];
   104         double yaw, pitch, roll;
   106         return (
abs(pitch) > M_PI / 2) || (
abs(roll) > M_PI / 2);
   110 inline void snapOrientation(geometry_msgs::Quaternion& to, 
const geometry_msgs::Quaternion& from, 
bool auto_flip = 
false)
   125         diff.getRPY(_, _, yaw);
   131 inline void transformToPose(
const geometry_msgs::Transform& transform, geometry_msgs::Pose& pose)
   133         pose.position.x = transform.translation.x;
   134         pose.position.y = transform.translation.y;
   135         pose.position.z = transform.translation.z;
   136         pose.orientation = transform.rotation;
 Matrix3x3 transposeTimes(const Matrix3x3 &m) const
static tf::Quaternion createQuaternionFromRPY(double roll, double pitch, double yaw)
void snapOrientation(geometry_msgs::Quaternion &to, const geometry_msgs::Quaternion &from, bool auto_flip=false)
static void param(ros::NodeHandle nh, const std::string ¶m_name, T ¶m_val)
void fillPose(geometry_msgs::Pose &pose, const cv::Vec3d &rvec, const cv::Vec3d &tvec)
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
static void parseCameraInfo(const sensor_msgs::CameraInfoConstPtr &cinfo, cv::Mat &matrix, cv::Mat &dist)
void getEulerYPR(tfScalar &yaw, tfScalar &pitch, tfScalar &roll, unsigned int solution_number=1) const
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
bool isFlipped(tf::Quaternion &q)
void fillTranslation(geometry_msgs::Vector3 &translation, const cv::Vec3d &tvec)
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
bool getParam(const std::string &key, std::string &s) const
static void quaternionTFToMsg(const Quaternion &bt, geometry_msgs::Quaternion &msg)
void setRotation(const Vector3 &axis, const tf2Scalar &angle)
void transformToPose(const geometry_msgs::Transform &transform, geometry_msgs::Pose &pose)
INLINE Rall1d< T, V, S > abs(const Rall1d< T, V, S > &x)
ROSCPP_DECL void shutdown()
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
void rotatePoint(cv::Point3f &p, cv::Point3f origin, float angle)
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
void fillTransform(geometry_msgs::Transform &transform, const cv::Vec3d &rvec, const cv::Vec3d &tvec)