Fawkes API  Fawkes Development Version
rospub_thread.h
1 /***************************************************************************
2  * navgraph_rospub_thread.h - Publish navgraph to ROS
3  *
4  * Created: Wed Jun 08 20:16:31 2016
5  * Copyright 2016 Tim Niemueller [www.niemueller.de]
6  ****************************************************************************/
7 
8 /* This program is free software; you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation; either version 2 of the License, or
11  * (at your option) any later version.
12  *
13  * This program is distributed in the hope that it will be useful,
14  * but WITHOUT ANY WARRANTY; without even the implied warranty of
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  * GNU Library General Public License for more details.
17  *
18  * Read the full text in the LICENSE.GPL file in the doc directory.
19  */
20 
21 #ifndef __PLUGINS_NAVGRAPH_NAVGRAPH_ROSPUB_THREAD_H_
22 #define __PLUGINS_NAVGRAPH_NAVGRAPH_ROSPUB_THREAD_H_
23 
24 #include <core/threading/thread.h>
25 #include <aspect/clock.h>
26 #include <aspect/configurable.h>
27 #include <aspect/logging.h>
28 #include <aspect/aspect_provider.h>
29 #include <plugins/ros/aspect/ros.h>
30 #include <navgraph/aspect/navgraph.h>
31 
32 #include <navgraph/navgraph.h>
33 
34 #include <ros/publisher.h>
35 
37 : public fawkes::Thread,
38  public fawkes::ClockAspect,
39  public fawkes::LoggingAspect,
41  public fawkes::ROSAspect,
44 {
45  private:
46  public:
48  virtual ~NavGraphROSPubThread();
49 
50  virtual void init();
51  virtual void loop();
52  virtual void finalize();
53 
54  virtual void graph_changed() throw();
55 
56  /** Stub to see name in backtrace for easier debugging. @see Thread::run() */
57  protected: virtual void run() { Thread::run();}
58 
59  private:
60  void publish_graph();
61 
62  private:
63  ros::Publisher pub_;
64 };
65 
66 #endif
Publish navgaraph to ROS.
Definition: rospub_thread.h:36
NavGraphROSPubThread()
Constructor.
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 void init()
Initialize the thread.
Thread class encapsulation of pthreads.
Definition: thread.h:42
virtual void finalize()
Finalize the thread.
Thread aspect to log output.
Definition: logging.h:35
Thread aspect to access configuration data.
Definition: configurable.h:35
virtual void loop()
Code to execute in the thread.
virtual ~NavGraphROSPubThread()
Destructor.
Topological graph change listener.
Definition: navgraph.h:175
virtual void graph_changed()
Function called if the graph has been changed.
virtual void run()
Stub to see name in backtrace for easier debugging.
Definition: rospub_thread.h:57
Thread aspect to access NavGraph.
Definition: navgraph.h:37