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 <tf/types.h>
25 #include <stdio.h>
26 #include <math.h>
27 #include <utils/math/angle.h>
28 #include <core/threading/mutex_locker.h>
29 
30 #include <interfaces/Position3DInterface.h>
31 
32 #include <gazebo/transport/Node.hh>
33 #include <gazebo/msgs/msgs.hh>
34 #include <gazebo/transport/transport.hh>
35 #include <aspect/logging.h>
36 #include <tf/transform_publisher.h>
37 #include <utils/time/clock.h>
38 
39 using namespace fawkes;
40 using namespace gazebo;
41 
42 /** @class LocalizationSimThread "gazsim_localization_thread.h"
43  * Thread simulates the Localization in Gazebo
44  * @author Frederik Zwilling
45  */
46 
47 /** Constructor. */
49  : Thread("LocalizationSimThread", Thread::OPMODE_WAITFORWAKEUP),
50  BlockedTimingAspect(BlockedTimingAspect::WAKEUP_HOOK_SENSOR_PROCESS),
51  TransformAspect(TransformAspect::BOTH, "Pose")
52 {
53 }
54 
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_ = gazebonode->Subscribe(gps_topic_, &LocalizationSimThread::on_localization_msg, this);
70 
71  new_data_ = false;
72 }
73 
75 {
76  blackboard->close(localization_if_);
77 }
78 
80 {
81  if(new_data_)
82  {
83  //write interface
84  localization_if_->set_frame(global_frame_id_.c_str());
85  localization_if_->set_visibility_history(100);
86  localization_if_->set_translation(0, x_);
87  localization_if_->set_translation(1, y_);
88  localization_if_->set_translation(2, z_);
89  localization_if_->set_rotation(0, quat_x_);
90  localization_if_->set_rotation(1, quat_y_);
91  localization_if_->set_rotation(2, quat_z_);
92  localization_if_->set_rotation(3, quat_w_);
93  localization_if_->write();
94 
95  //publish transform (similar as in amcl_thread.cpp)
96  tf::Quaternion rotation = tf::Quaternion(quat_x_, quat_y_, quat_z_, quat_w_);
97  tf::Point position = tf::Point(x_, y_, z_);
98  tf::Transform latest_tf_ = tf::Transform(rotation,position);
99  Time transform_expiration =
100  (clock->now() + transform_tolerance_);
101  tf_publisher->send_transform(latest_tf_, transform_expiration,
102  global_frame_id_, odom_frame_id_);
103 
104  new_data_ = false;
105  }
106 }
107 
108 void LocalizationSimThread::on_localization_msg(ConstPosePtr &msg)
109 {
110  //logger->log_info(name(), "Got new Localization data.\n");
111 
112  MutexLocker lock(loop_mutex);
113 
114  //read data from message
115  x_ = msg->position().x();
116  y_ = msg->position().y();
117  z_ = msg->position().z();
118  quat_x_ = msg->orientation().x();
119  quat_y_ = msg->orientation().y();
120  quat_z_ = msg->orientation().z();
121  quat_w_ = msg->orientation().w();
122 
123  new_data_ = true;
124 }
void set_frame(const char *new_frame)
Set frame value.
tf::TransformPublisher * tf_publisher
This is the transform publisher which can be used to publish transforms via the blackboard.
Definition: tf.h:71
Definition: gps.h:30
Fawkes library namespace.
Mutex locking helper.
Definition: mutex_locker.h:33
A class for handling time.
Definition: time.h:91
void set_translation(unsigned int index, const double new_translation)
Set translation value at given index.
Thread class encapsulation of pthreads.
Definition: thread.h:42
void write()
Write from local copy into BlackBoard memory.
Definition: interface.cpp:500
void set_rotation(unsigned int index, const double new_rotation)
Set rotation value at given index.
Mutex * loop_mutex
Mutex that is used to protect a call to loop().
Definition: thread.h:139
Logger * logger
This is the Logger member used to access the logger.
Definition: logging.h:44
Thread aspect to access the transform system.
Definition: tf.h:42
Clock * clock
By means of this member access to the clock is given.
Definition: clock.h:45
Time now() const
Get the current time.
Definition: clock.cpp:269
Thread aspect to use blocked timing.
Position3DInterface Fawkes BlackBoard Interface.
void set_visibility_history(const int32_t new_visibility_history)
Set visibility_history value.
virtual void send_transform(const StampedTransform &transform, const bool is_static=false)
Publish transform.
virtual void init()
Initialize the thread.
const char * name() const
Get name of thread.
Definition: thread.h:95
gazebo::transport::NodePtr gazebonode
Gazebo Node for communication with a robot.
Definition: gazebo.h:47
virtual void log_debug(const char *component, const char *format,...)=0
Log debug message.
virtual void loop()
Code to execute in the thread.
Configuration * config
This is the Configuration member used to access the configuration.
Definition: configurable.h:44
virtual Interface * open_for_writing(const char *interface_type, const char *identifier, const char *owner=NULL)=0
Open interface for writing.
virtual float get_float(const char *path)=0
Get value from configuration which is of type float.
virtual void finalize()
Finalize the thread.
virtual std::string get_string(const char *path)=0
Get value from configuration which is of type string.
BlackBoard * blackboard
This is the BlackBoard instance you can use to interact with the BlackBoard.
Definition: blackboard.h:44
virtual void close(Interface *interface)=0
Close interface.