35 #ifndef LOCOMOTOR_LOCOMOTOR_H 36 #define LOCOMOTOR_LOCOMOTOR_H 41 #include <locomotor_msgs/NavigationState.h> 42 #include <locomotor_msgs/ResultCode.h> 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&)>;
66 inline locomotor_msgs::ResultCode
makeResultCode(
int component = -1,
int result_code = -1,
67 const std::string& message =
"")
69 locomotor_msgs::ResultCode code;
70 code.component = component;
71 code.result_code = result_code;
72 code.message = message;
103 virtual void setGoal(nav_2d_msgs::Pose2DStamped
goal);
223 nav_2d_msgs::Pose2DStamped
getRobotPose(
const std::string& target_frame)
const;
226 std::shared_ptr<nav_2d_utils::OdomSubscriber>
odom_sub_;
239 #endif // LOCOMOTOR_LOCOMOTOR_H nav_2d_utils::PluginMux< nav_core2::LocalPlanner > local_planner_mux_
nav_core2::GlobalPlanner & getCurrentGlobalPlanner()
nav_2d_msgs::Pose2DStamped getLocalRobotPose() const
nav_2d_msgs::Pose2DStamped getRobotPose(const std::string &target_frame) const
void publishTwist(const nav_2d_msgs::Twist2DStamped &command)
std::function< void(const nav_2d_msgs::Path2D &, const ros::Duration &)> GlobalPlanCallback
nav_core2::LocalPlanner & getCurrentLocalPlanner()
pluginlib::ClassLoader< nav_core2::Costmap > costmap_loader_
Collection of objects used in ROS CallbackQueue threading.
std::vector< std::string > getGlobalPlannerNames() const
locomotor_msgs::ResultCode makeResultCode(int component=-1, int result_code=-1, const std::string &message="")
std::string getCurrentLocalPlannerName() const
TwistPublisher twist_pub_
nav_core2::Costmap::Ptr global_costmap_
std::function< void(const locomotor_msgs::ResultCode)> NavigationFailureCallback
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.
std::vector< std::string > getLocalPlannerNames() const
std::function< void(nav_core2::NavCore2ExceptionPtr, const ros::Duration &)> CostmapUpdateExceptionCallback
void publishPath(const nav_2d_msgs::Path2D &global_plan)
void initializeGlobalPlanners(Executor &ex)
ros::NodeHandle private_nh_
virtual void setGoal(nav_2d_msgs::Pose2DStamped goal)
Starts a new navigation to the given goal.
std::function< void(nav_core2::NavCore2ExceptionPtr, const ros::Duration &)> PlannerExceptionCallback
bool useGlobalPlanner(const std::string &name)
locomotor_msgs::NavigationState state_
void publishPath(const nav_2d_msgs::Path2D &global_plan)
bool usePlugin(const std::string &name)
nav_2d_msgs::Pose2DStamped getGlobalRobotPose() const
an extensible path planning coordination engine
std::function< void(const ros::Duration &)> CostmapUpdateCallback
std::string getCurrentPluginName() const
const locomotor_msgs::NavigationState & getNavigationState() const
std::string robot_base_frame_
void initializeLocalCostmap(Executor &ex)
nav_2d_utils::PluginMux< nav_core2::GlobalPlanner > global_planner_mux_
void initializeGlobalCostmap(Executor &ex)
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...
void doCostmapUpdate(nav_core2::Costmap &costmap, Executor &result_ex, CostmapUpdateCallback cb, CostmapUpdateExceptionCallback fail_cb)
TFListenerPtr getTFListener() const
void initializeLocalPlanners(Executor &ex)
void requestNavigationFailure(Executor &result_ex, const locomotor_msgs::ResultCode &result, NavigationFailureCallback cb=nullptr)
Request that a onNavigationFailure event be added as a new callback.
Locomotor(const ros::NodeHandle &private_nh)
Base Constructor.
bool useLocalPlanner(const std::string &name)
nav_core2::Costmap::Ptr local_costmap_
nav_core2::Costmap::Ptr getLocalCostmap() const
std::function< void()> NavigationCompleteCallback
std::shared_ptr< Costmap > Ptr
void makeLocalPlan(Executor &result_ex, LocalPlanCallback cb, PlannerExceptionCallback fail_cb, NavigationCompleteCallback complete_cb)
std::shared_ptr< tf::TransformListener > TFListenerPtr
nav_core2::Costmap::Ptr getGlobalCostmap() const
void makeGlobalPlan(Executor &result_ex, GlobalPlanCallback cb, PlannerExceptionCallback fail_cb)
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.
std::string getCurrentGlobalPlannerName() const
std::function< void(const nav_2d_msgs::Twist2DStamped &, const ros::Duration &)> LocalPlanCallback
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.
std::vector< std::string > getPluginNames() const
std::shared_ptr< nav_2d_utils::OdomSubscriber > odom_sub_
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.