continuous_segmenter.cpp
Go to the documentation of this file.
1 
12 #include <ros/ros.h>
13 #include <std_srvs/Empty.h>
14 
15 using namespace std;
16 
24 int main(int argc, char **argv)
25 {
26  // initialize ROS and the node
27  ros::init(argc, argv, "continuous_segmenter");
28 
29  ros::NodeHandle node;
30  ros::NodeHandle pnh("~");
31  ros::ServiceClient segmentClient;
32  segmentClient = node.serviceClient<std_srvs::Empty>("rail_segmentation/segment");
33  std_srvs::Empty srv;
34  double rate;
35  pnh.param("segmentation_rate", rate, 0.5);
36 
37  ros::Rate loop_rate(rate);
38  while (ros::ok())
39  {
40  segmentClient.call(srv);
41  ros::spinOnce();
42  loop_rate.sleep();
43  }
44 
45  return EXIT_SUCCESS;
46 }
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ROSCPP_DECL bool ok()
bool sleep()
ROSCPP_DECL void spinOnce()


rail_segmentation
Author(s): Russell Toris , David Kent
autogenerated on Sun Feb 16 2020 04:02:44