patrol.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2016-2017, the neonavigation authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <ros/ros.h>
31 
33 #include <move_base_msgs/MoveBaseAction.h>
34 #include <nav_msgs/Path.h>
35 
37 
39 {
40 protected:
42 
45 
47  std::shared_ptr<MoveBaseClient> act_cli_;
48 
49  nav_msgs::Path path_;
50  size_t pos_;
51 
52  void cbPath(const nav_msgs::Path::ConstPtr& msg)
53  {
54  path_ = *msg;
55  pos_ = 0;
56  }
57 
58 public:
60  : nh_()
61  , pnh_("~")
62  {
65  nh_, "patrol_nodes",
66  pnh_, "path", 1, &PatrolActionNode::cbPath, this);
67  act_cli_.reset(new MoveBaseClient("move_base", false));
68 
69  pos_ = 0;
70  }
71  bool sendNextGoal()
72  {
73  move_base_msgs::MoveBaseGoal goal;
74 
75  if (path_.poses.size() <= pos_)
76  {
77  ROS_WARN("Patrol finished. Waiting next path.");
78  path_.poses.clear();
79 
80  return false;
81  }
82 
83  goal.target_pose.header = path_.poses[pos_].header;
84  goal.target_pose.header.stamp = ros::Time::now();
85  goal.target_pose.pose = path_.poses[pos_].pose;
86 
87  act_cli_->sendGoal(goal);
88  pos_++;
89 
90  return true;
91  }
92  void spin()
93  {
94  ros::Rate rate(1.0);
95 
96  while (ros::ok())
97  {
98  ros::spinOnce();
99  rate.sleep();
100 
101  if (path_.poses.size() == 0)
102  {
103  continue;
104  }
105 
106  if (pos_ == 0)
107  {
108  sendNextGoal();
109  continue;
110  }
111 
112  actionlib::SimpleClientGoalState state = act_cli_->getState();
114  {
115  ROS_INFO("Action has been finished.");
116  sendNextGoal();
117  }
119  {
120  ROS_ERROR("Action has been aborted. Skipping.");
121  sendNextGoal();
122  }
123  else if (state == actionlib::SimpleClientGoalState::LOST)
124  {
125  ROS_WARN_ONCE("Action server is not ready.");
126  }
127  }
128  }
129 };
130 
131 int main(int argc, char** argv)
132 {
133  ros::init(argc, argv, "patrol");
134 
135  PatrolActionNode pa;
136  pa.spin();
137 
138  return 0;
139 }
void cbPath(const nav_msgs::Path::ConstPtr &msg)
Definition: patrol.cpp:52
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::NodeHandle pnh_
Definition: patrol.cpp:44
std::shared_ptr< MoveBaseClient > act_cli_
Definition: patrol.cpp:47
ros::Subscriber subscribe(ros::NodeHandle &nh_new, const std::string &topic_new, ros::NodeHandle &nh_old, const std::string &topic_old, uint32_t queue_size, void(*fp)(M), const ros::TransportHints &transport_hints=ros::TransportHints())
#define ROS_WARN(...)
#define ROS_WARN_ONCE(...)
bool sendNextGoal()
Definition: patrol.cpp:71
#define ROS_INFO(...)
ROSCPP_DECL bool ok()
nav_msgs::Path path_
Definition: patrol.cpp:49
ros::Subscriber sub_path_
Definition: patrol.cpp:46
bool sleep()
static Time now()
int main(int argc, char **argv)
Definition: patrol.cpp:131
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)
actionlib::SimpleActionClient< move_base_msgs::MoveBaseAction > MoveBaseClient
Definition: patrol.cpp:41
ros::NodeHandle nh_
Definition: patrol.cpp:43


planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Tue Jul 9 2019 05:00:13