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 --- proxyPoseWithCovarianceStamped.cpp 00020 * 00021 * Created on: Aug 6, 2012 00022 * 00023 */ 00024 00025 #include "ddsproxyposewithcovariancestamped.h" 00026 #include <ros/callback_queue.h> 00027 00028 int main(int argc, char *argv[]){ 00029 00030 ros::init(argc, argv, "ddsProxyPoseWithCovarianceStamped"); 00031 00032 DDSProxyPoseWithCovarianceStamped *proxy_node = new DDSProxyPoseWithCovarianceStamped(); 00033 00034 ROS_INFO("Initialized DDS <-PoseWithCovarianceStamped-> ROS "); 00035 proxy_node->initialize("IMPERA", "amcl_pose", "ddsPoseWithCovarianceStamped", "geometry_msgs.PoseWithCovarianceStamped"); 00036 00037 ros::Rate loop_rate(proxy_node->getFrequency()); 00038 00039 while(ros::ok()) 00040 { 00041 ros::getGlobalCallbackQueue()->callAvailable(ros::WallDuration(0.1)); 00042 proxy_node->update(); 00043 loop_rate.sleep(); 00044 } 00045 00046 return 0; 00047 } 00048