00001 /********************************************************************* 00002 * utils.hpp 00003 * 00004 * Created on: Jun 16, 2014 00005 * Author: Filip Mandic 00006 * 00007 ********************************************************************/ 00008 00009 /********************************************************************* 00010 * Software License Agreement (BSD License) 00011 * 00012 * Copyright (c) 2014, LABUST, UNIZG-FER 00013 * All rights reserved. 00014 * 00015 * Redistribution and use in source and binary forms, with or without 00016 * modification, are permitted provided that the following conditions 00017 * are met: 00018 * 00019 * * Redistributions of source code must retain the above copyright 00020 * notice, this list of conditions and the following disclaimer. 00021 * * Redistributions in binary form must reproduce the above 00022 * copyright notice, this list of conditions and the following 00023 * disclaimer in the documentation and/or other materials provided 00024 * with the distribution. 00025 * * Neither the name of the LABUST nor the names of its 00026 * contributors may be used to endorse or promote products derived 00027 * from this software without specific prior written permission. 00028 * 00029 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00030 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00031 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00032 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00033 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00034 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00035 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00036 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00037 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00038 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00039 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00040 * POSSIBILITY OF SUCH DAMAGE. 00041 *********************************************************************/ 00042 00043 #ifndef UTILS_HPP_ 00044 #define UTILS_HPP_ 00045 00046 #include <ros/ros.h> 00047 00048 namespace labust{ 00049 namespace utilities{ 00050 00051 /************************************************************* 00052 *** Functions used calling ROS services 00053 *************************************************************/ 00054 template <typename custom_srv> 00055 custom_srv callService(ros::ServiceClient& client, custom_srv& request){ 00056 00057 if (client.call(request)){ 00058 ROS_INFO("Call to service %s successful", client.getService().c_str()); 00059 return request; 00060 } else { 00061 ROS_ERROR("Call to service %s failed", client.getService().c_str()); 00062 } 00063 } 00064 00065 /************************************************************* 00066 *** Functions for ROS message serialization and deserialization 00067 *************************************************************/ 00068 template <typename msgType> 00069 std::vector<uint8_t> serializeMsg(msgType data){ 00070 00071 uint32_t serial_size = ros::serialization::serializationLength(data); 00072 std::vector<uint8_t> buffer(serial_size); 00073 00074 ros::serialization::OStream stream(&buffer.front(), serial_size); 00075 ros::serialization::serialize(stream, data); 00076 00077 return buffer; 00078 } 00079 00080 template <typename msgType> 00081 msgType deserializeMsg(std::vector<uint8_t> my_buffer){ 00082 00083 msgType my_msg; 00084 00085 uint32_t serial_size = ros::serialization::serializationLength(my_msg); 00086 uint8_t *iter = &my_buffer.front(); 00087 00088 ros::serialization::IStream stream(iter, serial_size); 00089 ros::serialization::deserialize(stream, my_msg); 00090 00091 return my_msg; 00092 } 00093 00094 /************************************************************* 00095 *** Functions used for splitting string expressions 00096 *************************************************************/ 00097 std::vector<std::string> &split(const std::string &s, char delim, std::vector<std::string> &elems) { 00098 std::stringstream ss(s); 00099 std::string item; 00100 while (std::getline(ss, item, delim)) { 00101 if(!item.empty()){ 00102 elems.push_back(item); 00103 } 00104 } 00105 return elems; 00106 } 00107 00108 std::vector<std::string> split(const std::string &s, char delim) { 00109 std::vector<std::string> elems; 00110 split(s, delim, elems); 00111 return elems; 00112 } 00113 } 00114 } 00115 00116 #endif /* UTILS_HPP_ */