00001 /* 00002 * Copyright (c) 2012 DFKI GmbH, Bremen, Germany 00003 * 00004 * This file is free software: you may copy, redistribute and/or modify it 00005 * under the terms of the GNU General Public License as published by the 00006 * Free Software Foundation, either version 3 of the License, or (at your 00007 * option) any later version. 00008 * 00009 * This file is distributed in the hope that it will be useful, but 00010 * WITHOUT ANY WARRANTY; without even the implied warranty of 00011 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU 00012 * General Public License for more details. 00013 * 00014 * You should have received a copy of the GNU General Public License 00015 * along with this program. If not, see <http://www.gnu.org/licenses/>. 00016 * 00017 * Author: Ronny Hartanto (ronny.hartanto@dfki.de) 00018 * 00019 * FILE --- ddsproxyposestamped.h 00020 * 00021 * Created on: Sep 10, 2012 00022 */ 00023 #ifndef _DDSPROXYPOSESTAMPED_H_ 00024 #define _DDSPROXYPOSESTAMPED_H_ 00025 00026 // DDS includes 00027 #include "ddsProxy.h" 00028 00029 // Message specific includes 00030 #include <geometry_msgs/PoseStamped.h> 00031 #include "../idl_gen/proxyPoseStamped.h" 00032 #include "../idl_gen/ccpp_proxyPoseStamped.h" 00033 00034 class DDSProxyPoseStamped: public DDSProxy { 00035 public: 00036 DDSProxyPoseStamped(); 00037 ~DDSProxyPoseStamped(); 00038 template <class T> void messageCallback(const ros::MessageEvent<T const>& event); 00039 void update(); 00040 void registerProxy(); 00041 private: 00042 proxyPoseStampedDataWriter_var m_data_writer; 00043 proxyPoseStampedDataReader_var m_data_reader; 00044 }; 00045 00046 #endif // _DDSPROXYPOSESTAMPED_H_