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 <string>
39 
40 namespace locomotor
41 {
43 {
44  ros::WallDuration duration = ros::WallTime::now() - start_time;
45  return ros::Duration(duration.sec, duration.nsec);
46 }
47 
49  costmap_loader_("nav_core2", "nav_core2::Costmap"),
50  global_planner_mux_("nav_core2", "nav_core2::GlobalPlanner",
51  "global_planner_namespaces", "dlux_global_planner::DluxGlobalPlanner",
52  "current_global_planner", "switch_global_planner"),
53  local_planner_mux_("nav_core2", "nav_core2::LocalPlanner",
54  "local_planner_namespaces", "dwb_local_planner::DWBLocalPlanner",
55  "current_local_planner", "switch_local_planner"),
56  private_nh_(private_nh), path_pub_(private_nh_), twist_pub_(private_nh_)
57 {
58  tf_ = std::make_shared<tf::TransformListener>(ros::Duration(10));
59 
60  private_nh_.param("robot_base_frame", robot_base_frame_, std::string("base_link"));
61 
62  // If true, when getting robot pose, use ros::Time(0) instead of ros::Time::now()
63  private_nh_.param("use_latest_pose", use_latest_pose_, true);
64 
65  local_planner_mux_.setSwitchCallback(std::bind(&Locomotor::switchLocalPlannerCallback, this, std::placeholders::_1,
66  std::placeholders::_2));
67 
68  ros::NodeHandle global_nh;
69  odom_sub_ = std::make_shared<nav_2d_utils::OdomSubscriber>(global_nh);
70 }
71 
73 {
74  std::string costmap_class;
75  private_nh_.param("global_costmap_class", costmap_class, std::string("nav_core_adapter::CostmapAdapter"));
76  ROS_INFO_NAMED("Locomotor", "Loading Global Costmap %s", costmap_class.c_str());
77  global_costmap_ = costmap_loader_.createUniqueInstance(costmap_class);
78  ROS_INFO_NAMED("Locomotor", "Initializing Global Costmap");
79  global_costmap_->initialize(ex.getNodeHandle(), "global_costmap", tf_);
80 }
81 
83 {
84  std::string costmap_class;
85  private_nh_.param("local_costmap_class", costmap_class, std::string("nav_core_adapter::CostmapAdapter"));
86  ROS_INFO_NAMED("Locomotor", "Loading Local Costmap %s", costmap_class.c_str());
87  local_costmap_ = costmap_loader_.createUniqueInstance(costmap_class);
88  ROS_INFO_NAMED("Locomotor", "Initializing Local Costmap");
89  local_costmap_->initialize(ex.getNodeHandle(), "local_costmap", tf_);
90 }
91 
93 {
94  for (auto planner_name : global_planner_mux_.getPluginNames())
95  {
96  ROS_INFO_NAMED("Locomotor", "Initializing global planner %s", planner_name.c_str());
97  global_planner_mux_.getPlugin(planner_name).initialize(ex.getNodeHandle(), planner_name, tf_, global_costmap_);
98  }
99 }
100 
102 {
103  for (auto planner_name : local_planner_mux_.getPluginNames())
104  {
105  ROS_INFO_NAMED("Locomotor", "Initializing local planner %s", planner_name.c_str());
106  local_planner_mux_.getPlugin(planner_name).initialize(ex.getNodeHandle(), planner_name, tf_, local_costmap_);
107  }
108 }
109 
110 void Locomotor::setGoal(nav_2d_msgs::Pose2DStamped goal)
111 {
112  local_planner_mux_.getCurrentPlugin().setGoalPose(goal);
113  state_ = locomotor_msgs::NavigationState();
114  state_.goal = goal;
115 }
116 
117 void Locomotor::switchLocalPlannerCallback(const std::string&, const std::string& new_planner)
118 {
119  auto& new_local_planner = local_planner_mux_.getPlugin(new_planner);
120  new_local_planner.setGoalPose(state_.goal);
121  new_local_planner.setPlan(state_.global_plan);
122 }
123 
126 {
127  work_ex.addCallback(
128  std::bind(&Locomotor::doCostmapUpdate, this, std::ref(*global_costmap_), std::ref(result_ex), cb, fail_cb));
129 }
130 
133 {
134  work_ex.addCallback(
135  std::bind(&Locomotor::doCostmapUpdate, this, std::ref(*local_costmap_), std::ref(result_ex), cb, fail_cb));
136 }
137 
140 {
141  work_ex.addCallback(std::bind(&Locomotor::makeGlobalPlan, this, std::ref(result_ex), cb, fail_cb));
142 }
143 
146  NavigationCompleteCallback complete_cb)
147 {
148  work_ex.addCallback(std::bind(&Locomotor::makeLocalPlan, this, std::ref(result_ex), cb, fail_cb, complete_cb));
149 }
150 
151 void Locomotor::requestNavigationFailure(Executor& result_ex, const locomotor_msgs::ResultCode& result,
153 {
154  result_ex.addCallback(std::bind(cb, result));
155 }
156 
159 {
160  ros::WallTime start_t = ros::WallTime::now();
161  try
162  {
163  {
164  boost::unique_lock<boost::recursive_mutex> lock(*(costmap.getMutex()));
165  costmap.update();
166  }
167  if (cb) result_ex.addCallback(std::bind(cb, getTimeDiffFromNow(start_t)));
168  }
169  catch (const nav_core2::CostmapException& e)
170  {
171  if (fail_cb)
172  result_ex.addCallback(std::bind(fail_cb, std::current_exception(), getTimeDiffFromNow(start_t)));
173  }
174 }
175 
177 {
178  ros::WallTime start_t = ros::WallTime::now();
179  try
180  {
181  state_.global_pose = getGlobalRobotPose();
182 
183  {
184  boost::unique_lock<boost::recursive_mutex> lock(*(global_costmap_->getMutex()));
185  state_.global_plan = global_planner_mux_.getCurrentPlugin().makePlan(state_.global_pose, state_.goal);
186  }
187  if (cb) result_ex.addCallback(std::bind(cb, state_.global_plan, getTimeDiffFromNow(start_t)));
188  }
189  // if we didn't get a plan and we are in the planning state (the robot isn't moving)
190  catch (const nav_core2::PlannerException& e)
191  {
192  if (fail_cb)
193  result_ex.addCallback(std::bind(fail_cb, std::current_exception(), getTimeDiffFromNow(start_t)));
194  }
195 }
196 
198  NavigationCompleteCallback complete_cb)
199 {
200  state_.global_pose = getGlobalRobotPose();
201  state_.local_pose = getLocalRobotPose();
202  state_.current_velocity = odom_sub_->getTwistStamped();
203  auto& local_planner = local_planner_mux_.getCurrentPlugin();
204 
205  if (local_planner.isGoalReached(state_.local_pose, state_.current_velocity.velocity))
206  {
207  if (complete_cb) result_ex.addCallback(std::bind(complete_cb));
208  return;
209  }
210 
211  // Actual Control
212  // Extra Scope for Mutex
213  {
214  boost::unique_lock<boost::recursive_mutex> lock(*(local_costmap_->getMutex()));
215  ros::WallTime start_t = ros::WallTime::now();
216  try
217  {
218  state_.command_velocity = local_planner.computeVelocityCommands(state_.local_pose,
219  state_.current_velocity.velocity);
220  lock.unlock();
221  if (cb) result_ex.addCallback(std::bind(cb, state_.command_velocity, getTimeDiffFromNow(start_t)));
222  }
223  catch (const nav_core2::PlannerException& e)
224  {
225  lock.unlock();
226  if (fail_cb)
227  result_ex.addCallback(std::bind(fail_cb, std::current_exception(), getTimeDiffFromNow(start_t)));
228  }
229  }
230 }
231 
232 nav_2d_msgs::Pose2DStamped Locomotor::getRobotPose(const std::string& target_frame) const
233 {
234  nav_2d_msgs::Pose2DStamped robot_pose, transformed_pose;
235  robot_pose.header.frame_id = robot_base_frame_;
236  if (!use_latest_pose_)
237  {
238  robot_pose.header.stamp = ros::Time::now();
239  }
240  bool ret = nav_2d_utils::transformPose(tf_, target_frame, robot_pose, transformed_pose);
241  if (!ret)
242  {
243  throw nav_core2::PlannerTFException("Could not get pose into costmap frame!");
244  }
245  return transformed_pose;
246 }
247 
248 } // namespace locomotor
nav_2d_utils::PluginMux< nav_core2::LocalPlanner > local_planner_mux_
Definition: locomotor.h:218
nav_2d_msgs::Pose2DStamped getLocalRobotPose() const
Definition: locomotor.h:185
nav_2d_msgs::Pose2DStamped getRobotPose(const std::string &target_frame) const
Definition: locomotor.cpp:232
ros::Duration getTimeDiffFromNow(const ros::WallTime &start_time)
Definition: locomotor.cpp:42
std::function< void(const nav_2d_msgs::Path2D &, const ros::Duration &)> GlobalPlanCallback
Definition: locomotor.h:59
#define ROS_INFO_NAMED(name,...)
pluginlib::ClassLoader< nav_core2::Costmap > costmap_loader_
Definition: locomotor.h:211
Collection of objects used in ROS CallbackQueue threading.
Definition: executor.h:71
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:223
nav_core2::Costmap::Ptr global_costmap_
Definition: locomotor.h:215
std::function< void(const locomotor_msgs::ResultCode)> NavigationFailureCallback
Definition: locomotor.h:63
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:131
std::function< void(nav_core2::NavCore2ExceptionPtr, const ros::Duration &)> CostmapUpdateExceptionCallback
Definition: locomotor.h:58
void initializeGlobalPlanners(Executor &ex)
Definition: locomotor.cpp:92
ros::NodeHandle private_nh_
Definition: locomotor.h:228
virtual void setGoal(nav_2d_msgs::Pose2DStamped goal)
Starts a new navigation to the given goal.
Definition: locomotor.cpp:110
std::function< void(nav_core2::NavCore2ExceptionPtr, const ros::Duration &)> PlannerExceptionCallback
Definition: locomotor.h:61
T & getPlugin(const std::string &name)
locomotor_msgs::NavigationState state_
Definition: locomotor.h:229
nav_2d_msgs::Pose2DStamped getGlobalRobotPose() const
Definition: locomotor.h:184
std::function< void(const ros::Duration &)> CostmapUpdateCallback
Definition: locomotor.h:57
bool param(const std::string &param_name, T &param_val, const T &default_val) const
std::string robot_base_frame_
Definition: locomotor.h:230
void initializeLocalCostmap(Executor &ex)
Definition: locomotor.cpp:82
nav_2d_utils::PluginMux< nav_core2::GlobalPlanner > global_planner_mux_
Definition: locomotor.h:214
void initializeGlobalCostmap(Executor &ex)
Definition: locomotor.cpp:72
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:117
void doCostmapUpdate(nav_core2::Costmap &costmap, Executor &result_ex, CostmapUpdateCallback cb, CostmapUpdateExceptionCallback fail_cb)
Definition: locomotor.cpp:157
void initializeLocalPlanners(Executor &ex)
Definition: locomotor.cpp:101
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:151
Locomotor(const ros::NodeHandle &private_nh)
Base Constructor.
Definition: locomotor.cpp:48
void setSwitchCallback(SwitchCallback switch_callback)
static WallTime now()
nav_core2::Costmap::Ptr local_costmap_
Definition: locomotor.h:219
static Time now()
std::function< void()> NavigationCompleteCallback
Definition: locomotor.h:62
void addCallback(LocomotorCallback::Function f)
Add a callback to this executor&#39;s CallbackQueue.
Definition: executor.cpp:64
void makeLocalPlan(Executor &result_ex, LocalPlanCallback cb, PlannerExceptionCallback fail_cb, NavigationCompleteCallback complete_cb)
Definition: locomotor.cpp:197
virtual const ros::NodeHandle & getNodeHandle() const
Gets NodeHandle coupled with this executor&#39;s CallbackQueue.
Definition: executor.cpp:59
void makeGlobalPlan(Executor &result_ex, GlobalPlanCallback cb, PlannerExceptionCallback fail_cb)
Definition: locomotor.cpp:176
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:124
virtual void update()
virtual mutex_t * getMutex()=0
std::function< void(const nav_2d_msgs::Twist2DStamped &, const ros::Duration &)> LocalPlanCallback
Definition: locomotor.h:60
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:138
std::vector< std::string > getPluginNames() const
std::shared_ptr< nav_2d_utils::OdomSubscriber > odom_sub_
Definition: locomotor.h:225
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:144


locomotor
Author(s):
autogenerated on Wed Jun 26 2019 20:06:18