robot_activity_tutorials_minimal_node.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  *********************************************************************/
37 #include <ros/ros.h>
39 
40 #include <robot_activity_msgs/State.h>
41 #include <std_srvs/Empty.h>
42 
44 {
45 
47 {
48 public:
49  /* Important to inherit the constructor */
50  using ManagedRobotActivity::ManagedRobotActivity;
52  {
53  ROS_DEBUG_STREAM(getNamespace() << " destructed!");
54  }
55 
56 private:
57  void onManagedCreate() override
58  {
59  subscriber_manager.subscribe("/heartbeat", 1,
61 
64 
65  auto timer = registerIsolatedTimer(
66  std::bind(&MyRobotActivity::myTimerCallback, this), 0.5, true);
67  };
68  void onManagedTerminate() override {};
69 
70  bool onManagedConfigure() override { return true; };
71  bool onManagedUnconfigure() override { return true; };
72 
73  bool onManagedStart() override { return true; };
74  bool onManagedStop() override { return true; };
75 
76  bool onManagedResume() override { return true; };
77  bool onManagedPause() override { return true; };
78 
80  {
81  ROS_INFO_STREAM(getNamespace() << " Timer Counter: " << counter);
82  counter++;
83  unsigned int seed = time(NULL);
84  float r2 = rand_r(&seed) / (RAND_MAX / 0.10);
85  ros::Duration(2.05 - r2).sleep();
86  };
87 
89  {
91  << msg->node_name << " is in " << unsigned(msg->state));
92  };
93 
95  std_srvs::Empty::Request& request,
96  std_srvs::Empty::Response& response)
97  {
98  ROS_INFO_STREAM(getNamespace() << " Service called, returning true");
99  return true;
100  };
101 
102  int counter = 0;
103 };
104 
105 } // namespace robot_activity_tutorials
106 
107 int main(int argc, char *argv[])
108 {
110 
111  MyRobotActivity node1(argc, argv, "first");
112  node1.init().runAsync();
113 
114  MyRobotActivity node2(argc, argv, "second");
115  node2.init().runAsync();
116 
118  return 0;
119 }
int main(int argc, char *argv[])
void mySubscriberCallback(boost::shared_ptr< robot_activity_msgs::State const > msg)
resource::SubscriberManager subscriber_manager
bool sleep() const
resource::ServiceServerManager service_manager
ManagedServiceServer::SharedPtr advertiseService(Args &&...args)
bool myServiceCallback(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
std::shared_ptr< IsolatedAsyncTimer > registerIsolatedTimer(const IsolatedAsyncTimer::LambdaCallback &callback, const float &frequency, bool stoppable=true, bool autostart=false, bool oneshot=false)
#define ROS_DEBUG_STREAM(args)
#define ROS_INFO_STREAM(args)
ManagedSubscriber::SharedPtr subscribe(Args &&...args)
std::string getNamespace() const
ROSCPP_DECL void waitForShutdown()


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