Fawkes API  Fawkes Development Version
talkerpub_thread.cpp
1 
2 /***************************************************************************
3  * talkerpub_thread.cpp - Publish talker messages via ROS
4  *
5  * Created: Thu May 05 18:50:04 2011
6  * Copyright 2006-2011 Tim Niemueller [www.niemueller.de]
7  *
8  ****************************************************************************/
9 
10 /* This program is free software; you can redistribute it and/or modify
11  * it under the terms of the GNU General Public License as published by
12  * the Free Software Foundation; either version 2 of the License, or
13  * (at your option) any later version.
14  *
15  * This program is distributed in the hope that it will be useful,
16  * but WITHOUT ANY WARRANTY; without even the implied warranty of
17  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
18  * GNU Library General Public License for more details.
19  *
20  * Read the full text in the LICENSE.GPL file in the doc directory.
21  */
22 
23 #include "talkerpub_thread.h"
24 
25 #include <ros/ros.h>
26 #include <std_msgs/String.h>
27 
28 using namespace fawkes;
29 
30 /** @class ROSTalkerPubThread "talkerpub_thread.h"
31  * Thread to publish messages via ROS.
32  *
33  * @author Tim Niemueller
34  */
35 
36 /** Constructor. */
38 : Thread("ROSTalkerPubThread", Thread::OPMODE_WAITFORWAKEUP),
40 {
41 }
42 
43 /** Destructor. */
45 {
46 }
47 
48 void
50 {
51  pub_ = rosnode->advertise<std_msgs::String>("/chatter", 10);
52 }
53 
54 void
56 {
57  pub_.shutdown();
58 }
59 
60 void
62 {
63  Time t;
64 
65  std_msgs::String msg;
66  msg.data = std::string("Hello world ") + t.str();
67 
68  pub_.publish(msg);
69 }
const char * str(bool utc=false) const
Output function.
Definition: time.cpp:790
virtual ~ROSTalkerPubThread()
Destructor.
ROSTalkerPubThread()
Constructor.
Fawkes library namespace.
virtual void finalize()
Finalize the thread.
virtual void init()
Initialize the thread.
A class for handling time.
Definition: time.h:92
virtual void loop()
Code to execute in the thread.
Thread class encapsulation of pthreads.
Definition: thread.h:45
Thread aspect to use blocked timing.
LockPtr< ros::NodeHandle > rosnode
Central ROS node handle.
Definition: ros.h:47