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 
00047 #include <rtt/os/TimeService.hpp>
00048 #include <rtt/os/Mutex.hpp>
00049 
00050 #include <list>
00051 #include <string>
00052 
00053 namespace rtt_rosclock {
00054 
00055   class SimClockActivityManager;
00056 
00057   class SimClockActivity : public RTT::base::ActivityInterface
00058   {
00059   public:
00060     SimClockActivity(
00061         RTT::base::RunnableInterface* run = 0,
00062         const std::string& name = "SimClockActivity");
00063 
00064     SimClockActivity(
00065         RTT::Seconds period, 
00066         RTT::base::RunnableInterface* r = 0,
00067         const std::string& name ="SimClockActivity");
00068 
00069     virtual ~SimClockActivity();
00070 
00071     virtual RTT::Seconds getPeriod() const;
00072     virtual bool setPeriod(RTT::Seconds s);
00073 
00074     virtual unsigned getCpuAffinity() const;
00075     virtual bool setCpuAffinity(unsigned cpu);
00076 
00077     virtual RTT::os::ThreadInterface* thread();
00078 
00079     virtual bool initialize();
00080     virtual void step();
00081     virtual void loop();
00082     virtual bool breakLoop();
00083     virtual void finalize();
00084 
00085     virtual bool start();
00086     virtual bool stop();
00087 
00088     virtual bool isRunning() const;
00089     virtual bool isPeriodic() const;
00090     virtual bool isActive() const;
00091 
00092     virtual bool execute();
00093     virtual bool trigger();
00094 
00095     virtual RTT::os::TimeService::ticks getLastExecutionTicks() const;
00096 
00097   private:
00098     std::string name_;
00099 
00101     RTT::Seconds period_;
00102 
00104     bool running_;
00105 
00107     bool active_;
00108 
00110     RTT::os::TimeService::ticks last_;
00111 
00113     boost::shared_ptr<SimClockActivityManager> manager_;
00114   };
00115 }
00116 
00117 #endif  // ifndef __RTT_ROSCLOCK_RTT_ROSCLOCK_SIM_CLOCK_ACTIVITY_H


rtt_rosclock
Author(s):
autogenerated on Wed Sep 16 2015 06:59:15