Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 #ifndef COB_VISION_UTILS_ROS_MSG_CONVERSIONS_H__
00019 #define COB_VISION_UTILS_ROS_MSG_CONVERSIONS_H__
00020
00021 #include <cob_object_detection_msgs/Detection.h>
00022 #include <visualization_msgs/Marker.h>
00023
00024 #include <Eigen/Geometry>
00025
00026 namespace cob_perception_common
00027 {
00028
00029
00030 inline void EigenToROSMsg(const Eigen::Vector3f& pt_eigen, geometry_msgs::Point& pt_msg)
00031 { pt_msg.x=pt_eigen[0]; pt_msg.y=pt_eigen[1]; pt_msg.z=pt_eigen[2]; }
00032
00033 inline void EigenToROSMsg(const Eigen::Quaternion<float>& q_eigen, geometry_msgs::Quaternion& q_msg)
00034 { q_msg.x=q_eigen.x(); q_msg.y=q_eigen.y(); q_msg.z=q_eigen.z(); q_msg.w=q_eigen.w(); }
00035
00036 inline void EigenToROSMsg(const Eigen::Vector3f& pt, const Eigen::Quaternion<float>& rot, geometry_msgs::Pose& pose)
00037 { EigenToROSMsg(pt, pose.position); EigenToROSMsg(rot, pose.orientation); }
00038
00039
00040
00041 inline void ROSMsgToEigen(const geometry_msgs::Point& pt_msg, Eigen::Vector3f& pt_eigen)
00042 { pt_eigen[0]=pt_msg.x; pt_eigen[1]=pt_msg.y; pt_eigen[2]=pt_msg.z; }
00043
00044 inline void ROSMsgToEigen(const geometry_msgs::Quaternion& q_msg, Eigen::Quaternion<float>& q_eigen)
00045 { q_eigen.x()=q_msg.x; q_eigen.y()=q_msg.y; q_eigen.z()=q_msg.z; q_eigen.w()=q_msg.w; }
00046
00047 inline void ROSMsgToEigen(const geometry_msgs::Pose& pose, Eigen::Vector3f& pt, Eigen::Quaternion<float>& rot)
00048 { ROSMsgToEigen(pose.position, pt); ROSMsgToEigen(pose.orientation, rot); }
00049
00050
00051
00052
00053 void boundingBoxToMarker(const cob_object_detection_msgs::Detection& bb, visualization_msgs::Marker& marker)
00054 {
00055 marker.action = visualization_msgs::Marker::ADD;
00056 marker.type = visualization_msgs::Marker::LINE_LIST;
00057 geometry_msgs::Point pt;
00058
00059
00060
00061
00062
00063
00064
00065
00066
00067
00068
00069
00070
00071
00072
00073
00074
00075
00076
00077
00078
00079
00080 marker.points.resize(24);
00081 pt.x = bb.bounding_box_lwh.x;
00082 pt.y = bb.bounding_box_lwh.y;
00083 pt.z = 0;
00084
00085 marker.points[0]=marker.points[7]=marker.points[8] = pt;
00086
00087 pt.x = -bb.bounding_box_lwh.x;
00088 marker.points[1]=marker.points[2]=marker.points[10] = pt;
00089
00090 pt.y = -bb.bounding_box_lwh.y;
00091 marker.points[3]=marker.points[4]=marker.points[12] = pt;
00092
00093 pt.x = bb.bounding_box_lwh.x;
00094 marker.points[5]=marker.points[6]=marker.points[14] = pt;
00095
00096
00097 pt.y = bb.bounding_box_lwh.y;
00098 pt.z = bb.bounding_box_lwh.z;
00099
00100 marker.points[9]=marker.points[16]=marker.points[23] = pt;
00101
00102 pt.x = -bb.bounding_box_lwh.x;
00103 marker.points[11]=marker.points[17]=marker.points[18] = pt;
00104
00105 pt.y = -bb.bounding_box_lwh.y;
00106 marker.points[13]=marker.points[19]=marker.points[20] = pt;
00107
00108 pt.x = bb.bounding_box_lwh.x;
00109 marker.points[15]=marker.points[21]=marker.points[22] = pt;
00110
00111 marker.pose = bb.pose.pose;
00112
00113 marker.scale.x = 0.01;
00114 marker.color.r = 0;
00115 marker.color.g = 1;
00116 marker.color.b = 0;
00117 marker.color.a = 1.0;
00118 }
00119 }
00120
00121 #endif // COB_VISION_UTILS_ROS_MSG_CONVERSIONS_H__