Public Member Functions | Private Attributes | List of all members
naoqi::publisher::JointStatePublisher Class Reference

#include <joint_state.hpp>

Public Member Functions

bool isInitialized () const
 
virtual bool isSubscribed () const
 
 JointStatePublisher (const std::string &topic="/joint_states")
 
virtual void publish (const sensor_msgs::JointState &js_msg, const std::vector< geometry_msgs::TransformStamped > &tf_transforms)
 
virtual void reset (ros::NodeHandle &nh)
 
std::string topic () const
 

Private Attributes

bool is_initialized_
 
ros::Publisher pub_joint_states_
 
boost::shared_ptr< tf2_ros::TransformBroadcastertf_broadcasterPtr_
 
std::string topic_
 

Detailed Description

Definition at line 34 of file publishers/joint_state.hpp.

Constructor & Destructor Documentation

◆ JointStatePublisher()

naoqi::publisher::JointStatePublisher::JointStatePublisher ( const std::string &  topic = "/joint_states")

Definition at line 28 of file publishers/joint_state.cpp.

Member Function Documentation

◆ isInitialized()

bool naoqi::publisher::JointStatePublisher::isInitialized ( ) const
inline

Definition at line 45 of file publishers/joint_state.hpp.

◆ isSubscribed()

bool naoqi::publisher::JointStatePublisher::isSubscribed ( ) const
virtual

Definition at line 54 of file publishers/joint_state.cpp.

◆ publish()

void naoqi::publisher::JointStatePublisher::publish ( const sensor_msgs::JointState &  js_msg,
const std::vector< geometry_msgs::TransformStamped > &  tf_transforms 
)
virtual

ROBOT STATE PUBLISHER

Definition at line 33 of file publishers/joint_state.cpp.

◆ reset()

void naoqi::publisher::JointStatePublisher::reset ( ros::NodeHandle nh)
virtual

Definition at line 45 of file publishers/joint_state.cpp.

◆ topic()

std::string naoqi::publisher::JointStatePublisher::topic ( ) const
inline

Definition at line 40 of file publishers/joint_state.hpp.

Member Data Documentation

◆ is_initialized_

bool naoqi::publisher::JointStatePublisher::is_initialized_
private

Definition at line 65 of file publishers/joint_state.hpp.

◆ pub_joint_states_

ros::Publisher naoqi::publisher::JointStatePublisher::pub_joint_states_
private

initialize separate publishers for js and odom

Definition at line 61 of file publishers/joint_state.hpp.

◆ tf_broadcasterPtr_

boost::shared_ptr<tf2_ros::TransformBroadcaster> naoqi::publisher::JointStatePublisher::tf_broadcasterPtr_
private

Definition at line 58 of file publishers/joint_state.hpp.

◆ topic_

std::string naoqi::publisher::JointStatePublisher::topic_
private

Definition at line 63 of file publishers/joint_state.hpp.


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


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 3 2024 03:50:07