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!");
ros::Subscriber sub_input_
The input subscriber.
boost::shared_ptr< const T > TConstPtr
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::vector< boost::shared_ptr< ros::Publisher > > pubs_output_
The output list of publishers.
void input_callback(const TConstPtr &input)
boost::shared_ptr< const T > TConstPtr
std::vector< boost::shared_ptr< ros::Publisher > > pubs_output_
The output list of publishers.
Type const & getType() const
ros::NodeHandle & getPrivateNodeHandle() const
Subscriber sub_input_
The input subscriber.
void onInit()
Nodelet initialization routine.
#define ROS_INFO_STREAM(args)
NodeletDEMUX represent a demux nodelet for topics: it takes 1 input topic, and publishes on N (<=8) o...
bool getParam(const std::string &key, std::string &s) const
ros::NodeHandle private_nh_
ROS local node handle.
ros::NodeHandle private_nh_
ROS local node handle.
XmlRpc::XmlRpcValue output_topics_
The list of output topics passed as a parameter.
void onInit()
Nodelet initialization routine.
void input_callback(const TConstPtr &input)
XmlRpc::XmlRpcValue output_topics_
The list of output topics passed as a parameter.