Connect the callbacks in Locomotor to do global planning once and then local planning on a timer. More...
Public Member Functions | |
void | setGoal (nav_2d_msgs::Pose2DStamped goal) |
SingleThreadLocomotor (const ros::NodeHandle &private_nh) | |
Protected Member Functions | |
void | controlLoopCallback (const ros::TimerEvent &event) |
void | onGlobalCostmapException (nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration &planning_time) |
void | onGlobalCostmapUpdate (const ros::Duration &planning_time) |
void | onGlobalPlanningException (nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration &planning_time) |
void | onLocalCostmapException (nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration &planning_time) |
void | onLocalCostmapUpdate (const ros::Duration &planning_time) |
void | onLocalPlanningException (nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration &planning_time) |
void | onNavigationCompleted () |
void | onNavigationFailure (const locomotor_msgs::ResultCode result) |
void | onNewGlobalPlan (nav_2d_msgs::Path2D new_global_plan, const ros::Duration &planning_time) |
void | onNewLocalPlan (nav_2d_msgs::Twist2DStamped new_command, const ros::Duration &planning_time) |
void | requestGlobalCostmapUpdate () |
void | requestNavigationFailure (const locomotor_msgs::ResultCode &result) |
Protected Attributes | |
LocomotorActionServer | as_ |
ros::Timer | control_loop_timer_ |
ros::Duration | desired_control_duration_ |
Locomotor | locomotor_ |
Executor | main_ex_ |
ros::NodeHandle | private_nh_ |
Connect the callbacks in Locomotor to do global planning once and then local planning on a timer.
When a new goal is recieved, it triggers a global costmap update When that finishes, it requests a global plan. When that finishes, it starts a timer to update the local costmap. When the local costmap update finishes, it requests a local plan. When the goal is reached, it stops the timer.
Definition at line 53 of file single_thread_locomotor.cpp.
locomotor::SingleThreadLocomotor::SingleThreadLocomotor | ( | const ros::NodeHandle & | private_nh | ) | [inline, explicit] |
Definition at line 56 of file single_thread_locomotor.cpp.
void locomotor::SingleThreadLocomotor::controlLoopCallback | ( | const ros::TimerEvent & | event | ) | [inline, protected] |
Definition at line 122 of file single_thread_locomotor.cpp.
void locomotor::SingleThreadLocomotor::onGlobalCostmapException | ( | nav_core2::NavCore2ExceptionPtr | e_ptr, |
const ros::Duration & | planning_time | ||
) | [inline, protected] |
Definition at line 101 of file single_thread_locomotor.cpp.
void locomotor::SingleThreadLocomotor::onGlobalCostmapUpdate | ( | const ros::Duration & | planning_time | ) | [inline, protected] |
Definition at line 94 of file single_thread_locomotor.cpp.
void locomotor::SingleThreadLocomotor::onGlobalPlanningException | ( | nav_core2::NavCore2ExceptionPtr | e_ptr, |
const ros::Duration & | planning_time | ||
) | [inline, protected] |
Definition at line 115 of file single_thread_locomotor.cpp.
void locomotor::SingleThreadLocomotor::onLocalCostmapException | ( | nav_core2::NavCore2ExceptionPtr | e_ptr, |
const ros::Duration & | planning_time | ||
) | [inline, protected] |
Definition at line 137 of file single_thread_locomotor.cpp.
void locomotor::SingleThreadLocomotor::onLocalCostmapUpdate | ( | const ros::Duration & | planning_time | ) | [inline, protected] |
Definition at line 129 of file single_thread_locomotor.cpp.
void locomotor::SingleThreadLocomotor::onLocalPlanningException | ( | nav_core2::NavCore2ExceptionPtr | e_ptr, |
const ros::Duration & | planning_time | ||
) | [inline, protected] |
Definition at line 155 of file single_thread_locomotor.cpp.
void locomotor::SingleThreadLocomotor::onNavigationCompleted | ( | ) | [inline, protected] |
Definition at line 162 of file single_thread_locomotor.cpp.
void locomotor::SingleThreadLocomotor::onNavigationFailure | ( | const locomotor_msgs::ResultCode | result | ) | [inline, protected] |
Definition at line 169 of file single_thread_locomotor.cpp.
void locomotor::SingleThreadLocomotor::onNewGlobalPlan | ( | nav_2d_msgs::Path2D | new_global_plan, |
const ros::Duration & | planning_time | ||
) | [inline, protected] |
Definition at line 107 of file single_thread_locomotor.cpp.
void locomotor::SingleThreadLocomotor::onNewLocalPlan | ( | nav_2d_msgs::Twist2DStamped | new_command, |
const ros::Duration & | planning_time | ||
) | [inline, protected] |
Definition at line 143 of file single_thread_locomotor.cpp.
void locomotor::SingleThreadLocomotor::requestGlobalCostmapUpdate | ( | ) | [inline, protected] |
Definition at line 80 of file single_thread_locomotor.cpp.
void locomotor::SingleThreadLocomotor::requestNavigationFailure | ( | const locomotor_msgs::ResultCode & | result | ) | [inline, protected] |
Definition at line 87 of file single_thread_locomotor.cpp.
void locomotor::SingleThreadLocomotor::setGoal | ( | nav_2d_msgs::Pose2DStamped | goal | ) | [inline] |
Definition at line 71 of file single_thread_locomotor.cpp.
Definition at line 188 of file single_thread_locomotor.cpp.
Definition at line 182 of file single_thread_locomotor.cpp.
Definition at line 180 of file single_thread_locomotor.cpp.
Definition at line 177 of file single_thread_locomotor.cpp.
Executor locomotor::SingleThreadLocomotor::main_ex_ [protected] |
Definition at line 185 of file single_thread_locomotor.cpp.
Definition at line 175 of file single_thread_locomotor.cpp.