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>
50 #include <map>
51 #include <memory>
52 #include <string>
53 #include <vector>
54 
55 namespace locomotor
56 {
57 // Callback Type Definitions
58 using CostmapUpdateCallback = std::function<void (const ros::Duration&)>;
59 using CostmapUpdateExceptionCallback = std::function<void (nav_core2::NavCore2ExceptionPtr, const ros::Duration&)>;
60 using GlobalPlanCallback = std::function<void (const nav_2d_msgs::Path2D&, const ros::Duration&)>;
61 using LocalPlanCallback = std::function<void (const nav_2d_msgs::Twist2DStamped&, const ros::Duration&)>;
62 using PlannerExceptionCallback = std::function<void (nav_core2::NavCore2ExceptionPtr, const ros::Duration&)>;
63 using NavigationCompleteCallback = std::function<void ()>;
64 using NavigationFailureCallback = std::function<void (const locomotor_msgs::ResultCode)>;
65 
66 inline locomotor_msgs::ResultCode makeResultCode(int component = -1, int result_code = -1,
67  const std::string& message = "")
68 {
69  locomotor_msgs::ResultCode code;
70  code.component = component;
71  code.result_code = result_code;
72  code.message = message;
73  return code;
74 }
75 
80 class Locomotor
81 {
82 public:
86  explicit Locomotor(const ros::NodeHandle& private_nh);
87 
96  void initializeLocalPlanners(Executor& ex); // end of InitializeMethods group
98 
103  virtual void setGoal(nav_2d_msgs::Pose2DStamped goal);
104 
117  void requestGlobalCostmapUpdate(Executor& work_ex, Executor& result_ex,
118  CostmapUpdateCallback cb = nullptr,
119  CostmapUpdateExceptionCallback fail_cb = nullptr);
120 
128  void requestLocalCostmapUpdate(Executor& work_ex, Executor& result_ex,
129  CostmapUpdateCallback cb = nullptr,
130  CostmapUpdateExceptionCallback fail_cb = nullptr);
131 
139  void requestGlobalPlan(Executor& work_ex, Executor& result_ex,
140  GlobalPlanCallback cb = nullptr,
141  PlannerExceptionCallback fail_cb = nullptr);
142 
151  void requestLocalPlan(Executor& work_ex, Executor& result_ex,
152  LocalPlanCallback cb = nullptr,
153  PlannerExceptionCallback fail_cb = nullptr,
154  NavigationCompleteCallback complete_cb = nullptr);
155 
162  void requestNavigationFailure(Executor& result_ex, const locomotor_msgs::ResultCode& result,
163  NavigationFailureCallback cb = nullptr); // end of ActionRequests group
165 
166  const locomotor_msgs::NavigationState& getNavigationState() const { return state_; }
167 
168  // Global/Local Planner Access
169  std::vector<std::string> getGlobalPlannerNames() const { return global_planner_mux_.getPluginNames(); }
172  bool useGlobalPlanner(const std::string& name) { return global_planner_mux_.usePlugin(name); }
173 
174  std::vector<std::string> getLocalPlannerNames() const { return local_planner_mux_.getPluginNames(); }
177  bool useLocalPlanner(const std::string& name) { return local_planner_mux_.usePlugin(name); }
178 
179  // Costmap Access
182 
183  // Additional Convenience Access
184  TFListenerPtr getTFListener() const { return tf_; }
185  nav_2d_msgs::Pose2DStamped getGlobalRobotPose() const { return getRobotPose(global_costmap_->getFrameId()); }
186  nav_2d_msgs::Pose2DStamped getLocalRobotPose() const { return getRobotPose(local_costmap_->getFrameId()); }
187 
188  // Publisher Access
189  void publishPath(const nav_2d_msgs::Path2D& global_plan) { path_pub_.publishPath(global_plan); }
190  void publishTwist(const nav_2d_msgs::Twist2DStamped& command) { twist_pub_.publishTwist(command); }
191 
192 protected:
197  void doCostmapUpdate(nav_core2::Costmap& costmap, Executor& result_ex,
201  NavigationCompleteCallback complete_cb); // end of ActualActions group
203 
209  virtual void switchLocalPlannerCallback(const std::string& old_planner, const std::string& new_planner);
210 
211  // Costmap Loader
213 
214  // Global Planners and Costmap
217 
218  // Local Planners and Costmap
221 
222  // Tools for getting the position and velocity of the robot
223  nav_2d_msgs::Pose2DStamped getRobotPose(const std::string& target_frame) const;
226  std::shared_ptr<nav_2d_utils::OdomSubscriber> odom_sub_;
227 
228  // Core Variables
230  locomotor_msgs::NavigationState state_;
231  std::string robot_base_frame_;
232 
233  // Publishers
236 };
237 } // namespace locomotor
238 
239 #endif // LOCOMOTOR_LOCOMOTOR_H
nav_2d_utils::PluginMux< nav_core2::LocalPlanner > local_planner_mux_
Definition: locomotor.h:219
nav_core2::GlobalPlanner & getCurrentGlobalPlanner()
Definition: locomotor.h:171
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
void publishTwist(const nav_2d_msgs::Twist2DStamped &command)
Definition: locomotor.h:190
std::function< void(const nav_2d_msgs::Path2D &, const ros::Duration &)> GlobalPlanCallback
Definition: locomotor.h:60
nav_core2::LocalPlanner & getCurrentLocalPlanner()
Definition: locomotor.h:176
pluginlib::ClassLoader< nav_core2::Costmap > costmap_loader_
Definition: locomotor.h:212
Collection of objects used in ROS CallbackQueue threading.
Definition: executor.h:72
std::vector< std::string > getGlobalPlannerNames() const
Definition: locomotor.h:169
TFListenerPtr tf_
Definition: locomotor.h:224
locomotor_msgs::ResultCode makeResultCode(int component=-1, int result_code=-1, const std::string &message="")
Definition: locomotor.h:66
std::string getCurrentLocalPlannerName() const
Definition: locomotor.h:175
TwistPublisher twist_pub_
Definition: locomotor.h:235
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::vector< std::string > getLocalPlannerNames() const
Definition: locomotor.h:174
std::function< void(nav_core2::NavCore2ExceptionPtr, const ros::Duration &)> CostmapUpdateExceptionCallback
Definition: locomotor.h:59
void publishPath(const nav_2d_msgs::Path2D &global_plan)
Definition: publishers.cpp:71
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
bool useGlobalPlanner(const std::string &name)
Definition: locomotor.h:172
PathPublisher path_pub_
Definition: locomotor.h:234
locomotor_msgs::NavigationState state_
Definition: locomotor.h:230
void publishPath(const nav_2d_msgs::Path2D &global_plan)
Definition: locomotor.h:189
bool usePlugin(const std::string &name)
nav_2d_msgs::Pose2DStamped getGlobalRobotPose() const
Definition: locomotor.h:185
an extensible path planning coordination engine
Definition: locomotor.h:80
std::function< void(const ros::Duration &)> CostmapUpdateCallback
Definition: locomotor.h:58
std::string getCurrentPluginName() const
const locomotor_msgs::NavigationState & getNavigationState() const
Definition: locomotor.h:166
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
TFListenerPtr getTFListener() const
Definition: locomotor.h:184
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
bool useLocalPlanner(const std::string &name)
Definition: locomotor.h:177
nav_core2::Costmap::Ptr local_costmap_
Definition: locomotor.h:220
nav_core2::Costmap::Ptr getLocalCostmap() const
Definition: locomotor.h:181
std::function< void()> NavigationCompleteCallback
Definition: locomotor.h:63
std::shared_ptr< Costmap > Ptr
void makeLocalPlan(Executor &result_ex, LocalPlanCallback cb, PlannerExceptionCallback fail_cb, NavigationCompleteCallback complete_cb)
Definition: locomotor.cpp:198
std::shared_ptr< tf::TransformListener > TFListenerPtr
nav_core2::Costmap::Ptr getGlobalCostmap() const
Definition: locomotor.h:180
void makeGlobalPlan(Executor &result_ex, GlobalPlanCallback cb, PlannerExceptionCallback fail_cb)
Definition: locomotor.cpp:177
void publishTwist(const nav_2d_msgs::Twist2DStamped &command)
Definition: publishers.cpp:125
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
std::string getCurrentGlobalPlannerName() const
Definition: locomotor.h:170
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