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)
75 ros::init(argc, argv, topic_name +
string(
"_drop"),
77 if ((argc != 4 && argc != 5) || atoi(argv[2]) < 0 || atoi(argv[3]) < 1)
static string g_output_topic
void publish(const boost::shared_ptr< M > &message) const
int main(int argc, char **argv)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
static ros::Publisher g_pub
static ros::NodeHandle * g_node
void in_cb(const boost::shared_ptr< ShapeShifter const > &msg)