#include <ddsProxy.h>
Public Member Functions | |
DDSProxy () | |
int | getFrequency () |
void | initialize (std::string domain, std::string ros_topic, std::string dds_topic, std::string ros_msg_type) |
template<class T > | |
void | messageCallback (const ros::MessageEvent< T const > &event) |
virtual void | registerProxy ()=0 |
virtual void | update ()=0 |
~DDSProxy () | |
Protected Attributes | |
std::string | dds_domain_name |
std::string | dds_message_name |
Topic_var | m_data_topic |
ros::NodeHandle | nh_ |
std::string | node_name |
ros::Publisher | pub |
std::string | robot_name |
int | ros_frequency |
std::string | ros_message_name |
std::string | ros_message_type |
ros::Subscriber | sub |
Definition at line 39 of file ddsProxy.h.
DDSProxy::DDSProxy | ( | ) | [inline] |
Definition at line 54 of file ddsProxy.h.
DDSProxy::~DDSProxy | ( | ) | [inline] |
Definition at line 55 of file ddsProxy.h.
int DDSProxy::getFrequency | ( | ) | [inline] |
Definition at line 87 of file ddsProxy.h.
void DDSProxy::initialize | ( | std::string | domain, |
std::string | ros_topic, | ||
std::string | dds_topic, | ||
std::string | ros_msg_type | ||
) | [inline] |
Definition at line 58 of file ddsProxy.h.
void DDSProxy::messageCallback | ( | const ros::MessageEvent< T const > & | event | ) |
virtual void DDSProxy::registerProxy | ( | ) | [pure virtual] |
virtual void DDSProxy::update | ( | ) | [pure virtual] |
std::string DDSProxy::dds_domain_name [protected] |
Definition at line 46 of file ddsProxy.h.
std::string DDSProxy::dds_message_name [protected] |
Definition at line 48 of file ddsProxy.h.
Topic_var DDSProxy::m_data_topic [protected] |
Definition at line 45 of file ddsProxy.h.
ros::NodeHandle DDSProxy::nh_ [protected] |
Definition at line 41 of file ddsProxy.h.
std::string DDSProxy::node_name [protected] |
Definition at line 50 of file ddsProxy.h.
ros::Publisher DDSProxy::pub [protected] |
Definition at line 43 of file ddsProxy.h.
std::string DDSProxy::robot_name [protected] |
Definition at line 51 of file ddsProxy.h.
int DDSProxy::ros_frequency [protected] |
Definition at line 52 of file ddsProxy.h.
std::string DDSProxy::ros_message_name [protected] |
Definition at line 47 of file ddsProxy.h.
std::string DDSProxy::ros_message_type [protected] |
Definition at line 49 of file ddsProxy.h.
ros::Subscriber DDSProxy::sub [protected] |
Definition at line 42 of file ddsProxy.h.