ros_msg_conversions.h
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #ifndef COB_VISION_UTILS_ROS_MSG_CONVERSIONS_H__
19 #define COB_VISION_UTILS_ROS_MSG_CONVERSIONS_H__
20 
21 #include <cob_object_detection_msgs/Detection.h>
22 #include <visualization_msgs/Marker.h>
23 
24 #include <Eigen/Geometry> // for transformations
25 
27 {
28 
29  // Eigen to ROS conversions
30  inline void EigenToROSMsg(const Eigen::Vector3f& pt_eigen, geometry_msgs::Point& pt_msg)
31  { pt_msg.x=pt_eigen[0]; pt_msg.y=pt_eigen[1]; pt_msg.z=pt_eigen[2]; }
32 
33  inline void EigenToROSMsg(const Eigen::Quaternion<float>& q_eigen, geometry_msgs::Quaternion& q_msg)
34  { q_msg.x=q_eigen.x(); q_msg.y=q_eigen.y(); q_msg.z=q_eigen.z(); q_msg.w=q_eigen.w(); }
35 
36  inline void EigenToROSMsg(const Eigen::Vector3f& pt, const Eigen::Quaternion<float>& rot, geometry_msgs::Pose& pose)
37  { EigenToROSMsg(pt, pose.position); EigenToROSMsg(rot, pose.orientation); }
38 
39 
40  // ROS to Eigen conversions
41  inline void ROSMsgToEigen(const geometry_msgs::Point& pt_msg, Eigen::Vector3f& pt_eigen)
42  { pt_eigen[0]=pt_msg.x; pt_eigen[1]=pt_msg.y; pt_eigen[2]=pt_msg.z; }
43 
44  inline void ROSMsgToEigen(const geometry_msgs::Quaternion& q_msg, Eigen::Quaternion<float>& q_eigen)
45  { q_eigen.x()=q_msg.x; q_eigen.y()=q_msg.y; q_eigen.z()=q_msg.z; q_eigen.w()=q_msg.w; }
46 
47  inline void ROSMsgToEigen(const geometry_msgs::Pose& pose, Eigen::Vector3f& pt, Eigen::Quaternion<float>& rot)
48  { ROSMsgToEigen(pose.position, pt); ROSMsgToEigen(pose.orientation, rot); }
49 
50 
51 
52  // Marker properties type, lifetime, header and id should be set manually;
53  void boundingBoxToMarker(const cob_object_detection_msgs::Detection& bb, visualization_msgs::Marker& marker)
54  {
55  marker.action = visualization_msgs::Marker::ADD;
56  marker.type = visualization_msgs::Marker::LINE_LIST;
57  geometry_msgs::Point pt;
58 
59  /*************************
60  * Lines between point indices of 0-1, 2-3, 4-5, ...
61  *
62  * bottom of bounding box:
63  *
64  * 1,2,10 0,7,8
65  * +-------+
66  * | |
67  * +-------+
68  * 3,4,12 5,6,14
69  *
70  * top of bounding box:
71  *
72  * 11,17,18 9,16,23
73  * +-------+
74  * | |
75  * +-------+
76  * 13,19,20 15,21,22
77  *
78  *************************/
79 
80  marker.points.resize(24);
81  pt.x = bb.bounding_box_lwh.x;
82  pt.y = bb.bounding_box_lwh.y;
83  pt.z = 0;
84 
85  marker.points[0]=marker.points[7]=marker.points[8] = pt;
86 
87  pt.x = -bb.bounding_box_lwh.x;
88  marker.points[1]=marker.points[2]=marker.points[10] = pt;
89 
90  pt.y = -bb.bounding_box_lwh.y;
91  marker.points[3]=marker.points[4]=marker.points[12] = pt;
92 
93  pt.x = bb.bounding_box_lwh.x;
94  marker.points[5]=marker.points[6]=marker.points[14] = pt;
95 
96 
97  pt.y = bb.bounding_box_lwh.y;
98  pt.z = bb.bounding_box_lwh.z;
99 
100  marker.points[9]=marker.points[16]=marker.points[23] = pt;
101 
102  pt.x = -bb.bounding_box_lwh.x;
103  marker.points[11]=marker.points[17]=marker.points[18] = pt;
104 
105  pt.y = -bb.bounding_box_lwh.y;
106  marker.points[13]=marker.points[19]=marker.points[20] = pt;
107 
108  pt.x = bb.bounding_box_lwh.x;
109  marker.points[15]=marker.points[21]=marker.points[22] = pt;
110 
111  marker.pose = bb.pose.pose;
112 
113  marker.scale.x = 0.01;
114  marker.color.r = 0;
115  marker.color.g = 1;
116  marker.color.b = 0;
117  marker.color.a = 1.0;
118  }
119 }
120 
121 #endif // COB_VISION_UTILS_ROS_MSG_CONVERSIONS_H__
void boundingBoxToMarker(const cob_object_detection_msgs::Detection &bb, visualization_msgs::Marker &marker)
void ROSMsgToEigen(const geometry_msgs::Point &pt_msg, Eigen::Vector3f &pt_eigen)
void EigenToROSMsg(const Eigen::Vector3f &pt_eigen, geometry_msgs::Point &pt_msg)


cob_vision_utils
Author(s): Jan Fischer
autogenerated on Sun Oct 18 2020 13:13:20