Public Member Functions | Protected Member Functions | Protected Attributes
locomove_base::LocoMoveBase Class Reference

#include <locomove_base.h>

List of all members.

Public Member Functions

 LocoMoveBase (const ros::NodeHandle &nh)
void resetState ()
void setGoal (nav_2d_msgs::Pose2DStamped goal)

Protected Member Functions

void controlLoopCallback (const ros::TimerEvent &event)
void executeCB ()
costmap_2d::Costmap2DROSgetCostmapPointer (const nav_core2::Costmap::Ptr &costmap)
void goalCB (const geometry_msgs::PoseStamped::ConstPtr &goal)
void loadDefaultRecoveryBehaviors ()
 Loads the default recovery behaviors for the navigation stack.
bool loadRecoveryBehaviors (ros::NodeHandle node)
 Load the recovery behaviors for the navigation stack from the parameter server.
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 planLoopCallback (const ros::TimerEvent &event)
void publishZeroVelocity ()
void recovery ()
void requestGlobalCostmapUpdate ()
void requestNavigationFailure (const locomotor_msgs::ResultCode &result)

Protected Attributes

ros::Timer control_loop_timer_
costmap_2d::Costmap2DROScontroller_costmap_ros_
ros::Duration desired_control_duration_
ros::Duration desired_plan_duration_
locomotor::Executor global_planning_ex_
ros::Publisher goal_pub_
ros::Subscriber goal_sub_
bool has_global_plan_
ros::Time last_oscillation_reset_
ros::Time last_valid_control_
ros::Time last_valid_plan_
locomotor::Executor local_planning_ex_
locomotor::Locomotor locomotor_
geometry_msgs::Pose2D oscillation_pose_
ros::Timer plan_loop_timer_
costmap_2d::Costmap2DROSplanner_costmap_ros_
 planning_retries_
ros::NodeHandle private_nh_
std::vector< boost::shared_ptr
< nav_core::RecoveryBehavior > > 
recovery_behaviors_
unsigned int recovery_index_
pluginlib::ClassLoader
< nav_core::RecoveryBehavior
recovery_loader_
RecoveryTrigger recovery_trigger_
actionlib::SimpleActionServer
< move_base_msgs::MoveBaseAction > 
server_

Detailed Description

Definition at line 52 of file locomove_base.h.


Constructor & Destructor Documentation

Definition at line 153 of file locomove_base.cpp.


Member Function Documentation

Definition at line 332 of file locomove_base.cpp.

Definition at line 625 of file locomove_base.cpp.

costmap_2d::Costmap2DROS * locomove_base::LocoMoveBase::getCostmapPointer ( const nav_core2::Costmap::Ptr &  costmap) [protected]

Definition at line 226 of file locomove_base.cpp.

void locomove_base::LocoMoveBase::goalCB ( const geometry_msgs::PoseStamped::ConstPtr &  goal) [protected]

Definition at line 620 of file locomove_base.cpp.

Loads the default recovery behaviors for the navigation stack.

Definition at line 573 of file locomove_base.cpp.

Load the recovery behaviors for the navigation stack from the parameter server.

Parameters:
nodeThe ros::NodeHandle to be used for loading parameters
Returns:
True if the recovery behaviors were loaded successfully, false otherwise

Definition at line 488 of file locomove_base.cpp.

void locomove_base::LocoMoveBase::onGlobalCostmapException ( nav_core2::NavCore2ExceptionPtr  e_ptr,
const ros::Duration planning_time 
) [protected]

Definition at line 284 of file locomove_base.cpp.

void locomove_base::LocoMoveBase::onGlobalCostmapUpdate ( const ros::Duration planning_time) [protected]

Definition at line 276 of file locomove_base.cpp.

void locomove_base::LocoMoveBase::onGlobalPlanningException ( nav_core2::NavCore2ExceptionPtr  e_ptr,
const ros::Duration planning_time 
) [protected]

Definition at line 314 of file locomove_base.cpp.

void locomove_base::LocoMoveBase::onLocalCostmapException ( nav_core2::NavCore2ExceptionPtr  e_ptr,
const ros::Duration planning_time 
) [protected]

Definition at line 355 of file locomove_base.cpp.

void locomove_base::LocoMoveBase::onLocalCostmapUpdate ( const ros::Duration planning_time) [protected]

Definition at line 339 of file locomove_base.cpp.

void locomove_base::LocoMoveBase::onLocalPlanningException ( nav_core2::NavCore2ExceptionPtr  e_ptr,
const ros::Duration planning_time 
) [protected]

Definition at line 397 of file locomove_base.cpp.

Definition at line 415 of file locomove_base.cpp.

void locomove_base::LocoMoveBase::onNavigationFailure ( const locomotor_msgs::ResultCode  result) [protected]

Definition at line 426 of file locomove_base.cpp.

void locomove_base::LocoMoveBase::onNewGlobalPlan ( nav_2d_msgs::Path2D  new_global_plan,
const ros::Duration planning_time 
) [protected]

Definition at line 294 of file locomove_base.cpp.

void locomove_base::LocoMoveBase::onNewLocalPlan ( nav_2d_msgs::Twist2DStamped  new_command,
const ros::Duration planning_time 
) [protected]

Definition at line 362 of file locomove_base.cpp.

Definition at line 264 of file locomove_base.cpp.

Definition at line 253 of file locomove_base.cpp.

Definition at line 436 of file locomove_base.cpp.

Definition at line 269 of file locomove_base.cpp.

void locomove_base::LocoMoveBase::requestNavigationFailure ( const locomotor_msgs::ResultCode &  result) [protected]

Definition at line 258 of file locomove_base.cpp.

Definition at line 239 of file locomove_base.cpp.

void locomove_base::LocoMoveBase::setGoal ( nav_2d_msgs::Pose2DStamped  goal)

Definition at line 211 of file locomove_base.cpp.


Member Data Documentation

Definition at line 118 of file locomove_base.h.

Definition at line 138 of file locomove_base.h.

Definition at line 113 of file locomove_base.h.

Definition at line 113 of file locomove_base.h.

Definition at line 121 of file locomove_base.h.

Definition at line 141 of file locomove_base.h.

Definition at line 102 of file locomove_base.h.

Definition at line 124 of file locomove_base.h.

Definition at line 131 of file locomove_base.h.

Definition at line 125 of file locomove_base.h.

Definition at line 125 of file locomove_base.h.

Definition at line 121 of file locomove_base.h.

Definition at line 98 of file locomove_base.h.

geometry_msgs::Pose2D locomove_base::LocoMoveBase::oscillation_pose_ [protected]

Definition at line 133 of file locomove_base.h.

Definition at line 118 of file locomove_base.h.

Definition at line 137 of file locomove_base.h.

Definition at line 127 of file locomove_base.h.

Definition at line 97 of file locomove_base.h.

Definition at line 111 of file locomove_base.h.

Definition at line 112 of file locomove_base.h.

Definition at line 110 of file locomove_base.h.

Definition at line 109 of file locomove_base.h.

actionlib::SimpleActionServer<move_base_msgs::MoveBaseAction> locomove_base::LocoMoveBase::server_ [protected]

Definition at line 106 of file locomove_base.h.


The documentation for this class was generated from the following files:


locomove_base
Author(s):
autogenerated on Wed Jun 26 2019 20:09:50