7 #include <std_msgs/String.h> 8 #include <std_msgs/Empty.h> 11 DigitalOut
myled(LED1);
13 void messageCb(
const std_msgs::Empty& toggle_msg) {
22 char hello[13] =
"hello world!";
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber< std_msgs::Empty > sub("toggle_led", messageCb)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher chatter("chatter",&str_msg)
void messageCb(const std_msgs::Empty &toggle_msg)