an extensible path planning coordination engine More...
#include <locomotor.h>
Public Member Functions | |
| nav_core2::GlobalPlanner & | getCurrentGlobalPlanner () |
| std::string | getCurrentGlobalPlannerName () const |
| nav_core2::LocalPlanner & | getCurrentLocalPlanner () |
| std::string | getCurrentLocalPlannerName () const |
| nav_core2::Costmap::Ptr | getGlobalCostmap () const |
| std::vector< std::string > | getGlobalPlannerNames () const |
| nav_2d_msgs::Pose2DStamped | getGlobalRobotPose () const |
| nav_core2::Costmap::Ptr | getLocalCostmap () const |
| std::vector< std::string > | getLocalPlannerNames () const |
| nav_2d_msgs::Pose2DStamped | getLocalRobotPose () const |
| const locomotor_msgs::NavigationState & | getNavigationState () const |
| TFListenerPtr | getTFListener () const |
| void | initializeGlobalCostmap (Executor &ex) |
| void | initializeGlobalPlanners (Executor &ex) |
| void | initializeLocalCostmap (Executor &ex) |
| void | initializeLocalPlanners (Executor &ex) |
| Locomotor (const ros::NodeHandle &private_nh) | |
| Base Constructor. More... | |
| void | publishPath (const nav_2d_msgs::Path2D &global_plan) |
| void | publishTwist (const nav_2d_msgs::Twist2DStamped &command) |
| 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. More... | |
| 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. More... | |
| 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. More... | |
| 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. More... | |
| void | requestNavigationFailure (Executor &result_ex, const locomotor_msgs::ResultCode &result, NavigationFailureCallback cb=nullptr) |
| Request that a onNavigationFailure event be added as a new callback. More... | |
| virtual void | setGoal (nav_2d_msgs::Pose2DStamped goal) |
| Starts a new navigation to the given goal. More... | |
| bool | useGlobalPlanner (const std::string &name) |
| bool | useLocalPlanner (const std::string &name) |
Protected Member Functions | |
| void | doCostmapUpdate (nav_core2::Costmap &costmap, Executor &result_ex, CostmapUpdateCallback cb, CostmapUpdateExceptionCallback fail_cb) |
| nav_2d_msgs::Pose2DStamped | getRobotPose (const std::string &target_frame) const |
| void | makeGlobalPlan (Executor &result_ex, GlobalPlanCallback cb, PlannerExceptionCallback fail_cb) |
| void | makeLocalPlan (Executor &result_ex, LocalPlanCallback cb, PlannerExceptionCallback fail_cb, NavigationCompleteCallback complete_cb) |
| 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. More... | |
Protected Attributes | |
| pluginlib::ClassLoader< nav_core2::Costmap > | costmap_loader_ |
| nav_core2::Costmap::Ptr | global_costmap_ |
| nav_2d_utils::PluginMux< nav_core2::GlobalPlanner > | global_planner_mux_ |
| nav_core2::Costmap::Ptr | local_costmap_ |
| nav_2d_utils::PluginMux< nav_core2::LocalPlanner > | local_planner_mux_ |
| std::shared_ptr< nav_2d_utils::OdomSubscriber > | odom_sub_ |
| PathPublisher | path_pub_ |
| ros::NodeHandle | private_nh_ |
| std::string | robot_base_frame_ |
| locomotor_msgs::NavigationState | state_ |
| std::shared_ptr< tf2_ros::TransformListener > | tf2_listener_ |
| TFListenerPtr | tf_ |
| TwistPublisher | twist_pub_ |
| bool | use_latest_pose_ |
an extensible path planning coordination engine
Definition at line 81 of file locomotor.h.
|
explicit |
Base Constructor.
Definition at line 49 of file locomotor.cpp.
|
inline |
Definition at line 172 of file locomotor.h.
|
inline |
Definition at line 171 of file locomotor.h.
|
inline |
Definition at line 177 of file locomotor.h.
|
inline |
Definition at line 176 of file locomotor.h.
|
inline |
Definition at line 181 of file locomotor.h.
|
inline |
Definition at line 170 of file locomotor.h.
|
inline |
Definition at line 186 of file locomotor.h.
|
inline |
Definition at line 182 of file locomotor.h.
|
inline |
Definition at line 175 of file locomotor.h.
|
inline |
Definition at line 187 of file locomotor.h.
|
inline |
Definition at line 167 of file locomotor.h.
|
protected |
Definition at line 234 of file locomotor.cpp.
|
inline |
Definition at line 185 of file locomotor.h.
|
inline |
Definition at line 190 of file locomotor.h.
|
inline |
Definition at line 191 of file locomotor.h.
|
virtual |
Starts a new navigation to the given goal.
| goal | The goal to navigate to |
Definition at line 112 of file locomotor.cpp.
|
protectedvirtual |
Callback for when the local planner switches to ensure the new planner has up to date information.
| old_planner | Name used on local_planner_mux of the old planner |
| new_planner | Name used on local_planner_mux of the new planner |
Definition at line 119 of file locomotor.cpp.
|
inline |
Definition at line 173 of file locomotor.h.
|
inline |
Definition at line 178 of file locomotor.h.
|
protected |
Definition at line 213 of file locomotor.h.
|
protected |
Definition at line 217 of file locomotor.h.
|
protected |
Definition at line 216 of file locomotor.h.
|
protected |
Definition at line 221 of file locomotor.h.
|
protected |
Definition at line 220 of file locomotor.h.
|
protected |
Definition at line 228 of file locomotor.h.
|
protected |
Definition at line 236 of file locomotor.h.
|
protected |
Definition at line 231 of file locomotor.h.
|
protected |
Definition at line 233 of file locomotor.h.
|
protected |
Definition at line 232 of file locomotor.h.
|
protected |
Definition at line 226 of file locomotor.h.
|
protected |
Definition at line 225 of file locomotor.h.
|
protected |
Definition at line 237 of file locomotor.h.
|
protected |
Definition at line 227 of file locomotor.h.