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 <memory>
31 
32 #include <ros/ros.h>
33 
35 #include <move_base_msgs/MoveBaseAction.h>
36 #include <planner_cspace_msgs/MoveWithToleranceAction.h>
37 #include <nav_msgs/Path.h>
38 
40 
42 {
43 protected:
46 
49 
51  std::shared_ptr<MoveBaseClient> act_cli_;
52  std::shared_ptr<MoveWithToleranceClient> act_cli_tolerant_;
53 
54  nav_msgs::Path path_;
55  size_t pos_;
60 
61  void cbPath(const nav_msgs::Path::ConstPtr& msg)
62  {
63  path_ = *msg;
64  pos_ = 0;
65  }
66 
67 public:
69  : nh_()
70  , pnh_("~")
71  {
74  nh_, "patrol_nodes",
75  pnh_, "path", 1, &PatrolActionNode::cbPath, this);
76 
77  pnh_.param("with_tolerance", with_tolerance_, false);
78  pnh_.param("tolerance_lin", tolerance_lin_, 0.1);
79  pnh_.param("tolerance_ang", tolerance_ang_, 0.1);
80  pnh_.param("tolerance_ang_finish", tolerance_ang_finish_, 0.05);
81 
82  if (with_tolerance_)
83  {
84  act_cli_tolerant_.reset(new MoveWithToleranceClient("tolerant_move", false));
85  }
86  else
87  {
88  act_cli_.reset(new MoveBaseClient("move_base", false));
89  }
90 
91  pos_ = 0;
92  }
93  bool sendNextGoal()
94  {
95  if (path_.poses.size() <= pos_)
96  {
97  ROS_WARN("Patrol finished. Waiting next path.");
98  path_.poses.clear();
99 
100  return false;
101  }
102 
103  if (with_tolerance_)
104  {
105  planner_cspace_msgs::MoveWithToleranceGoal goal;
106 
107  goal.target_pose.header = path_.poses[pos_].header;
108  goal.target_pose.header.stamp = ros::Time::now();
109  goal.target_pose.pose = path_.poses[pos_].pose;
110  goal.goal_tolerance_lin = tolerance_lin_;
111  goal.goal_tolerance_ang = tolerance_ang_;
112  goal.goal_tolerance_ang_finish = tolerance_ang_finish_;
113 
114  act_cli_tolerant_->sendGoal(goal);
115  }
116  else
117  {
118  move_base_msgs::MoveBaseGoal goal;
119 
120  goal.target_pose.header = path_.poses[pos_].header;
121  goal.target_pose.header.stamp = ros::Time::now();
122  goal.target_pose.pose = path_.poses[pos_].pose;
123 
124  act_cli_->sendGoal(goal);
125  }
126  pos_++;
127 
128  return true;
129  }
130  void spin()
131  {
132  ros::Rate rate(1.0);
133 
134  while (ros::ok())
135  {
136  ros::spinOnce();
137  rate.sleep();
138 
139  if (path_.poses.size() == 0)
140  {
141  continue;
142  }
143 
144  if (pos_ == 0)
145  {
146  sendNextGoal();
147  continue;
148  }
149 
151  with_tolerance_ ?
152  act_cli_tolerant_->getState() :
153  act_cli_->getState();
155  {
156  ROS_INFO("Action has been finished.");
157  sendNextGoal();
158  }
160  {
161  ROS_ERROR("Action has been aborted. Skipping.");
162  sendNextGoal();
163  }
164  else if (state == actionlib::SimpleClientGoalState::LOST)
165  {
166  ROS_WARN_ONCE("Action server is not ready.");
167  }
168  }
169  }
170 };
171 
172 int main(int argc, char** argv)
173 {
174  ros::init(argc, argv, "patrol");
175 
176  PatrolActionNode pa;
177  pa.spin();
178 
179  return 0;
180 }
void cbPath(const nav_msgs::Path::ConstPtr &msg)
Definition: patrol.cpp:61
std::shared_ptr< MoveWithToleranceClient > act_cli_tolerant_
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:48
std::shared_ptr< MoveBaseClient > act_cli_
Definition: patrol.cpp:51
actionlib::SimpleActionClient< planner_cspace_msgs::MoveWithToleranceAction > MoveWithToleranceClient
Definition: patrol.cpp:45
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())
bool with_tolerance_
Definition: patrol.cpp:56
#define ROS_WARN(...)
#define ROS_WARN_ONCE(...)
bool sendNextGoal()
Definition: patrol.cpp:93
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
double tolerance_ang_finish_
Definition: patrol.cpp:59
ROSCPP_DECL bool ok()
nav_msgs::Path path_
Definition: patrol.cpp:54
ros::Subscriber sub_path_
Definition: patrol.cpp:50
bool sleep()
double tolerance_ang_
Definition: patrol.cpp:58
static Time now()
double tolerance_lin_
Definition: patrol.cpp:57
int main(int argc, char **argv)
Definition: patrol.cpp:172
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)
actionlib::SimpleActionClient< move_base_msgs::MoveBaseAction > MoveBaseClient
Definition: patrol.cpp:44
ros::NodeHandle nh_
Definition: patrol.cpp:47


planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Wed May 12 2021 02:20:42