robot_activity_tutorials.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2018, University of Luxembourg
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 University of Luxembourg nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  * Author: Maciej Zurad
00036  *********************************************************************/
00037 #include <robot_activity_tutorials/robot_activity_tutorials.h>
00038 
00039 namespace robot_activity_tutorials
00040 {
00041 
00042 void RobotActivityTutorials::timerCallback()
00043 {
00044   ROS_INFO_STREAM(getNamespace() << " " << counter);
00045   counter++;
00046 }
00047 
00048 void RobotActivityTutorials::heartbeatCallback(
00049   boost::shared_ptr<robot_activity_msgs::State const> msg)
00050 {
00051   ROS_INFO_STREAM(getNamespace() << " State: " << unsigned(msg->state));
00052 }
00053 
00054 bool RobotActivityTutorials::serviceCallback(
00055   std_srvs::Empty::Request& request,
00056   std_srvs::Empty::Response& response)
00057 {
00058   ROS_INFO_STREAM(getNamespace() << " Service called, returning true");
00059   return true;
00060 }
00061 
00062 void RobotActivityTutorials::onManagedCreate()
00063 {
00064   ROS_INFO("onManagedCreate");
00065   /*
00066     C++11 lambda as Timer's callback
00067     context is a local variable, which is **copied** ([=]) into lambda its
00068     state can be changed due to **mutable** keyword
00069     The lambda callback has access to the class object since ([=]) captures
00070     **this** by reference, therefore we can access **node_namespace_**,
00071     which resides in RobotActivity class
00072   */
00073   int context = 0;
00074   robot_activity::IsolatedAsyncTimer::LambdaCallback cb = [ = ]() mutable
00075   {
00076     ROS_INFO_STREAM(getNamespace() << " " << context);
00077     context++;
00078   };
00079 
00080   /*
00081     registers the previous callback in timer at 1Hz, which is stoppable
00082     meaning that Timer will only be fired in RUNNING state
00083   */
00084   registerIsolatedTimer(cb, 1.0, true);
00085 
00086 
00087   /*
00088     registers timer with a member function of this class as a callback,
00089     which is std::bind'ed or boost:bind'ed
00090     This timer is unstoppable
00091   */
00092   registerIsolatedTimer(
00093     std::bind(&RobotActivityTutorials::timerCallback, this),
00094     1.0,
00095     false);
00096 
00097   subscriber_manager.subscribe("/heartbeat", 1, &RobotActivityTutorials::heartbeatCallback, this);
00098   service_manager.advertiseService("/test", &RobotActivityTutorials::serviceCallback, this);
00099 }
00100 
00101 void RobotActivityTutorials::onManagedTerminate()
00102 {
00103   ROS_INFO("onManagedTerminate");
00104 }
00105 
00106 bool RobotActivityTutorials::onManagedConfigure()
00107 {
00108   ROS_INFO("onManagedConfigure");
00109   return true;
00110 }
00111 
00112 bool RobotActivityTutorials::onManagedUnconfigure()
00113 {
00114   ROS_INFO("onManagedUnconfigure");
00115   return true;
00116 }
00117 
00118 bool RobotActivityTutorials::onManagedStart()
00119 {
00120   ROS_INFO("onManagedStart");
00121   return true;
00122 }
00123 
00124 bool RobotActivityTutorials::onManagedStop()
00125 {
00126   ROS_INFO("onManagedStop");
00127   return true;
00128 }
00129 
00130 bool RobotActivityTutorials::onManagedPause()
00131 {
00132   ROS_INFO("onManagedPause");
00133   return true;
00134 }
00135 
00136 bool RobotActivityTutorials::onManagedResume()
00137 {
00138   ROS_INFO("onManagedResume");
00139   return true;
00140 }
00141 
00142 }  // namespace robot_activity_tutorials


robot_activity_tutorials
Author(s): Maciej ZURAD
autogenerated on Thu Jun 6 2019 18:10:06