dynamic_graph_manager
dynamic_graph::RosRobotStatePublisher Class Reference

This class define a dynamic graph wrapper around the vicon client. More...

#include <ros_robot_state_publisher.hpp>

Inheritance diagram for dynamic_graph::RosRobotStatePublisher:
Collaboration diagram for dynamic_graph::RosRobotStatePublisher:

Public Member Functions

 RosRobotStatePublisher (const std::string &name)
 
void add (const std::string &base_link_name, const std::string &joint_names, const std::string &tf_prefix, const std::string &signal_name, const std::string &joint_state_topic_name)
 
int & trigger (int &, int)
 Trigger the publishing of the data to ros for all signals. More...
 
void send_data (const RosRobotStatePublisherInternal &publisher, int time)
 Signal callback functions.
 

Private Member Functions

virtual const std::string & getClassName (void) const
 Get the CLASS_NAME object. More...
 
void set_tf_msg_to_identity (geometry_msgs::TransformStamped &msg)
 Set a tf msg to identity. More...
 
void normalize_tf_msg_quaternion (geometry_msgs::TransformStamped &msg)
 Normalize the tf message quaternion before sending it to the. More...
 

Private Attributes

SignalOUT trigger_signal_
 Create an internal output signal which should be call periodically in the device in order to publish the data. More...
 
ros::NodeHandle & ros_node_handle_
 Ros node handle corresponding to the dynamic graph process node handle.
 
std::map< std::string, RosRobotStatePublisherInternalpublishers_
 This is the list of publishers registered for this class. More...
 
ros::Duration rate_
 manage the rate data publication in topics
 
ros::Time last_time_of_publication_
 Check at what time the publication was done.
 

Static Private Attributes

static const std::string CLASS_NAME
 The class name used to identify it in the dynamic graph pool.
 

Detailed Description

This class define a dynamic graph wrapper around the vicon client.

Member Function Documentation

◆ add()

void dynamic_graph::RosRobotStatePublisher::add ( const std::string &  base_link_name,
const std::string &  joint_names,
const std::string &  tf_prefix,
const std::string &  signal_name,
const std::string &  joint_state_topic_name 
)
Parameters
base_link_name
joint_names
tf_prefix
signal_name

◆ getClassName()

virtual const std::string& dynamic_graph::RosRobotStatePublisher::getClassName ( void  ) const
inlineprivatevirtual

Get the CLASS_NAME object.

Returns
const std::string&

◆ normalize_tf_msg_quaternion()

void dynamic_graph::RosRobotStatePublisher::normalize_tf_msg_quaternion ( geometry_msgs::TransformStamped &  msg)
private

Normalize the tf message quaternion before sending it to the.

Parameters
[in]

◆ set_tf_msg_to_identity()

void dynamic_graph::RosRobotStatePublisher::set_tf_msg_to_identity ( geometry_msgs::TransformStamped &  msg)
private

Set a tf msg to identity.

Parameters
[in]

◆ trigger()

int & dynamic_graph::RosRobotStatePublisher::trigger ( int &  dummy,
int  time 
)

Trigger the publishing of the data to ros for all signals.

Returns
int& dummy stuff.

Member Data Documentation

◆ publishers_

std::map<std::string, RosRobotStatePublisherInternal> dynamic_graph::RosRobotStatePublisher::publishers_
private

This is the list of publishers registered for this class.

It correspond to the list of robot states one wants to publish. See the add methode (Command)

◆ trigger_signal_

SignalOUT dynamic_graph::RosRobotStatePublisher::trigger_signal_
private

Create an internal output signal which should be call periodically in the device in order to publish the data.

The callback function of this signal is the trigger methode.


The documentation for this class was generated from the following files: