locomotor.h
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 #ifndef LOCOMOTOR_LOCOMOTOR_H
36 #define LOCOMOTOR_LOCOMOTOR_H
37 
38 #include <ros/ros.h>
39 #include <locomotor/executor.h>
40 #include <locomotor/publishers.h>
41 #include <locomotor_msgs/NavigationState.h>
42 #include <locomotor_msgs/ResultCode.h>
43 #include <nav_core2/exceptions.h>
44 #include <nav_core2/costmap.h>
47 #include <pluginlib/class_loader.h>
51 #include <map>
52 #include <memory>
53 #include <string>
54 #include <vector>
55 
56 namespace locomotor
57 {
58 // Callback Type Definitions
59 using CostmapUpdateCallback = std::function<void (const ros::Duration&)>;
61 using GlobalPlanCallback = std::function<void (const nav_2d_msgs::Path2D&, const ros::Duration&)>;
62 using LocalPlanCallback = std::function<void (const nav_2d_msgs::Twist2DStamped&, const ros::Duration&)>;
64 using NavigationCompleteCallback = std::function<void ()>;
65 using NavigationFailureCallback = std::function<void (const locomotor_msgs::ResultCode)>;
66 
67 inline locomotor_msgs::ResultCode makeResultCode(int component = -1, int result_code = -1,
68  const std::string& message = "")
69 {
70  locomotor_msgs::ResultCode code;
71  code.component = component;
72  code.result_code = result_code;
73  code.message = message;
74  return code;
75 }
76 
81 class Locomotor
82 {
83 public:
87  explicit Locomotor(const ros::NodeHandle& private_nh);
88 
97  void initializeLocalPlanners(Executor& ex); // end of InitializeMethods group
99 
104  virtual void setGoal(nav_2d_msgs::Pose2DStamped goal);
105 
118  void requestGlobalCostmapUpdate(Executor& work_ex, Executor& result_ex,
119  CostmapUpdateCallback cb = nullptr,
120  CostmapUpdateExceptionCallback fail_cb = nullptr);
121 
129  void requestLocalCostmapUpdate(Executor& work_ex, Executor& result_ex,
130  CostmapUpdateCallback cb = nullptr,
131  CostmapUpdateExceptionCallback fail_cb = nullptr);
132 
140  void requestGlobalPlan(Executor& work_ex, Executor& result_ex,
141  GlobalPlanCallback cb = nullptr,
142  PlannerExceptionCallback fail_cb = nullptr);
143 
152  void requestLocalPlan(Executor& work_ex, Executor& result_ex,
153  LocalPlanCallback cb = nullptr,
154  PlannerExceptionCallback fail_cb = nullptr,
155  NavigationCompleteCallback complete_cb = nullptr);
156 
163  void requestNavigationFailure(Executor& result_ex, const locomotor_msgs::ResultCode& result,
164  NavigationFailureCallback cb = nullptr); // end of ActionRequests group
166 
167  const locomotor_msgs::NavigationState& getNavigationState() const { return state_; }
168 
169  // Global/Local Planner Access
170  std::vector<std::string> getGlobalPlannerNames() const { return global_planner_mux_.getPluginNames(); }
173  bool useGlobalPlanner(const std::string& name) { return global_planner_mux_.usePlugin(name); }
174 
175  std::vector<std::string> getLocalPlannerNames() const { return local_planner_mux_.getPluginNames(); }
178  bool useLocalPlanner(const std::string& name) { return local_planner_mux_.usePlugin(name); }
179 
180  // Costmap Access
183 
184  // Additional Convenience Access
185  TFListenerPtr getTFListener() const { return tf_; }
186  nav_2d_msgs::Pose2DStamped getGlobalRobotPose() const { return getRobotPose(global_costmap_->getFrameId()); }
187  nav_2d_msgs::Pose2DStamped getLocalRobotPose() const { return getRobotPose(local_costmap_->getFrameId()); }
188 
189  // Publisher Access
190  void publishPath(const nav_2d_msgs::Path2D& global_plan) { path_pub_.publishPath(global_plan); }
191  void publishTwist(const nav_2d_msgs::Twist2DStamped& command) { twist_pub_.publishTwist(command); }
192 
193 protected:
198  void doCostmapUpdate(nav_core2::Costmap& costmap, Executor& result_ex,
202  NavigationCompleteCallback complete_cb); // end of ActualActions group
204 
210  virtual void switchLocalPlannerCallback(const std::string& old_planner, const std::string& new_planner);
211 
212  // Costmap Loader
214 
215  // Global Planners and Costmap
218 
219  // Local Planners and Costmap
222 
223  // Tools for getting the position and velocity of the robot
224  nav_2d_msgs::Pose2DStamped getRobotPose(const std::string& target_frame) const;
226  std::shared_ptr<tf2_ros::TransformListener> tf2_listener_;
228  std::shared_ptr<nav_2d_utils::OdomSubscriber> odom_sub_;
229 
230  // Core Variables
232  locomotor_msgs::NavigationState state_;
233  std::string robot_base_frame_;
234 
235  // Publishers
238 };
239 } // namespace locomotor
240 
241 #endif // LOCOMOTOR_LOCOMOTOR_H
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
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::TwistPublisher::publishTwist
void publishTwist(const nav_2d_msgs::Twist2DStamped &command)
Definition: publishers.cpp:125
locomotor::Locomotor::getTFListener
TFListenerPtr getTFListener() const
Definition: locomotor.h:185
class_loader.h
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
nav_core2::LocalPlanner
locomotor::Executor
Collection of objects used in ROS CallbackQueue threading.
Definition: executor.h:72
locomotor::PathPublisher::publishPath
void publishPath(const nav_2d_msgs::Path2D &global_plan)
Definition: publishers.cpp:71
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
ros.h
nav_2d_utils::PluginMux::getCurrentPluginName
std::string getCurrentPluginName() const
locomotor
Definition: executor.h:43
command
ROSLIB_DECL std::string command(const std::string &cmd)
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
locomotor::Locomotor
an extensible path planning coordination engine
Definition: locomotor.h:81
locomotor::Locomotor::useLocalPlanner
bool useLocalPlanner(const std::string &name)
Definition: locomotor.h:178
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_core2::GlobalPlanner
locomotor::TwistPublisher
Definition: publishers.h:58
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::getLocalCostmap
nav_core2::Costmap::Ptr getLocalCostmap() const
Definition: locomotor.h:182
locomotor::Locomotor::local_planner_mux_
nav_2d_utils::PluginMux< nav_core2::LocalPlanner > local_planner_mux_
Definition: locomotor.h:220
nav_core2::NavCore2ExceptionPtr
std::exception_ptr NavCore2ExceptionPtr
locomotor::Locomotor::publishTwist
void publishTwist(const nav_2d_msgs::Twist2DStamped &command)
Definition: locomotor.h:191
locomotor::Locomotor::getCurrentGlobalPlannerName
std::string getCurrentGlobalPlannerName() const
Definition: locomotor.h:171
nav_2d_utils::PluginMux::getPluginNames
std::vector< std::string > getPluginNames() const
nav_2d_utils::PluginMux::usePlugin
bool usePlugin(const std::string &name)
locomotor::Locomotor::makeLocalPlan
void makeLocalPlan(Executor &result_ex, LocalPlanCallback cb, PlannerExceptionCallback fail_cb, NavigationCompleteCallback complete_cb)
Definition: locomotor.cpp:199
nav_2d_utils::PluginMux< nav_core2::GlobalPlanner >
costmap.h
locomotor::Locomotor::private_nh_
ros::NodeHandle private_nh_
Definition: locomotor.h:231
locomotor::Locomotor::useGlobalPlanner
bool useGlobalPlanner(const std::string &name)
Definition: locomotor.h:173
locomotor::Locomotor::publishPath
void publishPath(const nav_2d_msgs::Path2D &global_plan)
Definition: locomotor.h:190
locomotor::Locomotor::global_planner_mux_
nav_2d_utils::PluginMux< nav_core2::GlobalPlanner > global_planner_mux_
Definition: locomotor.h:216
locomotor::Locomotor::getGlobalPlannerNames
std::vector< std::string > getGlobalPlannerNames() const
Definition: locomotor.h:170
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
local_planner.h
locomotor::Locomotor::getCurrentGlobalPlanner
nav_core2::GlobalPlanner & getCurrentGlobalPlanner()
Definition: locomotor.h:172
publishers.h
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
pluginlib::ClassLoader< nav_core2::Costmap >
executor.h
exceptions.h
locomotor::Locomotor::getCurrentLocalPlanner
nav_core2::LocalPlanner & getCurrentLocalPlanner()
Definition: locomotor.h:177
locomotor::Locomotor::getRobotPose
nav_2d_msgs::Pose2DStamped getRobotPose(const std::string &target_frame) const
Definition: locomotor.cpp:234
transform_listener.h
nav_core2::Costmap::Ptr
std::shared_ptr< Costmap > Ptr
locomotor::Locomotor::path_pub_
PathPublisher path_pub_
Definition: locomotor.h:236
locomotor::Locomotor::twist_pub_
TwistPublisher twist_pub_
Definition: locomotor.h:237
locomotor::Locomotor::getGlobalRobotPose
nav_2d_msgs::Pose2DStamped getGlobalRobotPose() const
Definition: locomotor.h:186
locomotor::Locomotor::getGlobalCostmap
nav_core2::Costmap::Ptr getGlobalCostmap() const
Definition: locomotor.h:181
TFListenerPtr
std::shared_ptr< tf2_ros::Buffer > TFListenerPtr
locomotor::Locomotor::getCurrentLocalPlannerName
std::string getCurrentLocalPlannerName() const
Definition: locomotor.h:176
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
locomotor::CostmapUpdateCallback
std::function< void(const ros::Duration &)> CostmapUpdateCallback
Definition: locomotor.h:59
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::Locomotor::getNavigationState
const locomotor_msgs::NavigationState & getNavigationState() const
Definition: locomotor.h:167
odom_subscriber.h
plugin_mux.h
locomotor::Locomotor::tf_
TFListenerPtr tf_
Definition: locomotor.h:225
global_planner.h
locomotor::PathPublisher
Definition: publishers.h:47
locomotor::Locomotor::getLocalPlannerNames
std::vector< std::string > getLocalPlannerNames() const
Definition: locomotor.h:175
locomotor::makeResultCode
locomotor_msgs::ResultCode makeResultCode(int component=-1, int result_code=-1, const std::string &message="")
Definition: locomotor.h:67
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
locomotor::CostmapUpdateExceptionCallback
std::function< void(nav_core2::NavCore2ExceptionPtr, const ros::Duration &)> CostmapUpdateExceptionCallback
Definition: locomotor.h:60
ros::NodeHandle


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