rtt_rosclock_sim_clock_thread.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Johannes Meyer, TU Darmstadt
5  * Copyright (c) 2013, Intermodalics BVBA
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of TU Darmstadt and Intermodalics BVBA
19  * nor the names of its contributors may be
20  * used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * Copyright (c) 2014, Jonathan Bohren, The Johns Hopkins University
37  * - Generalized for multiple time sources
38  * - Integrated with rtt_rosclock package
39  *********************************************************************/
40 
41 #ifndef __RTT_ROSCLOCK_SIM_CLOCK_THREAD_H
42 #define __RTT_ROSCLOCK_SIM_CLOCK_THREAD_H
43 
44 #include <rtt/Service.hpp>
45 #include <rtt/os/Thread.hpp>
46 #include <rtt/os/TimeService.hpp>
47 
48 #include <ros/ros.h>
49 #include <ros/subscriber.h>
50 #include <ros/callback_queue.h>
51 
52 #include <rosgraph_msgs/Clock.h>
53 
54 namespace rtt_rosclock {
55 
61  {
62  public:
68  static void Release();
69 
70  virtual ~SimClockThread();
71 
76  };
77 
79  bool setClockSource(SimClockSource clock_source);
81  bool useROSClockTopic();
83  bool useManualClock();
84 
86  bool simTimeEnabled() const;
87 
96  bool updateClock(const ros::Time new_time);
97 
98  protected:
99 
101  SimClockThread();
103  void operator=(SimClockThread const&);
104 
107 
109  void resetTimeService();
110 
112  bool updateClockInternal(const ros::Time new_time);
113 
114  // RTT::os::Thread interface
115  virtual bool initialize();
116  virtual void loop();
117  virtual bool breakLoop();
118  virtual void finalize();
119 
122 
125 
128 
136  void clockMsgCallback(const rosgraph_msgs::ClockConstPtr& clock);
137  };
138 
139 }
140 
141 #endif // ifndef __RTT_ROSCLOCK_RTT_ROSCLOCK_ACTIVITY_H
142 
143 
144 
bool useManualClock()
Set the clock source to use a manual source, i.e. call updateClock() manually.
bool updateClockInternal(const ros::Time new_time)
Update the RTT clock and SimClockActivities with a new time (see updateClock() for manually updating)...
void operator=(SimClockThread const &)
void resetTimeService()
Re-set the RTT::os::TimeService to zero and restart logging.
static boost::shared_ptr< SimClockThread > GetInstance()
Get an instance to the singleton SimClockThread or NULL.
bool useROSClockTopic()
Set the clock source to use the ROS /clock topic.
SimClockSource
Simulation clock sources.
ros::Subscriber clock_subscriber_
ROS /clock topic subscriber.
ros::NodeHandle nh_
ROS NodeHandle for communication.
static boost::shared_ptr< SimClockThread > Instance()
Get an instance to the singleton SimClockThread or create one.
static void Release()
Release the singleton SimClockThread.
bool updateClock(const ros::Time new_time)
ros::CallbackQueue callback_queue_
Custom callback queue used in this thread.
void clockMsgCallback(const rosgraph_msgs::ClockConstPtr &clock)
ROS message callback for /clock topic.
bool simTimeEnabled() const
Check if simulation time is enabled.
static boost::shared_ptr< SimClockThread > singleton
SimClockThread singleton.
bool setClockSource(SimClockSource clock_source)
Set the simulation clock source by ID (see ClockSource enum)
bool process_callbacks_
Keep running the thread loop if this is set to true.
SimClockThread()
Constructor is protected, use Instance() to create and get a singleton.
RTT::os::TimeService * time_service_
Convenient pointer to RTT time service.
SimClockSource clock_source_
Current clock source.


rtt_rosclock
Author(s):
autogenerated on Sat Jun 8 2019 18:06:00