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


locomotor
Author(s):
autogenerated on Sun May 18 2025 02:47:30