BootUpNode.cpp
Go to the documentation of this file.
1 #include "ros/ros.h"
2 #include "std_srvs/SetBool.h"
3 
4 bool boot_finished = false;
5 bool node_finished = false;
6 
7 bool bootUpService(std_srvs::SetBool::Request &req,
8  std_srvs::SetBool::Response &res) {
9  if (boot_finished) {
10  res.success = 1;
11  res.message = "Finished";
12  node_finished = true;
13  } else {
14  res.success = false;
15  res.message = "Still booting ...";
16  }
17  return true;
18 }
19 
21  boot_finished = true;
22 }
23 
24 int main(int argc, char **argv) {
25  ros::init(argc, argv, "bootUpNode");
26  ros::NodeHandle privateNh("~");
27  double wait_time;
28  privateNh.param<double>("wait_time", wait_time, 1);
29  ros::NodeHandle nh("rsm");
30  ros::ServiceServer bootup_service = nh.advertiseService("bootUpFinished",
32  ros::Timer timer = nh.createTimer(ros::Duration(wait_time), timerCallback,
33  true);
34 
35  while (ros::ok() && !node_finished) {
36  ros::spin();
37  }
38  return 0;
39 }
bool boot_finished
Definition: BootUpNode.cpp:4
bool bootUpService(std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res)
Definition: BootUpNode.cpp:7
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void timerCallback(const ros::TimerEvent &)
Definition: BootUpNode.cpp:20
ROSCPP_DECL void spin(Spinner &spinner)
int main(int argc, char **argv)
Definition: BootUpNode.cpp:24
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ROSCPP_DECL bool ok()
bool node_finished
Definition: BootUpNode.cpp:5


rsm_additions
Author(s): Marco Steinbrink
autogenerated on Tue Mar 16 2021 02:44:35