ddsProxy.h
Go to the documentation of this file.
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 *
00018 *
00019 *  Author: Ronny Hartanto (ronny.hartanto@dfki.de)
00020 *  
00021 * FILE --- ddsProxy.h
00022 *
00023 *  Created on: Aug 4, 2012
00024 */
00025 
00026 #ifndef DDSPROXY_H_
00027 #define DDSPROXY_H_
00028 
00029 // DDS includes
00030 #include "ddsManager.h"
00031 
00032 #include <iostream>
00033 #include <string>
00034 #include <iostream>
00035 
00036 // ROS includes
00037 #include <ros/ros.h>
00038 
00039 class DDSProxy{
00040 protected:
00041         ros::NodeHandle nh_;
00042     ros::Subscriber sub;
00043         ros::Publisher pub;
00044 
00045         Topic_var m_data_topic;
00046     std::string dds_domain_name;
00047     std::string ros_message_name;
00048     std::string dds_message_name;
00049     std::string ros_message_type;
00050     std::string node_name;
00051     std::string robot_name;
00052     int ros_frequency;
00053 public:
00054         DDSProxy() {};
00055         ~DDSProxy() {};
00056         template <class T> void messageCallback(const ros::MessageEvent<T const>& event);
00057         virtual void update() = 0;
00058         void initialize(std::string domain, std::string ros_topic, std::string dds_topic, std::string ros_msg_type) {
00059                 // Read parameters
00060                 node_name = ros::this_node::getName();
00061                 ROS_INFO("Node name : %s", node_name.c_str());
00062                 std::string param_domain_name = node_name.c_str();
00063                 param_domain_name.append("/domain_name");
00064                 std::string param_ros_msg_name = node_name.c_str();
00065                 param_ros_msg_name.append("/ros_msg_name");
00066                 std::string param_dds_msg_name = node_name.c_str();
00067                 param_dds_msg_name.append("/dds_msg_name");
00068                 std::string param_frequency_name = node_name.c_str();
00069                 param_frequency_name.append("/frequency");
00070                 std::string param_robot_name = node_name.c_str();
00071                 param_robot_name.append("/robot_name");
00072                 nh_.param(param_domain_name, dds_domain_name, domain);
00073                 nh_.param(param_ros_msg_name, ros_message_name, ros_topic);
00074                 nh_.param(param_dds_msg_name, dds_message_name, dds_topic);
00075                 nh_.param(param_frequency_name, ros_frequency, 1);
00076                 nh_.param(param_robot_name, robot_name, node_name);
00077                 ros_message_type = ros_msg_type;
00078                 ROS_INFO("DDS domain name: %s", dds_domain_name.c_str());
00079                 ROS_INFO("ROS message name: %s", ros_message_name.c_str());
00080                 ROS_INFO("DDS message name: %s", dds_message_name.c_str());
00081                 ROS_INFO("ROS message type: %s", ros_message_type.c_str());
00082                 ROS_INFO("ROS message freq: %d", ros_frequency);
00083                 ROS_INFO("Robot name: %s", robot_name.c_str());
00084                 registerProxy();
00085         }
00086         virtual void registerProxy() = 0;
00087         int getFrequency() {return ros_frequency;};
00088 };
00089 
00090 #endif /* DDSPROXY_H_ */


proxy_common
Author(s): Ronny Hartanto
autogenerated on Mon Oct 6 2014 06:54:18