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