Logging.cpp
Go to the documentation of this file.
1 /*
2  * rosserial PubSub Example
3  * Prints "hello world!" and toggles led
4  */
5 
6 #include <ros.h>
7 #include <std_msgs/String.h>
8 #include <std_msgs/Empty.h>
9 
11 
12 std_msgs::String str_msg;
13 ros::Publisher chatter("chatter", &str_msg);
14 
15 char hello[13] = "hello world!";
16 
17 char debug[]= "debug statements";
18 char info[] = "infos";
19 char warn[] = "warnings";
20 char errors[] = "errors";
21 char fatal[] = "fatalities";
22 
23 int main() {
24  nh.initNode();
25  nh.advertise(chatter);
26 
27  while (1) {
28  str_msg.data = hello;
30 
31  nh.logdebug(debug);
32  nh.loginfo(info);
33  nh.logwarn(warn);
34  nh.logerror(errors);
35  nh.logfatal(fatal);
36 
37  nh.spinOnce();
38  wait_ms(500);
39  }
40 }
41 
void publish(const boost::shared_ptr< M > &message) const
std_msgs::String str_msg
Definition: Logging.cpp:12
int main()
Definition: Logging.cpp:23
char fatal[]
Definition: Logging.cpp:21
char debug[]
Definition: Logging.cpp:17
ros::Publisher chatter("chatter",&str_msg)
char hello[13]
Definition: Logging.cpp:15
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
char info[]
Definition: Logging.cpp:18
char errors[]
Definition: Logging.cpp:20
char warn[]
Definition: Logging.cpp:19
ros::NodeHandle nh
Definition: Logging.cpp:10


rosserial_mbed
Author(s): Gary Servin
autogenerated on Fri Jun 7 2019 22:02:48