rtt_rosclock_sim_clock_activity.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2013, Johannes Meyer, TU Darmstadt
00005  *  Copyright (c) 2013, Intermodalics BVBA
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of TU Darmstadt and Intermodalics BVBA
00019  *     nor the names of its contributors may be
00020  *     used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  *  Copyright (c) 2014, Jonathan Bohren, The Johns Hopkins University
00037  *  - Generalized for multiple time sources
00038  *  - Integrated with rtt_rosclock package
00039  *********************************************************************/
00040 
00041 
00042 #ifndef __RTT_ROSCLOCK_RTT_ROSCLOCK_SIM_CLOCK_ACTIVITY_H
00043 #define __RTT_ROSCLOCK_RTT_ROSCLOCK_SIM_CLOCK_ACTIVITY_H
00044 
00045 #include <rtt/base/ActivityInterface.hpp>
00046 #include <rtt/base/RunnableInterface.hpp>
00047 
00048 #include <rtt/os/TimeService.hpp>
00049 #include <rtt/os/Mutex.hpp>
00050 
00051 #include <list>
00052 #include <string>
00053 
00054 namespace rtt_rosclock {
00055 
00056   class SimClockActivityManager;
00057 
00058   class SimClockActivity : public RTT::base::ActivityInterface
00059   {
00060   public:
00061     SimClockActivity(
00062         RTT::base::RunnableInterface* run = 0,
00063         const std::string& name = "SimClockActivity");
00064 
00065     SimClockActivity(
00066         RTT::Seconds period,
00067         RTT::base::RunnableInterface* r = 0,
00068         const std::string& name ="SimClockActivity");
00069 
00070     virtual ~SimClockActivity();
00071 
00072     virtual RTT::Seconds getPeriod() const;
00073     virtual bool isPeriodic() const;
00074     virtual bool setPeriod(RTT::Seconds s);
00075 
00076     virtual unsigned getCpuAffinity() const;
00077     virtual bool setCpuAffinity(unsigned cpu);
00078 
00079     virtual RTT::os::ThreadInterface* thread();
00080 
00081     virtual bool initialize();
00082     virtual void step();
00083 #if defined(RTT_VERSION_GTE)
00084 #if RTT_VERSION_GTE(2,9,0)
00085     virtual void work(RTT::base::RunnableInterface::WorkReason);
00086 #endif
00087 #endif
00088     virtual void loop();
00089     virtual bool breakLoop();
00090     virtual void finalize();
00091 
00092     virtual bool start();
00093     virtual bool stop();
00094 
00095     virtual bool isRunning() const;
00096     virtual bool isActive() const;
00097 
00098     virtual bool execute();
00099     virtual bool trigger();
00100     virtual bool timeout();
00101 
00102     virtual RTT::os::TimeService::ticks getLastExecutionTicks() const;
00103 
00104   private:
00105     std::string name_;
00106 
00108     RTT::Seconds period_;
00109 
00111     bool running_;
00112 
00114     bool active_;
00115 
00117     RTT::os::TimeService::ticks last_;
00118 
00120     boost::shared_ptr<SimClockActivityManager> manager_;
00121   };
00122 }
00123 
00124 #endif  // ifndef __RTT_ROSCLOCK_RTT_ROSCLOCK_SIM_CLOCK_ACTIVITY_H


rtt_rosclock
Author(s):
autogenerated on Mon Apr 3 2017 03:35:24