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. | |
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. | |
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. | |
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. | |
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. | |
void | requestNavigationFailure (Executor &result_ex, const locomotor_msgs::ResultCode &result, NavigationFailureCallback cb=nullptr) |
Request that a onNavigationFailure event be added as a new callback. | |
virtual void | setGoal (nav_2d_msgs::Pose2DStamped goal) |
Starts a new navigation to the given goal. | |
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. | |
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_ |
TFListenerPtr | tf_ |
TwistPublisher | twist_pub_ |
bool | use_latest_pose_ |
an extensible path planning coordination engine
Definition at line 79 of file locomotor.h.
locomotor::Locomotor::Locomotor | ( | const ros::NodeHandle & | private_nh | ) | [explicit] |
Base Constructor.
Definition at line 48 of file locomotor.cpp.
Definition at line 170 of file locomotor.h.
std::string locomotor::Locomotor::getCurrentGlobalPlannerName | ( | ) | const [inline] |
Definition at line 169 of file locomotor.h.
Definition at line 175 of file locomotor.h.
std::string locomotor::Locomotor::getCurrentLocalPlannerName | ( | ) | const [inline] |
Definition at line 174 of file locomotor.h.
nav_core2::Costmap::Ptr locomotor::Locomotor::getGlobalCostmap | ( | ) | const [inline] |
Definition at line 179 of file locomotor.h.
std::vector<std::string> locomotor::Locomotor::getGlobalPlannerNames | ( | ) | const [inline] |
Definition at line 168 of file locomotor.h.
nav_2d_msgs::Pose2DStamped locomotor::Locomotor::getGlobalRobotPose | ( | ) | const [inline] |
Definition at line 184 of file locomotor.h.
nav_core2::Costmap::Ptr locomotor::Locomotor::getLocalCostmap | ( | ) | const [inline] |
Definition at line 180 of file locomotor.h.
std::vector<std::string> locomotor::Locomotor::getLocalPlannerNames | ( | ) | const [inline] |
Definition at line 173 of file locomotor.h.
nav_2d_msgs::Pose2DStamped locomotor::Locomotor::getLocalRobotPose | ( | ) | const [inline] |
Definition at line 185 of file locomotor.h.
const locomotor_msgs::NavigationState& locomotor::Locomotor::getNavigationState | ( | ) | const [inline] |
Definition at line 165 of file locomotor.h.
nav_2d_msgs::Pose2DStamped locomotor::Locomotor::getRobotPose | ( | const std::string & | target_frame | ) | const [protected] |
Definition at line 232 of file locomotor.cpp.
TFListenerPtr locomotor::Locomotor::getTFListener | ( | ) | const [inline] |
Definition at line 183 of file locomotor.h.
void locomotor::Locomotor::publishPath | ( | const nav_2d_msgs::Path2D & | global_plan | ) | [inline] |
Definition at line 188 of file locomotor.h.
void locomotor::Locomotor::publishTwist | ( | const nav_2d_msgs::Twist2DStamped & | command | ) | [inline] |
Definition at line 189 of file locomotor.h.
void locomotor::Locomotor::setGoal | ( | nav_2d_msgs::Pose2DStamped | goal | ) | [virtual] |
Starts a new navigation to the given goal.
goal | The goal to navigate to |
Definition at line 110 of file locomotor.cpp.
void locomotor::Locomotor::switchLocalPlannerCallback | ( | const std::string & | old_planner, |
const std::string & | new_planner | ||
) | [protected, virtual] |
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 117 of file locomotor.cpp.
bool locomotor::Locomotor::useGlobalPlanner | ( | const std::string & | name | ) | [inline] |
Definition at line 171 of file locomotor.h.
bool locomotor::Locomotor::useLocalPlanner | ( | const std::string & | name | ) | [inline] |
Definition at line 176 of file locomotor.h.
Definition at line 211 of file locomotor.h.
nav_core2::Costmap::Ptr locomotor::Locomotor::global_costmap_ [protected] |
Definition at line 215 of file locomotor.h.
nav_2d_utils::PluginMux<nav_core2::GlobalPlanner> locomotor::Locomotor::global_planner_mux_ [protected] |
Definition at line 214 of file locomotor.h.
nav_core2::Costmap::Ptr locomotor::Locomotor::local_costmap_ [protected] |
Definition at line 219 of file locomotor.h.
nav_2d_utils::PluginMux<nav_core2::LocalPlanner> locomotor::Locomotor::local_planner_mux_ [protected] |
Definition at line 218 of file locomotor.h.
std::shared_ptr<nav_2d_utils::OdomSubscriber> locomotor::Locomotor::odom_sub_ [protected] |
Definition at line 225 of file locomotor.h.
PathPublisher locomotor::Locomotor::path_pub_ [protected] |
Definition at line 233 of file locomotor.h.
ros::NodeHandle locomotor::Locomotor::private_nh_ [protected] |
Definition at line 228 of file locomotor.h.
std::string locomotor::Locomotor::robot_base_frame_ [protected] |
Definition at line 230 of file locomotor.h.
locomotor_msgs::NavigationState locomotor::Locomotor::state_ [protected] |
Definition at line 229 of file locomotor.h.
TFListenerPtr locomotor::Locomotor::tf_ [protected] |
Definition at line 223 of file locomotor.h.
TwistPublisher locomotor::Locomotor::twist_pub_ [protected] |
Definition at line 234 of file locomotor.h.
bool locomotor::Locomotor::use_latest_pose_ [protected] |
Definition at line 224 of file locomotor.h.