robot_activity_tutorials.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2018, University of Luxembourg
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 University of Luxembourg nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Maciej Zurad
36  *********************************************************************/
38 
40 {
41 
43 {
45  counter++;
46 }
47 
50 {
51  ROS_INFO_STREAM(getNamespace() << " State: " << unsigned(msg->state));
52 }
53 
55  std_srvs::Empty::Request& request,
56  std_srvs::Empty::Response& response)
57 {
58  ROS_INFO_STREAM(getNamespace() << " Service called, returning true");
59  return true;
60 }
61 
63 {
64  ROS_INFO("onManagedCreate");
65  /*
66  C++11 lambda as Timer's callback
67  context is a local variable, which is **copied** ([=]) into lambda its
68  state can be changed due to **mutable** keyword
69  The lambda callback has access to the class object since ([=]) captures
70  **this** by reference, therefore we can access **node_namespace_**,
71  which resides in RobotActivity class
72  */
73  int context = 0;
75  {
76  ROS_INFO_STREAM(getNamespace() << " " << context);
77  context++;
78  };
79 
80  /*
81  registers the previous callback in timer at 1Hz, which is stoppable
82  meaning that Timer will only be fired in RUNNING state
83  */
84  registerIsolatedTimer(cb, 1.0, true);
85 
86 
87  /*
88  registers timer with a member function of this class as a callback,
89  which is std::bind'ed or boost:bind'ed
90  This timer is unstoppable
91  */
93  std::bind(&RobotActivityTutorials::timerCallback, this),
94  1.0,
95  false);
96 
99 }
100 
102 {
103  ROS_INFO("onManagedTerminate");
104 }
105 
107 {
108  ROS_INFO("onManagedConfigure");
109  return true;
110 }
111 
113 {
114  ROS_INFO("onManagedUnconfigure");
115  return true;
116 }
117 
119 {
120  ROS_INFO("onManagedStart");
121  return true;
122 }
123 
125 {
126  ROS_INFO("onManagedStop");
127  return true;
128 }
129 
131 {
132  ROS_INFO("onManagedPause");
133  return true;
134 }
135 
137 {
138  ROS_INFO("onManagedResume");
139  return true;
140 }
141 
142 } // namespace robot_activity_tutorials
resource::SubscriberManager subscriber_manager
std::function< void(void)> LambdaCallback
resource::ServiceServerManager service_manager
#define ROS_INFO(...)
ManagedServiceServer::SharedPtr advertiseService(Args &&...args)
std::shared_ptr< IsolatedAsyncTimer > registerIsolatedTimer(const IsolatedAsyncTimer::LambdaCallback &callback, const float &frequency, bool stoppable=true, bool autostart=false, bool oneshot=false)
void heartbeatCallback(boost::shared_ptr< robot_activity_msgs::State const > msg)
#define ROS_INFO_STREAM(args)
ManagedSubscriber::SharedPtr subscribe(Args &&...args)
bool serviceCallback(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
std::string getNamespace() const


robot_activity_tutorials
Author(s): Maciej ZURAD
autogenerated on Mon Jun 10 2019 14:33:25