$search
00001 /********************************************************************* 00002 * 00003 * Copyright (c) 2011, Willow Garage, Inc. 00004 * All rights reserved. 00005 * 00006 * Redistribution and use in source and binary forms, with or without 00007 * modification, are permitted provided that the following conditions 00008 * are met: 00009 * 00010 * * Redistributions of source code must retain the above copyright 00011 * notice, this list of conditions and the following disclaimer. 00012 * * Redistributions in binary form must reproduce the above 00013 * copyright notice, this list of conditions and the following 00014 * disclaimer in the documentation and/or other materials provided 00015 * with the distribution. 00016 * * Neither the name of the Willow Garage nor the names of its 00017 * contributors may be used to endorse or promote products derived 00018 * from this software without specific prior written permission. 00019 * 00020 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00021 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00022 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00023 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00024 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00025 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00026 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00027 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00028 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00029 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00030 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00031 * POSSIBILITY OF SUCH DAMAGE. 00032 *********************************************************************/ 00033 00034 #ifndef _MSG_HELPERS_H_ 00035 #define _MSG_HELPERS_H_ 00036 00037 #include <ros/ros.h> 00038 #include <tf/tf.h> 00039 00040 #include <std_msgs/ColorRGBA.h> 00041 00042 #include <geometry_msgs/Vector3.h> 00043 #include <geometry_msgs/Point.h> 00044 #include <geometry_msgs/Quaternion.h> 00045 #include <geometry_msgs/Pose.h> 00046 #include <geometry_msgs/Transform.h> 00047 #include <geometry_msgs/PoseStamped.h> 00048 00049 namespace object_manipulator 00050 { 00051 00052 namespace msg 00053 { 00054 // A suite of simple msg "constructor" functions. It would be great if this feature was added to ROS msg generation... 00055 // Also includes a number of converter functions, for convenience... 00056 00057 inline std_msgs::ColorRGBA createColorMsg(const float red, const float blue, const float green, const float alpha = 1.0) { 00058 std_msgs::ColorRGBA color; 00059 color.r = red; 00060 color.g = green; 00061 color.b = blue; 00062 color.a = alpha; 00063 return color; 00064 } 00065 00066 // -------------------------------------------------------------------------------------------- 00067 inline geometry_msgs::Vector3 createVector3Msg(const float x, const float y, const float z) { 00068 geometry_msgs::Vector3 msg; 00069 msg.x = x; 00070 msg.y = y; 00071 msg.z = z; 00072 return msg; 00073 } 00074 00075 inline geometry_msgs::Vector3 createVector3Msg(const tf::Vector3 &v) { 00076 geometry_msgs::Vector3 msg; 00077 msg.x = v.x(); 00078 msg.y = v.y(); 00079 msg.z = v.z(); 00080 return msg; 00081 } 00082 00083 // -------------------------------------------------------------------------------------------- 00084 inline geometry_msgs::Point createPointMsg(const float x, const float y, const float z) { 00085 geometry_msgs::Point msg; 00086 msg.x = x; 00087 msg.y = y; 00088 msg.z = z; 00089 return msg; 00090 } 00091 00092 inline geometry_msgs::Point createPointMsg(const tf::Point &v) { 00093 geometry_msgs::Point msg; 00094 msg.x = v.x(); 00095 msg.y = v.y(); 00096 msg.z = v.z(); 00097 return msg; 00098 } 00099 00100 // -------------------------------------------------------------------------------------------- 00101 inline geometry_msgs::Quaternion createQuaternionMsg(const float x, const float y, const float z, const float w) { 00102 geometry_msgs::Quaternion msg; 00103 msg.x = x; 00104 msg.y = y; 00105 msg.z = z; 00106 msg.w = w; 00107 return msg; 00108 } 00109 00110 inline geometry_msgs::Quaternion createQuaternionMsg(const tf::Quaternion &q) { 00111 geometry_msgs::Quaternion msg; 00112 msg.x = q.x(); 00113 msg.y = q.y(); 00114 msg.z = q.z(); 00115 msg.w = q.w(); 00116 return msg; 00117 } 00118 00119 // -------------------------------------------------------------------------------------------- 00120 inline geometry_msgs::Pose createPoseMsg(const geometry_msgs::Point &v, const geometry_msgs::Quaternion &q) 00121 { 00122 geometry_msgs::Pose msg; 00123 msg.position = v; 00124 msg.orientation = q; 00125 return msg; 00126 } 00127 00128 inline geometry_msgs::Pose createPoseMsg(const geometry_msgs::Vector3 &v, const geometry_msgs::Quaternion &q) 00129 { 00130 geometry_msgs::Pose msg; 00131 msg.position = msg::createPointMsg(v.x, v.y, v.z); 00132 msg.orientation = q; 00133 return msg; 00134 } 00135 00136 // -------------------------------------------------------------------------------------------- 00137 inline geometry_msgs::PoseStamped createPoseStampedMsg(const geometry_msgs::Pose &p, const std::string &frame_id, const ros::Time &stamp) 00138 { 00139 geometry_msgs::PoseStamped msg; 00140 msg.pose = p; 00141 msg.header.frame_id = frame_id; 00142 msg.header.stamp = stamp; 00143 return msg; 00144 } 00145 00146 inline geometry_msgs::PoseStamped createPoseStampedMsg(const geometry_msgs::Point &v, const geometry_msgs::Quaternion &q, const std::string &frame_id, const ros::Time &stamp) 00147 { 00148 return createPoseStampedMsg( createPoseMsg(v, q), frame_id, stamp ); 00149 } 00150 00151 // -------------------------------------------------------------------------------------------- 00152 inline geometry_msgs::Transform createTransformMsg(const geometry_msgs::Point &v, const geometry_msgs::Quaternion &q) 00153 { 00154 geometry_msgs::Transform msg; 00155 msg.translation = msg::createVector3Msg(v.x, v.y, v.z); 00156 msg.rotation = q; 00157 return msg; 00158 } 00159 00160 inline geometry_msgs::Transform createTransformMsg(const geometry_msgs::Vector3 &v, const geometry_msgs::Quaternion &q) 00161 { 00162 geometry_msgs::Transform msg; 00163 msg.translation = v; 00164 msg.rotation = q; 00165 return msg; 00166 } 00167 00168 inline geometry_msgs::TransformStamped createTransformStampedMsg(const geometry_msgs::Transform &t, const std::string &frame_id, const ros::Time &stamp) 00169 { 00170 geometry_msgs::TransformStamped msg; 00171 msg.transform = t; 00172 msg.header.frame_id = frame_id; 00173 msg.header.stamp = stamp; 00174 return msg; 00175 } 00176 00177 inline geometry_msgs::TransformStamped createTransformStampedMsg(const geometry_msgs::Vector3 &v, const geometry_msgs::Quaternion &q, const std::string &frame_id, const ros::Time &stamp) 00178 { 00179 return createTransformStampedMsg( createTransformMsg(v, q), frame_id, stamp ); 00180 } 00181 00182 } // namepsace msg 00183 00184 } // namespace object_manipulator 00185 00186 #endif