Fawkes API
Fawkes Development Version
odometry_thread.h
1
/***************************************************************************
2
* odometry_thread.h - Thread to publish odometry to ROS
3
*
4
* Created: Fri Jun 1 13:29:39 CEST
5
* Copyright 2012 Sebastian Reuter
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_ROS_ODOMETRY_THREAD_H_
22
#define _PLUGINS_ROS_ODOMETRY_THREAD_H_
23
24
#include <aspect/blackboard.h>
25
#include <aspect/blocked_timing.h>
26
#include <aspect/configurable.h>
27
#include <aspect/logging.h>
28
#include <core/threading/thread.h>
29
#include <core/utils/lockptr.h>
30
#include <plugins/ros/aspect/ros.h>
31
#include <ros/node_handle.h>
32
33
namespace
fawkes
{
34
class
MotorInterface;
35
}
36
37
class
ROSOdometryThread
:
public
fawkes::Thread
,
38
public
fawkes::BlockedTimingAspect
,
39
public
fawkes::LoggingAspect
,
40
public
fawkes::ConfigurableAspect
,
41
public
fawkes::BlackBoardAspect
,
42
public
fawkes::ROSAspect
43
{
44
public
:
45
ROSOdometryThread
();
46
47
virtual
void
init
();
48
virtual
void
loop
();
49
virtual
void
finalize
();
50
51
/** Stub to see name in backtrace for easier debugging. @see Thread::run() */
52
protected
:
53
virtual
void
54
run
()
55
{
56
Thread::run();
57
}
58
59
private
:
60
void
publish_odom();
61
62
private
:
63
fawkes::MotorInterface
* motor_if_;
64
ros::Publisher pub_;
65
std::string cfg_odom_frame_id_;
66
std::string cfg_base_frame_id_;
67
boost::array<double, 36> odom_covariance_;
68
};
69
70
#endif
ROSOdometryThread::finalize
virtual void finalize()
Finalize the thread.
Definition:
odometry_thread.cpp:63
ROSOdometryThread
Definition:
odometry_thread.h:36
ROSOdometryThread::loop
virtual void loop()
Code to execute in the thread.
Definition:
odometry_thread.cpp:98
fawkes::BlockedTimingAspect
Definition:
blocked_timing.h:54
fawkes::MotorInterface
Definition:
MotorInterface.h:37
ROSOdometryThread::ROSOdometryThread
ROSOdometryThread()
Constructor.
Definition:
odometry_thread.cpp:35
fawkes::BlackBoardAspect
Definition:
blackboard.h:36
fawkes
fawkes::LoggingAspect
Definition:
logging.h:36
fawkes::ROSAspect
Definition:
ros.h:37
fawkes::Thread
Definition:
thread.h:44
fawkes::ConfigurableAspect
Definition:
configurable.h:36
ROSOdometryThread::init
virtual void init()
Initialize the thread.
Definition:
odometry_thread.cpp:42
ROSOdometryThread::run
virtual void run()
Stub to see name in backtrace for easier debugging.
Definition:
odometry_thread.h:53
src
plugins
ros
odometry_thread.h
Generated by
1.8.16