Fawkes API  Fawkes Development Version
ros_joints_thread.h
1 
2 /***************************************************************************
3  * ros_joints_thread.h - Publish Robotino joint info via ROS
4  *
5  * Created: Fri Mar 30 10:55:31 2012
6  * Copyright 2011-2012 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_ROBOTINO_ROS_JOINTS_THREAD_H_
24 #define _PLUGINS_ROBOTINO_ROS_JOINTS_THREAD_H_
25 
26 #include <aspect/blackboard.h>
27 #include <aspect/blocked_timing.h>
28 #include <aspect/configurable.h>
29 #include <aspect/logging.h>
30 #include <core/threading/thread.h>
31 #include <plugins/ros/aspect/ros.h>
32 #include <ros/publisher.h>
33 #include <sensor_msgs/JointState.h>
34 
35 namespace fawkes {
36 class RobotinoSensorInterface;
37 }
38 
42  public fawkes::LoggingAspect,
43  public fawkes::ROSAspect
44 {
45 public:
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:
54  virtual void
55  run()
56  {
57  Thread::run();
58  }
59 
60 private: // members
62 
63  ros::Publisher pub_joints_;
64  sensor_msgs::JointState joint_state_msg_;
65 };
66 
67 #endif
RobotinoRosJointsThread::RobotinoRosJointsThread
RobotinoRosJointsThread()
Constructor.
Definition: ros_joints_thread.cpp:38
fawkes::BlockedTimingAspect
Definition: blocked_timing.h:54
RobotinoRosJointsThread::init
virtual void init()
Initialize the thread.
Definition: ros_joints_thread.cpp:45
RobotinoRosJointsThread
Definition: ros_joints_thread.h:38
fawkes::BlackBoardAspect
Definition: blackboard.h:36
fawkes
fawkes::LoggingAspect
Definition: logging.h:36
fawkes::RobotinoSensorInterface
Definition: RobotinoSensorInterface.h:37
fawkes::ROSAspect
Definition: ros.h:37
RobotinoRosJointsThread::loop
virtual void loop()
Code to execute in the thread.
Definition: ros_joints_thread.cpp:68
fawkes::Thread
Definition: thread.h:44
RobotinoRosJointsThread::finalize
virtual void finalize()
Finalize the thread.
Definition: ros_joints_thread.cpp:61
RobotinoRosJointsThread::run
virtual void run()
Stub to see name in backtrace for easier debugging.
Definition: ros_joints_thread.h:54