Go to the documentation of this file.
47 static int s_count = 0;
61 #define USAGE "\nusage: drop IN_TOPIC X Y [OUT_TOPIC]\n\n" \
62 " This program will drop X out of every Y messages from IN_TOPIC,\n" \
63 " forwarding the rest to OUT_TOPIC if given, else to a topic \n" \
64 " named IN_TOPIC_drop\n\n"
65 int main(
int argc,
char **argv)
77 if ((argc != 4 && argc != 5) || atoi(argv[2]) < 0 || atoi(argv[3]) < 1)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
void publish(const boost::shared_ptr< M > &message) const
static string g_output_topic
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 in_cb(const boost::shared_ptr< ShapeShifter const > &msg)
static ros::Publisher g_pub
int main(int argc, char **argv)
static ros::NodeHandle * g_node
topic_tools
Author(s): Morgan Quigley, Brian Gerkey, Dirk Thomas
, Jacob Perron
autogenerated on Sat Sep 14 2024 03:00:05