rtt_rosclock_sim_clock_activity.cpp
Go to the documentation of this file.
00001 
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2013, Johannes Meyer, TU Darmstadt
00006  *  Copyright (c) 2013, Intermodalics BVBA
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of TU Darmstadt and Intermodalics BVBA
00020  *     nor the names of its contributors may be
00021  *     used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  *  Copyright (c) 2014, Jonathan Bohren, The Johns Hopkins University
00038  *  - Generalized for multiple time sources
00039  *  - Integrated with rtt_rosclock package
00040  *********************************************************************/
00041 
00042 #include <rtt_rosclock/rtt_rosclock_sim_clock_activity.h>
00043 #include <rtt_rosclock/rtt_rosclock_sim_clock_activity_manager.h>
00044 
00045 #include <rtt/base/RunnableInterface.hpp>
00046 #include <rtt/os/TimeService.hpp>
00047 #include <rtt/Logger.hpp>
00048 
00049 #include <boost/weak_ptr.hpp>
00050 
00051 using namespace RTT::base;
00052 using namespace rtt_rosclock;
00053 
00054 
00055 SimClockActivity::SimClockActivity(RunnableInterface* run, const std::string& name)
00056 : ActivityInterface(run)
00057   , name_(name)
00058   , period_(0.0)
00059   , running_(false)
00060   , active_(false)
00061   , manager_(SimClockActivityManager::Instance())
00062 {
00063   manager_->add(this);
00064 }
00065 
00066 SimClockActivity::SimClockActivity(RTT::Seconds period, RunnableInterface* run, const std::string& name)
00067 : ActivityInterface(run)
00068   , name_(name)
00069   , period_(period)
00070   , running_(false)
00071   , active_(false)
00072   , manager_(SimClockActivityManager::Instance())
00073 {
00074   manager_->add(this);
00075 }
00076 
00077 SimClockActivity::~SimClockActivity()
00078 {
00079   stop();
00080   manager_->remove(this);
00081 }
00082 
00083 RTT::Seconds SimClockActivity::getPeriod() const
00084 {
00085   if (period_ > 0.0)
00086     return period_;
00087   else
00088     return manager_->getSimulationPeriod();
00089 }
00090 
00091 bool SimClockActivity::setPeriod(RTT::Seconds s)
00092 {
00093   period_ = s;
00094   return true;
00095 }
00096 
00097 unsigned SimClockActivity::getCpuAffinity() const
00098 {
00099   return ~0;
00100 }
00101 
00102 bool SimClockActivity::setCpuAffinity(unsigned cpu)
00103 {
00104   return false;
00105 }
00106 
00107 RTT::os::ThreadInterface* SimClockActivity::thread()
00108 {
00109   return 0;
00110 }
00111 
00112 bool SimClockActivity::initialize()
00113 {
00114   return true;
00115 }
00116 
00117 void SimClockActivity::step()
00118 {
00119 }
00120 
00121 void SimClockActivity::loop()
00122 {
00123   this->step();
00124 }
00125 
00126 bool SimClockActivity::breakLoop()
00127 {
00128   return false;
00129 }
00130 
00131 
00132 void SimClockActivity::finalize()
00133 {
00134 }
00135 
00136 bool SimClockActivity::start()
00137 {
00138   if ( active_ == true )
00139   {
00140     RTT::log(RTT::Error) << "Unable to start slave as it is already started" << RTT::endlog();
00141     return false;
00142   }
00143 
00144   active_ = true;
00145   last_ = 0;
00146 
00147   if ( runner ? runner->initialize() : this->initialize() ) {
00148     running_ = true;
00149   } else {
00150     active_ = false;
00151   }
00152 
00153   return active_;
00154 }
00155 
00156 bool SimClockActivity::stop()
00157 {
00158   if ( !active_ )
00159     return false;
00160 
00161   running_ = false;
00162   if (runner)
00163     runner->finalize();
00164   else
00165     this->finalize();
00166   active_ = false;
00167   return true;
00168 }
00169 
00170 bool SimClockActivity::isRunning() const
00171 {
00172   return running_;
00173 }
00174 
00175 bool SimClockActivity::isPeriodic() const
00176 {
00177   return true;
00178 }
00179 
00180 bool SimClockActivity::isActive() const
00181 {
00182   return active_;
00183 }
00184 
00185 bool SimClockActivity::trigger()
00186 {
00187   return false;
00188 }
00189 
00190 bool SimClockActivity::execute()
00191 {
00192   if (!running_) return false;
00193   if (runner) runner->step(); else this->step();
00194   last_ = RTT::os::TimeService::Instance()->getTicks();
00195   return true;
00196 }
00197 
00198 RTT::os::TimeService::ticks SimClockActivity::getLastExecutionTicks() const
00199 {
00200   return last_;
00201 }


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