115 "Global Costmap failure."));
125 ROS_WARN_NAMED(
"locomotor",
"Global planning missed its desired rate of %.4fHz... " 126 "the loop actually took %.4f seconds (>%.4f).",
137 "Global Planning Failure."));
158 "Local Costmap failure."));
166 ROS_WARN_NAMED(
"locomotor",
"Control loop missed its desired rate of %.4fHz... " 167 "the loop actually took %.4f seconds (>%.4f).",
175 ROS_WARN_NAMED(
"Locomotor",
"Local planning error. Creating new global plan.");
212 int main(
int argc,
char** argv)
virtual void setPlan(const nav_2d_msgs::Path2D &path)=0
void publishTwist(const nav_2d_msgs::Twist2DStamped &command)
void failNavigation(const locomotor_msgs::ResultCode &result_code)
void onLocalPlanningException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration &planning_time)
nav_core2::LocalPlanner & getCurrentLocalPlanner()
#define ROS_INFO_NAMED(name,...)
Executor global_planning_ex_
Collection of objects used in ROS CallbackQueue threading.
void controlLoopCallback(const ros::TimerEvent &event)
#define ROS_WARN_NAMED(name,...)
ros::Timer control_loop_timer_
locomotor_msgs::ResultCode makeResultCode(int component=-1, int result_code=-1, const std::string &message="")
ros::NodeHandle private_nh_
void onNewLocalPlan(nav_2d_msgs::Twist2DStamped new_command, const ros::Duration &planning_time)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
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 onGlobalPlanningException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration &planning_time)
void initializeGlobalPlanners(Executor &ex)
LocomotorActionServer as_
virtual void setGoal(nav_2d_msgs::Pose2DStamped goal)
Starts a new navigation to the given goal.
void completeNavigation()
void requestGlobalCostmapUpdate()
std::exception_ptr NavCore2ExceptionPtr
ROSCPP_DECL void spin(Spinner &spinner)
void publishFeedback(const locomotor_msgs::NavigationState &nav_state)
double controller_frequency_
void planLoopCallback(const ros::TimerEvent &event)
void onLocalCostmapException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration &planning_time)
void publishPath(const nav_2d_msgs::Path2D &global_plan)
an extensible path planning coordination engine
void onNavigationCompleted()
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void requestNavigationFailure(const locomotor_msgs::ResultCode &result)
void onGlobalCostmapException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration &planning_time)
const locomotor_msgs::NavigationState & getNavigationState() const
DoubleThreadLocomotor(const ros::NodeHandle &private_nh)
void initializeLocalCostmap(Executor &ex)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
void initializeGlobalCostmap(Executor &ex)
void setGoal(nav_2d_msgs::Pose2DStamped goal)
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.
void onGlobalCostmapUpdate(const ros::Duration &planning_time)
ros::Duration desired_plan_duration_
int main(int argc, char **argv)
void onNewGlobalPlan(nav_2d_msgs::Path2D new_global_plan, const ros::Duration &planning_time)
double planner_frequency_
#define ROS_ERROR_NAMED(name,...)
Connect the callbacks in Locomotor to do global and local planning on two separate timers...
ros::Duration desired_control_duration_
Executor local_planning_ex_
void onLocalCostmapUpdate(const ros::Duration &planning_time)
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 onNavigationFailure(const locomotor_msgs::ResultCode result)
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.
ros::Timer plan_loop_timer_
int getResultCode(const NavCore2ExceptionPtr &e_ptr)
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.