utils.h
Go to the documentation of this file.
1 /*
2  * Utility functions
3  * Copyright (C) 2018 Copter Express Technologies
4  *
5  * Author: Oleg Kalachev <okalachev@gmail.com>
6  *
7  * Distributed under MIT License (available at https://opensource.org/licenses/MIT).
8  * The above copyright notice and this permission notice shall be included in all
9  * copies or substantial portions of the Software.
10  */
11 
12 #pragma once
13 
14 #include <cmath>
15 #include <ros/ros.h>
16 #include <tf/transform_datatypes.h>
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>
22 
23 // Read required param or shutdown the node
24 template<typename T>
25 static void param(ros::NodeHandle nh, const std::string& param_name, T& param_val)
26 {
27  if (!nh.getParam(param_name, param_val)) {
28  ROS_FATAL("Required param %s is not defined", param_name.c_str());
29  ros::shutdown();
30  }
31 }
32 
33 static void parseCameraInfo(const sensor_msgs::CameraInfoConstPtr& cinfo, cv::Mat& matrix, cv::Mat& dist)
34 {
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);
39 }
40 
41 inline void rotatePoint(cv::Point3f& p, cv::Point3f origin, float angle)
42 {
43  float s = sin(angle);
44  float c = cos(angle);
45 
46  // translate point back to origin:
47  p.x -= origin.x;
48  p.y -= origin.y;
49 
50  // rotate point
51  float xnew = p.x * c - p.y * s;
52  float ynew = p.x * s + p.y * c;
53 
54  // translate point back:
55  p.x = xnew + origin.x;
56  p.y = ynew + origin.y;
57 }
58 
59 inline void fillPose(geometry_msgs::Pose& pose, const cv::Vec3d& rvec, const cv::Vec3d& tvec)
60 {
61  pose.position.x = tvec[0];
62  pose.position.y = tvec[1];
63  pose.position.z = tvec[2];
64 
65  double angle = norm(rvec);
66  cv::Vec3d axis = rvec / angle;
67 
69  q.setRotation(tf2::Vector3(axis[0], axis[1], axis[2]), angle);
70 
71  pose.orientation.w = q.w();
72  pose.orientation.x = q.x();
73  pose.orientation.y = q.y();
74  pose.orientation.z = q.z();
75 }
76 
77 inline void fillTransform(geometry_msgs::Transform& transform, const cv::Vec3d& rvec, const cv::Vec3d& tvec)
78 {
79  transform.translation.x = tvec[0];
80  transform.translation.y = tvec[1];
81  transform.translation.z = tvec[2];
82 
83  double angle = norm(rvec);
84  cv::Vec3d axis = rvec / angle;
85 
87  q.setRotation(tf2::Vector3(axis[0], axis[1], axis[2]), angle);
88 
89  transform.rotation.w = q.w();
90  transform.rotation.x = q.x();
91  transform.rotation.y = q.y();
92  transform.rotation.z = q.z();
93 }
94 
95 inline void fillTranslation(geometry_msgs::Vector3& translation, const cv::Vec3d& tvec)
96 {
97  translation.x = tvec[0];
98  translation.y = tvec[1];
99  translation.z = tvec[2];
100 }
101 
102 inline bool isFlipped(tf::Quaternion& q)
103 {
104  double yaw, pitch, roll;
105  tf::Matrix3x3(q).getEulerYPR(yaw, pitch, roll);
106  return (abs(pitch) > M_PI / 2) || (abs(roll) > M_PI / 2);
107 }
108 
109 /* Set roll and pitch from "from" to "to", keeping yaw */
110 inline void snapOrientation(geometry_msgs::Quaternion& to, const geometry_msgs::Quaternion& from, bool auto_flip = false)
111 {
112  tf::Quaternion _from, _to;
113  tf::quaternionMsgToTF(from, _from);
114  tf::quaternionMsgToTF(to, _to);
115 
116  if (auto_flip) {
117  if (!isFlipped(_from)) {
118  static const tf::Quaternion flip = tf::createQuaternionFromRPY(M_PI, 0, 0);
119  _from *= flip; // flip "from"
120  }
121  }
122 
123  auto diff = tf::Matrix3x3(_to).transposeTimes(tf::Matrix3x3(_from));
124  double _, yaw;
125  diff.getRPY(_, _, yaw);
126  auto q = tf::createQuaternionFromRPY(0, 0, -yaw);
127  _from = _from * q; // set yaw from "to" to "from"
128  tf::quaternionTFToMsg(_from, to); // set "from" to "to"
129 }
130 
131 inline void transformToPose(const geometry_msgs::Transform& transform, geometry_msgs::Pose& pose)
132 {
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;
137 }
Matrix3x3 transposeTimes(const Matrix3x3 &m) const
static tf::Quaternion createQuaternionFromRPY(double roll, double pitch, double yaw)
#define ROS_FATAL(...)
void snapOrientation(geometry_msgs::Quaternion &to, const geometry_msgs::Quaternion &from, bool auto_flip=false)
Definition: utils.h:110
static void param(ros::NodeHandle nh, const std::string &param_name, T &param_val)
Definition: utils.h:25
void fillPose(geometry_msgs::Pose &pose, const cv::Vec3d &rvec, const cv::Vec3d &tvec)
Definition: utils.h:59
XmlRpcServer s
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)
Definition: utils.h:33
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)
Definition: utils.h:102
void fillTranslation(geometry_msgs::Vector3 &translation, const cv::Vec3d &tvec)
Definition: utils.h:95
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)
Definition: utils.h:131
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)
Definition: utils.h:41
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)
Definition: utils.h:77


aruco_pose
Author(s): Oleg Kalachev
autogenerated on Mon Feb 28 2022 22:08:24