18 #ifndef COB_VISION_UTILS_ROS_MSG_CONVERSIONS_H__ 19 #define COB_VISION_UTILS_ROS_MSG_CONVERSIONS_H__ 21 #include <cob_object_detection_msgs/Detection.h> 22 #include <visualization_msgs/Marker.h> 24 #include <Eigen/Geometry> 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]; }
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(); }
36 inline void EigenToROSMsg(
const Eigen::Vector3f& pt,
const Eigen::Quaternion<float>& rot, geometry_msgs::Pose& pose)
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; }
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; }
47 inline void ROSMsgToEigen(
const geometry_msgs::Pose& pose, Eigen::Vector3f& pt, Eigen::Quaternion<float>& rot)
53 void boundingBoxToMarker(
const cob_object_detection_msgs::Detection& bb, visualization_msgs::Marker& marker)
55 marker.action = visualization_msgs::Marker::ADD;
56 marker.type = visualization_msgs::Marker::LINE_LIST;
57 geometry_msgs::Point pt;
80 marker.points.resize(24);
81 pt.x = bb.bounding_box_lwh.x;
82 pt.y = bb.bounding_box_lwh.y;
85 marker.points[0]=marker.points[7]=marker.points[8] = pt;
87 pt.x = -bb.bounding_box_lwh.x;
88 marker.points[1]=marker.points[2]=marker.points[10] = pt;
90 pt.y = -bb.bounding_box_lwh.y;
91 marker.points[3]=marker.points[4]=marker.points[12] = pt;
93 pt.x = bb.bounding_box_lwh.x;
94 marker.points[5]=marker.points[6]=marker.points[14] = pt;
97 pt.y = bb.bounding_box_lwh.y;
98 pt.z = bb.bounding_box_lwh.z;
100 marker.points[9]=marker.points[16]=marker.points[23] = pt;
102 pt.x = -bb.bounding_box_lwh.x;
103 marker.points[11]=marker.points[17]=marker.points[18] = pt;
105 pt.y = -bb.bounding_box_lwh.y;
106 marker.points[13]=marker.points[19]=marker.points[20] = pt;
108 pt.x = bb.bounding_box_lwh.x;
109 marker.points[15]=marker.points[21]=marker.points[22] = pt;
111 marker.pose = bb.pose.pose;
113 marker.scale.x = 0.01;
117 marker.color.a = 1.0;
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)