Fawkes API  Fawkes Development Version
gazsim_localization_thread.cpp
1 /***************************************************************************
2  * gazsim_localization_thread.h - Thread provides
3  * the simulated position of a robot in Gazeo
4  *
5  * Created: Thu Aug 08 17:45:31 2013
6  * Copyright 2013 Frederik Zwilling
7  ****************************************************************************/
8 
9 /* This program is free software; you can redistribute it and/or modify
10  * it under the terms of the GNU General Public License as published by
11  * the Free Software Foundation; either version 2 of the License, or
12  * (at your option) any later version.
13  *
14  * This program is distributed in the hope that it will be useful,
15  * but WITHOUT ANY WARRANTY; without even the implied warranty of
16  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
17  * GNU Library General Public License for more details.
18  *
19  * Read the full text in the LICENSE.GPL file in the doc directory.
20  */
21 
22 #include "gazsim_localization_thread.h"
23 
24 #include <aspect/logging.h>
25 #include <core/threading/mutex_locker.h>
26 #include <interfaces/Position3DInterface.h>
27 #include <tf/transform_publisher.h>
28 #include <tf/types.h>
29 #include <utils/math/angle.h>
30 #include <utils/time/clock.h>
31 
32 #include <gazebo/msgs/msgs.hh>
33 #include <gazebo/transport/Node.hh>
34 #include <gazebo/transport/transport.hh>
35 #include <math.h>
36 #include <stdio.h>
37 
38 using namespace fawkes;
39 using namespace gazebo;
40 
41 /** @class LocalizationSimThread "gazsim_localization_thread.h"
42  * Thread simulates the Localization in Gazebo
43  * @author Frederik Zwilling
44  */
45 
46 /** Constructor. */
48 : Thread("LocalizationSimThread", Thread::OPMODE_WAITFORWAKEUP),
49  BlockedTimingAspect(BlockedTimingAspect::WAKEUP_HOOK_SENSOR_PROCESS),
50  TransformAspect(TransformAspect::BOTH, "Pose")
51 {
52 }
53 
54 void
56 {
57  logger->log_debug(name(), "Initializing Simulation of the Localization");
58 
59  //open interface
60  localization_if_ = blackboard->open_for_writing<Position3DInterface>("Pose");
61 
62  //read cofig values
63  gps_topic_ = config->get_string("/gazsim/topics/gps");
64  transform_tolerance_ = config->get_float("/plugins/amcl/transform_tolerance");
65  global_frame_id_ = config->get_string("/plugins/amcl/global_frame_id");
66  odom_frame_id_ = config->get_string("/plugins/amcl/odom_frame_id");
67 
68  //subscribing to gazebo publisher
69  localization_sub_ =
70  gazebonode->Subscribe(gps_topic_, &LocalizationSimThread::on_localization_msg, this);
71 
72  new_data_ = false;
73 }
74 
75 void
77 {
78  blackboard->close(localization_if_);
79 }
80 
81 void
83 {
84  if (new_data_) {
85  //write interface
86  localization_if_->set_frame(global_frame_id_.c_str());
87  localization_if_->set_visibility_history(100);
88  localization_if_->set_translation(0, x_);
89  localization_if_->set_translation(1, y_);
90  localization_if_->set_translation(2, z_);
91  localization_if_->set_rotation(0, quat_x_);
92  localization_if_->set_rotation(1, quat_y_);
93  localization_if_->set_rotation(2, quat_z_);
94  localization_if_->set_rotation(3, quat_w_);
95  localization_if_->write();
96 
97  //publish transform (similar as in amcl_thread.cpp)
98  tf::Quaternion rotation = tf::Quaternion(quat_x_, quat_y_, quat_z_, quat_w_);
99  tf::Point position = tf::Point(x_, y_, z_);
100  tf::Transform latest_tf_ = tf::Transform(rotation, position);
101  Time transform_expiration = (clock->now() + transform_tolerance_);
102  tf_publisher->send_transform(latest_tf_,
103  transform_expiration,
104  global_frame_id_,
105  odom_frame_id_);
106 
107  new_data_ = false;
108  }
109 }
110 
111 void
112 LocalizationSimThread::on_localization_msg(ConstPosePtr &msg)
113 {
114  //logger->log_info(name(), "Got new Localization data.\n");
115 
116  MutexLocker lock(loop_mutex);
117 
118  //read data from message
119  x_ = msg->position().x();
120  y_ = msg->position().y();
121  z_ = msg->position().z();
122  quat_x_ = msg->orientation().x();
123  quat_y_ = msg->orientation().y();
124  quat_z_ = msg->orientation().z();
125  quat_w_ = msg->orientation().w();
126 
127  new_data_ = true;
128 }
fawkes::Position3DInterface::set_rotation
void set_rotation(unsigned int index, const double new_rotation)
Set rotation value at given index.
Definition: Position3DInterface.cpp:203
fawkes::Position3DInterface::set_frame
void set_frame(const char *new_frame)
Set frame value.
Definition: Position3DInterface.cpp:97
fawkes::MutexLocker
Mutex locking helper.
Definition: mutex_locker.h:34
fawkes::GazeboAspect::gazebonode
gazebo::transport::NodePtr gazebonode
Gazebo Node for communication with a robot.
Definition: gazebo.h:46
fawkes::BlockedTimingAspect
Thread aspect to use blocked timing.
Definition: blocked_timing.h:51
fawkes::Thread::name
const char * name() const
Get name of thread.
Definition: thread.h:100
fawkes::ClockAspect::clock
Clock * clock
By means of this member access to the clock is given.
Definition: clock.h:42
LocalizationSimThread::loop
virtual void loop()
Code to execute in the thread.
Definition: gazsim_localization_thread.cpp:82
LocalizationSimThread::LocalizationSimThread
LocalizationSimThread()
Constructor.
Definition: gazsim_localization_thread.cpp:47
fawkes::LoggingAspect::logger
Logger * logger
This is the Logger member used to access the logger.
Definition: logging.h:41
fawkes::BlackBoard::close
virtual void close(Interface *interface)=0
Close interface.
fawkes::Position3DInterface::set_translation
void set_translation(unsigned int index, const double new_translation)
Set translation value at given index.
Definition: Position3DInterface.cpp:266
fawkes::Clock::now
Time now() const
Get the current time.
Definition: clock.cpp:242
fawkes
Fawkes library namespace.
fawkes::tf::TransformPublisher::send_transform
virtual void send_transform(const StampedTransform &transform, const bool is_static=false)
Publish transform.
Definition: transform_publisher.cpp:115
fawkes::TransformAspect
Thread aspect to access the transform system.
Definition: tf.h:39
fawkes::ConfigurableAspect::config
Configuration * config
This is the Configuration member used to access the configuration.
Definition: configurable.h:41
fawkes::Time
A class for handling time.
Definition: time.h:93
fawkes::Position3DInterface::set_visibility_history
void set_visibility_history(const int32_t new_visibility_history)
Set visibility_history value.
Definition: Position3DInterface.cpp:139
fawkes::Configuration::get_float
virtual float get_float(const char *path)=0
Get value from configuration which is of type float.
fawkes::Thread
Thread class encapsulation of pthreads.
Definition: thread.h:46
fawkes::Position3DInterface
Position3DInterface Fawkes BlackBoard Interface.
Definition: Position3DInterface.h:34
fawkes::TransformAspect::tf_publisher
tf::TransformPublisher * tf_publisher
This is the transform publisher which can be used to publish transforms via the blackboard.
Definition: tf.h:68
fawkes::BlackBoardAspect::blackboard
BlackBoard * blackboard
This is the BlackBoard instance you can use to interact with the BlackBoard.
Definition: blackboard.h:44
fawkes::Configuration::get_string
virtual std::string get_string(const char *path)=0
Get value from configuration which is of type string.
LocalizationSimThread::init
virtual void init()
Initialize the thread.
Definition: gazsim_localization_thread.cpp:55
fawkes::Thread::loop_mutex
Mutex * loop_mutex
Mutex that is used to protect a call to loop().
Definition: thread.h:152
LocalizationSimThread::finalize
virtual void finalize()
Finalize the thread.
Definition: gazsim_localization_thread.cpp:76
fawkes::Logger::log_debug
virtual void log_debug(const char *component, const char *format,...)=0
Log debug message.
fawkes::Interface::write
void write()
Write from local copy into BlackBoard memory.
Definition: interface.cpp:494
fawkes::BlackBoard::open_for_writing
virtual Interface * open_for_writing(const char *interface_type, const char *identifier, const char *owner=NULL)=0
Open interface for writing.