25 #ifndef __OEM7_ROS_PUBLISHER_HPP__ 26 #define __OEM7_ROS_PUBLISHER_HPP__ 49 typedef std::map<std::string, std::string> message_config_map_t;
51 message_config_map_t message_config_map;
52 nh.
getParam(name, message_config_map);
54 message_config_map_t::iterator topic_itr = message_config_map.find(
"topic");
55 if(topic_itr == message_config_map.end())
63 message_config_map_t::iterator q_size_itr = message_config_map.find(
"queue_size");
64 if(q_size_itr != message_config_map.end())
66 std::stringstream ss(q_size_itr->second);
70 message_config_map_t::iterator frame_id_itr = message_config_map.find(
"frame_id");
71 if(frame_id_itr != message_config_map.end())
73 frame_id_ = frame_id_itr->second;
76 ROS_INFO_STREAM(
"topic [" << topic_itr->second <<
"]: frame_id: '" << frame_id_ <<
"'; q size: " << queue_size);
77 ros_pub_ = nh.
advertise<M>(topic_itr->second, queue_size);
void publish(const boost::shared_ptr< M > &message) const
std::string frame_id_
Configurable frame ID.
ros::Publisher ros_pub_
ROS publisher.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_WARN_STREAM(args)
void publish(boost::shared_ptr< M > &msg)
void setup(const std::string &name, ros::NodeHandle &nh)
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
void SetROSHeader(const std::string &frame_id, boost::shared_ptr< T > &msg)
std::string getTopic() const