Fawkes API  Fawkes Development Version
talkerpub_thread.h
1 
2 /***************************************************************************
3  * talkerpub_thread.h - Publish talker messages via ROS
4  *
5  * Created: Thu May 05 18:48:40 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 #ifndef __PLUGINS_ROS_TALKERPUB_THREAD_H_
24 #define __PLUGINS_ROS_TALKERPUB_THREAD_H_
25 
26 #include <core/threading/thread.h>
27 #include <core/utils/lockptr.h>
28 #include <aspect/logging.h>
29 #include <aspect/configurable.h>
30 #include <aspect/clock.h>
31 #include <aspect/blocked_timing.h>
32 #include <plugins/ros/aspect/ros.h>
33 
34 #include <ros/publisher.h>
35 
37 : public fawkes::Thread,
39  public fawkes::LoggingAspect,
41  public fawkes::ClockAspect,
42  public fawkes::ROSAspect
43 {
44  public:
46  virtual ~ROSTalkerPubThread();
47 
48  virtual void init();
49  virtual void loop();
50  virtual void finalize();
51 
52  /** Stub to see name in backtrace for easier debugging. @see Thread::run() */
53  protected: virtual void run() { Thread::run(); }
54 
55  private:
56  ros::Publisher __pub;
57 };
58 
59 #endif
Thread aspect that allows to obtain the current time from the clock.
Definition: clock.h:36
Thread aspect to get access to a ROS node handle.
Definition: ros.h:39
virtual ~ROSTalkerPubThread()
Destructor.
ROSTalkerPubThread()
Constructor.
virtual void run()
Stub to see name in backtrace for easier debugging.
virtual void finalize()
Finalize the thread.
virtual void init()
Initialize the thread.
virtual void loop()
Code to execute in the thread.
Thread to publish messages via ROS.
Thread class encapsulation of pthreads.
Definition: thread.h:42
Thread aspect to use blocked timing.
Thread aspect to log output.
Definition: logging.h:35
Thread aspect to access configuration data.
Definition: configurable.h:35