locomotor.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #include <locomotor/locomotor.h>
36 #include <nav_2d_utils/tf_help.h>
37 #include <functional>
38 #include <memory>
39 #include <string>
40 
41 namespace locomotor
42 {
44 {
45  ros::WallDuration duration = ros::WallTime::now() - start_time;
46  return ros::Duration(duration.sec, duration.nsec);
47 }
48 
50  costmap_loader_("nav_core2", "nav_core2::Costmap"),
51  global_planner_mux_("nav_core2", "nav_core2::GlobalPlanner",
52  "global_planner_namespaces", "dlux_global_planner::DluxGlobalPlanner",
53  "current_global_planner", "switch_global_planner"),
54  local_planner_mux_("nav_core2", "nav_core2::LocalPlanner",
55  "local_planner_namespaces", "dwb_local_planner::DWBLocalPlanner",
56  "current_local_planner", "switch_local_planner"),
57  private_nh_(private_nh), path_pub_(private_nh_), twist_pub_(private_nh_)
58 {
59  tf_ = std::make_shared<tf::TransformListener>(ros::Duration(10));
60 
61  private_nh_.param("robot_base_frame", robot_base_frame_, std::string("base_link"));
62 
63  // If true, when getting robot pose, use ros::Time(0) instead of ros::Time::now()
64  private_nh_.param("use_latest_pose", use_latest_pose_, true);
65 
66  local_planner_mux_.setSwitchCallback(std::bind(&Locomotor::switchLocalPlannerCallback, this, std::placeholders::_1,
67  std::placeholders::_2));
68 
69  ros::NodeHandle global_nh;
70  odom_sub_ = std::make_shared<nav_2d_utils::OdomSubscriber>(global_nh);
71 }
72 
74 {
75  std::string costmap_class;
76  private_nh_.param("global_costmap_class", costmap_class, std::string("nav_core_adapter::CostmapAdapter"));
77  ROS_INFO_NAMED("Locomotor", "Loading Global Costmap %s", costmap_class.c_str());
78  global_costmap_ = costmap_loader_.createUniqueInstance(costmap_class);
79  ROS_INFO_NAMED("Locomotor", "Initializing Global Costmap");
80  global_costmap_->initialize(ex.getNodeHandle(), "global_costmap", tf_);
81 }
82 
84 {
85  std::string costmap_class;
86  private_nh_.param("local_costmap_class", costmap_class, std::string("nav_core_adapter::CostmapAdapter"));
87  ROS_INFO_NAMED("Locomotor", "Loading Local Costmap %s", costmap_class.c_str());
88  local_costmap_ = costmap_loader_.createUniqueInstance(costmap_class);
89  ROS_INFO_NAMED("Locomotor", "Initializing Local Costmap");
90  local_costmap_->initialize(ex.getNodeHandle(), "local_costmap", tf_);
91 }
92 
94 {
95  for (auto planner_name : global_planner_mux_.getPluginNames())
96  {
97  ROS_INFO_NAMED("Locomotor", "Initializing global planner %s", planner_name.c_str());
98  global_planner_mux_.getPlugin(planner_name).initialize(ex.getNodeHandle(), planner_name, tf_, global_costmap_);
99  }
100 }
101 
103 {
104  for (auto planner_name : local_planner_mux_.getPluginNames())
105  {
106  ROS_INFO_NAMED("Locomotor", "Initializing local planner %s", planner_name.c_str());
107  local_planner_mux_.getPlugin(planner_name).initialize(ex.getNodeHandle(), planner_name, tf_, local_costmap_);
108  }
109 }
110 
111 void Locomotor::setGoal(nav_2d_msgs::Pose2DStamped goal)
112 {
113  local_planner_mux_.getCurrentPlugin().setGoalPose(goal);
114  state_ = locomotor_msgs::NavigationState();
115  state_.goal = goal;
116 }
117 
118 void Locomotor::switchLocalPlannerCallback(const std::string&, const std::string& new_planner)
119 {
120  auto& new_local_planner = local_planner_mux_.getPlugin(new_planner);
121  new_local_planner.setGoalPose(state_.goal);
122  new_local_planner.setPlan(state_.global_plan);
123 }
124 
127 {
128  work_ex.addCallback(
129  std::bind(&Locomotor::doCostmapUpdate, this, std::ref(*global_costmap_), std::ref(result_ex), cb, fail_cb));
130 }
131 
134 {
135  work_ex.addCallback(
136  std::bind(&Locomotor::doCostmapUpdate, this, std::ref(*local_costmap_), std::ref(result_ex), cb, fail_cb));
137 }
138 
141 {
142  work_ex.addCallback(std::bind(&Locomotor::makeGlobalPlan, this, std::ref(result_ex), cb, fail_cb));
143 }
144 
147  NavigationCompleteCallback complete_cb)
148 {
149  work_ex.addCallback(std::bind(&Locomotor::makeLocalPlan, this, std::ref(result_ex), cb, fail_cb, complete_cb));
150 }
151 
152 void Locomotor::requestNavigationFailure(Executor& result_ex, const locomotor_msgs::ResultCode& result,
154 {
155  result_ex.addCallback(std::bind(cb, result));
156 }
157 
160 {
161  ros::WallTime start_t = ros::WallTime::now();
162  try
163  {
164  {
165  boost::unique_lock<boost::recursive_mutex> lock(*(costmap.getMutex()));
166  costmap.update();
167  }
168  if (cb) result_ex.addCallback(std::bind(cb, getTimeDiffFromNow(start_t)));
169  }
170  catch (const nav_core2::CostmapException& e)
171  {
172  if (fail_cb)
173  result_ex.addCallback(std::bind(fail_cb, std::current_exception(), getTimeDiffFromNow(start_t)));
174  }
175 }
176 
178 {
179  ros::WallTime start_t = ros::WallTime::now();
180  try
181  {
182  state_.global_pose = getGlobalRobotPose();
183 
184  {
185  boost::unique_lock<boost::recursive_mutex> lock(*(global_costmap_->getMutex()));
186  state_.global_plan = global_planner_mux_.getCurrentPlugin().makePlan(state_.global_pose, state_.goal);
187  }
188  if (cb) result_ex.addCallback(std::bind(cb, state_.global_plan, getTimeDiffFromNow(start_t)));
189  }
190  // if we didn't get a plan and we are in the planning state (the robot isn't moving)
191  catch (const nav_core2::PlannerException& e)
192  {
193  if (fail_cb)
194  result_ex.addCallback(std::bind(fail_cb, std::current_exception(), getTimeDiffFromNow(start_t)));
195  }
196 }
197 
199  NavigationCompleteCallback complete_cb)
200 {
201  state_.global_pose = getGlobalRobotPose();
202  state_.local_pose = getLocalRobotPose();
203  state_.current_velocity = odom_sub_->getTwistStamped();
204  auto& local_planner = local_planner_mux_.getCurrentPlugin();
205 
206  if (local_planner.isGoalReached(state_.local_pose, state_.current_velocity.velocity))
207  {
208  if (complete_cb) result_ex.addCallback(std::bind(complete_cb));
209  return;
210  }
211 
212  // Actual Control
213  // Extra Scope for Mutex
214  {
215  boost::unique_lock<boost::recursive_mutex> lock(*(local_costmap_->getMutex()));
216  ros::WallTime start_t = ros::WallTime::now();
217  try
218  {
219  state_.command_velocity = local_planner.computeVelocityCommands(state_.local_pose,
220  state_.current_velocity.velocity);
221  lock.unlock();
222  if (cb) result_ex.addCallback(std::bind(cb, state_.command_velocity, getTimeDiffFromNow(start_t)));
223  }
224  catch (const nav_core2::PlannerException& e)
225  {
226  lock.unlock();
227  if (fail_cb)
228  result_ex.addCallback(std::bind(fail_cb, std::current_exception(), getTimeDiffFromNow(start_t)));
229  }
230  }
231 }
232 
233 nav_2d_msgs::Pose2DStamped Locomotor::getRobotPose(const std::string& target_frame) const
234 {
235  nav_2d_msgs::Pose2DStamped robot_pose, transformed_pose;
236  robot_pose.header.frame_id = robot_base_frame_;
237  if (!use_latest_pose_)
238  {
239  robot_pose.header.stamp = ros::Time::now();
240  }
241  bool ret = nav_2d_utils::transformPose(tf_, target_frame, robot_pose, transformed_pose);
242  if (!ret)
243  {
244  throw nav_core2::PlannerTFException("Could not get pose into costmap frame!");
245  }
246  return transformed_pose;
247 }
248 
249 } // namespace locomotor
nav_2d_utils::PluginMux< nav_core2::LocalPlanner > local_planner_mux_
Definition: locomotor.h:219
nav_2d_msgs::Pose2DStamped getLocalRobotPose() const
Definition: locomotor.h:186
nav_2d_msgs::Pose2DStamped getRobotPose(const std::string &target_frame) const
Definition: locomotor.cpp:233
ros::Duration getTimeDiffFromNow(const ros::WallTime &start_time)
Definition: locomotor.cpp:43
std::function< void(const nav_2d_msgs::Path2D &, const ros::Duration &)> GlobalPlanCallback
Definition: locomotor.h:60
#define ROS_INFO_NAMED(name,...)
pluginlib::ClassLoader< nav_core2::Costmap > costmap_loader_
Definition: locomotor.h:212
Collection of objects used in ROS CallbackQueue threading.
Definition: executor.h:72
bool transformPose(const TFListenerPtr tf, const std::string frame, const geometry_msgs::PoseStamped &in_pose, geometry_msgs::PoseStamped &out_pose, const bool extrapolation_fallback=true)
TFListenerPtr tf_
Definition: locomotor.h:224
nav_core2::Costmap::Ptr global_costmap_
Definition: locomotor.h:216
std::function< void(const locomotor_msgs::ResultCode)> NavigationFailureCallback
Definition: locomotor.h:64
void requestLocalCostmapUpdate(Executor &work_ex, Executor &result_ex, CostmapUpdateCallback cb=nullptr, CostmapUpdateExceptionCallback fail_cb=nullptr)
Request the local costmap get updated as a new callback.
Definition: locomotor.cpp:132
std::function< void(nav_core2::NavCore2ExceptionPtr, const ros::Duration &)> CostmapUpdateExceptionCallback
Definition: locomotor.h:59
void initializeGlobalPlanners(Executor &ex)
Definition: locomotor.cpp:93
ros::NodeHandle private_nh_
Definition: locomotor.h:229
virtual void setGoal(nav_2d_msgs::Pose2DStamped goal)
Starts a new navigation to the given goal.
Definition: locomotor.cpp:111
std::function< void(nav_core2::NavCore2ExceptionPtr, const ros::Duration &)> PlannerExceptionCallback
Definition: locomotor.h:62
T & getPlugin(const std::string &name)
locomotor_msgs::NavigationState state_
Definition: locomotor.h:230
nav_2d_msgs::Pose2DStamped getGlobalRobotPose() const
Definition: locomotor.h:185
std::function< void(const ros::Duration &)> CostmapUpdateCallback
Definition: locomotor.h:58
bool param(const std::string &param_name, T &param_val, const T &default_val) const
std::string robot_base_frame_
Definition: locomotor.h:231
void initializeLocalCostmap(Executor &ex)
Definition: locomotor.cpp:83
nav_2d_utils::PluginMux< nav_core2::GlobalPlanner > global_planner_mux_
Definition: locomotor.h:215
void initializeGlobalCostmap(Executor &ex)
Definition: locomotor.cpp:73
virtual void switchLocalPlannerCallback(const std::string &old_planner, const std::string &new_planner)
Callback for when the local planner switches to ensure the new planner has up to date information...
Definition: locomotor.cpp:118
void doCostmapUpdate(nav_core2::Costmap &costmap, Executor &result_ex, CostmapUpdateCallback cb, CostmapUpdateExceptionCallback fail_cb)
Definition: locomotor.cpp:158
void initializeLocalPlanners(Executor &ex)
Definition: locomotor.cpp:102
void requestNavigationFailure(Executor &result_ex, const locomotor_msgs::ResultCode &result, NavigationFailureCallback cb=nullptr)
Request that a onNavigationFailure event be added as a new callback.
Definition: locomotor.cpp:152
Locomotor(const ros::NodeHandle &private_nh)
Base Constructor.
Definition: locomotor.cpp:49
void setSwitchCallback(SwitchCallback switch_callback)
static WallTime now()
nav_core2::Costmap::Ptr local_costmap_
Definition: locomotor.h:220
static Time now()
std::function< void()> NavigationCompleteCallback
Definition: locomotor.h:63
void addCallback(LocomotorCallback::Function f)
Add a callback to this executor&#39;s CallbackQueue.
Definition: executor.cpp:65
void makeLocalPlan(Executor &result_ex, LocalPlanCallback cb, PlannerExceptionCallback fail_cb, NavigationCompleteCallback complete_cb)
Definition: locomotor.cpp:198
virtual const ros::NodeHandle & getNodeHandle() const
Gets NodeHandle coupled with this executor&#39;s CallbackQueue.
Definition: executor.cpp:60
void makeGlobalPlan(Executor &result_ex, GlobalPlanCallback cb, PlannerExceptionCallback fail_cb)
Definition: locomotor.cpp:177
void requestGlobalCostmapUpdate(Executor &work_ex, Executor &result_ex, CostmapUpdateCallback cb=nullptr, CostmapUpdateExceptionCallback fail_cb=nullptr)
Request the global costmap get updated as a new callback.
Definition: locomotor.cpp:125
virtual void update()
virtual mutex_t * getMutex()=0
std::function< void(const nav_2d_msgs::Twist2DStamped &, const ros::Duration &)> LocalPlanCallback
Definition: locomotor.h:61
void requestGlobalPlan(Executor &work_ex, Executor &result_ex, GlobalPlanCallback cb=nullptr, PlannerExceptionCallback fail_cb=nullptr)
Request the global planner get run as a new callback.
Definition: locomotor.cpp:139
std::vector< std::string > getPluginNames() const
std::shared_ptr< nav_2d_utils::OdomSubscriber > odom_sub_
Definition: locomotor.h:226
void requestLocalPlan(Executor &work_ex, Executor &result_ex, LocalPlanCallback cb=nullptr, PlannerExceptionCallback fail_cb=nullptr, NavigationCompleteCallback complete_cb=nullptr)
Request the local planner get run as a new callback.
Definition: locomotor.cpp:145


locomotor
Author(s):
autogenerated on Sun Jan 10 2021 04:08:39