Go to the documentation of this file.
37 #ifndef NODELET_NODELET_DEMUX_H_
38 #define NODELET_NODELET_DEMUX_H_
50 template <
typename T,
typename Subscriber = message_filters::Subscriber<T> >
65 ROS_ERROR (
"[nodelet::NodeletDEMUX::init] Need a 'output_topics' parameter to be set before continuing!");
75 ROS_ERROR (
"[nodelet::NodeletDEMUX::init] Only one topic given. Does it make sense to passthrough?");
81 ROS_ERROR (
"[nodelet::NodeletDEMUX::init] More than 8 topics passed!");
96 ROS_ERROR (
"[nodelet::NodeletDEMUX::init] Invalid 'output_topics' parameter given!");
127 template <
typename T>
143 ROS_ERROR (
"[nodelet::NodeletDEMUX::init] Need a 'output_topics' parameter to be set before continuing!");
153 ROS_ERROR (
"[nodelet::NodeletDEMUX::init] Only one topic given. Does it make sense to passthrough?");
159 ROS_ERROR (
"[nodelet::NodeletDEMUX::init] More than 8 topics passed!");
174 ROS_ERROR (
"[nodelet::NodeletDEMUX::init] Invalid 'output_topics' parameter given!");
NodeletDEMUX represent a demux nodelet for topics: it takes 1 input topic, and publishes on N (<=8) o...
std::vector< boost::shared_ptr< ros::Publisher > > pubs_output_
The output list of publishers.
bool getParam(const std::string &key, bool &b) const
XmlRpc::XmlRpcValue output_topics_
The list of output topics passed as a parameter.
std::vector< boost::shared_ptr< ros::Publisher > > pubs_output_
The output list of publishers.
ros::NodeHandle & getPrivateNodeHandle() const
boost::shared_ptr< const T > TConstPtr
Subscriber sub_input_
The input subscriber.
ros::Subscriber sub_input_
The input subscriber.
ros::NodeHandle private_nh_
ROS local node handle.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
void onInit()
Nodelet initialization routine.
#define ROS_INFO_STREAM(args)
const Type & getType() const
void input_callback(const TConstPtr &input)
ros::NodeHandle private_nh_
ROS local node handle.
void input_callback(const TConstPtr &input)
void onInit()
Nodelet initialization routine.
boost::shared_ptr< const T > TConstPtr
XmlRpc::XmlRpcValue output_topics_
The list of output topics passed as a parameter.
nodelet_topic_tools
Author(s): Radu Bogdan Rusu, Tully Foote, Michael Carroll
autogenerated on Fri Nov 15 2024 03:38:12