Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
locomotor::DoubleThreadLocomotor Class Reference

Connect the callbacks in Locomotor to do global and local planning on two separate timers. More...

Public Member Functions

 DoubleThreadLocomotor (const ros::NodeHandle &private_nh)
 
void setGoal (nav_2d_msgs::Pose2DStamped goal)
 

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 planLoopCallback (const ros::TimerEvent &event)
 
void requestGlobalCostmapUpdate ()
 
void requestNavigationFailure (const locomotor_msgs::ResultCode &result)
 

Protected Attributes

LocomotorActionServer as_
 
ros::Timer control_loop_timer_
 
double controller_frequency_ { 20.0 }
 
ros::Duration desired_control_duration_
 
ros::Duration desired_plan_duration_
 
Executor global_planning_ex_
 
Executor local_planning_ex_
 
Locomotor locomotor_
 
ros::Timer plan_loop_timer_
 
double planner_frequency_ { 10.0 }
 
ros::NodeHandle private_nh_
 

Detailed Description

Connect the callbacks in Locomotor to do global and local planning on two separate timers.

Uses two Executors, local_planning_ex_ and global_planning_ex_

When a new goal is recieved, it starts a timer to update the global costmap on the global_planning_ex. When the global costmap update finishes, it requests a global plan on the global_planning_ex. When the first global plan is generated, it starts a timer to update the local costmap on the local_planning_ex. When the local costmap update finishes, it requests a local plan on the local_planning_ex. When the goal is reached, it stops both the timers.

Definition at line 55 of file double_thread_locomotor.cpp.

Constructor & Destructor Documentation

locomotor::DoubleThreadLocomotor::DoubleThreadLocomotor ( const ros::NodeHandle private_nh)
inlineexplicit

Definition at line 58 of file double_thread_locomotor.cpp.

Member Function Documentation

void locomotor::DoubleThreadLocomotor::controlLoopCallback ( const ros::TimerEvent event)
inlineprotected

Definition at line 140 of file double_thread_locomotor.cpp.

void locomotor::DoubleThreadLocomotor::onGlobalCostmapException ( nav_core2::NavCore2ExceptionPtr  e_ptr,
const ros::Duration planning_time 
)
inlineprotected

Definition at line 112 of file double_thread_locomotor.cpp.

void locomotor::DoubleThreadLocomotor::onGlobalCostmapUpdate ( const ros::Duration planning_time)
inlineprotected

Definition at line 104 of file double_thread_locomotor.cpp.

void locomotor::DoubleThreadLocomotor::onGlobalPlanningException ( nav_core2::NavCore2ExceptionPtr  e_ptr,
const ros::Duration planning_time 
)
inlineprotected

Definition at line 133 of file double_thread_locomotor.cpp.

void locomotor::DoubleThreadLocomotor::onLocalCostmapException ( nav_core2::NavCore2ExceptionPtr  e_ptr,
const ros::Duration planning_time 
)
inlineprotected

Definition at line 155 of file double_thread_locomotor.cpp.

void locomotor::DoubleThreadLocomotor::onLocalCostmapUpdate ( const ros::Duration planning_time)
inlineprotected

Definition at line 147 of file double_thread_locomotor.cpp.

void locomotor::DoubleThreadLocomotor::onLocalPlanningException ( nav_core2::NavCore2ExceptionPtr  e_ptr,
const ros::Duration planning_time 
)
inlineprotected

Definition at line 173 of file double_thread_locomotor.cpp.

void locomotor::DoubleThreadLocomotor::onNavigationCompleted ( )
inlineprotected

Definition at line 180 of file double_thread_locomotor.cpp.

void locomotor::DoubleThreadLocomotor::onNavigationFailure ( const locomotor_msgs::ResultCode  result)
inlineprotected

Definition at line 188 of file double_thread_locomotor.cpp.

void locomotor::DoubleThreadLocomotor::onNewGlobalPlan ( nav_2d_msgs::Path2D  new_global_plan,
const ros::Duration planning_time 
)
inlineprotected

Definition at line 118 of file double_thread_locomotor.cpp.

void locomotor::DoubleThreadLocomotor::onNewLocalPlan ( nav_2d_msgs::Twist2DStamped  new_command,
const ros::Duration planning_time 
)
inlineprotected

Definition at line 161 of file double_thread_locomotor.cpp.

void locomotor::DoubleThreadLocomotor::planLoopCallback ( const ros::TimerEvent event)
inlineprotected

Definition at line 85 of file double_thread_locomotor.cpp.

void locomotor::DoubleThreadLocomotor::requestGlobalCostmapUpdate ( )
inlineprotected

Definition at line 90 of file double_thread_locomotor.cpp.

void locomotor::DoubleThreadLocomotor::requestNavigationFailure ( const locomotor_msgs::ResultCode &  result)
inlineprotected

Definition at line 97 of file double_thread_locomotor.cpp.

void locomotor::DoubleThreadLocomotor::setGoal ( nav_2d_msgs::Pose2DStamped  goal)
inline

Definition at line 78 of file double_thread_locomotor.cpp.

Member Data Documentation

LocomotorActionServer locomotor::DoubleThreadLocomotor::as_
protected

Definition at line 208 of file double_thread_locomotor.cpp.

ros::Timer locomotor::DoubleThreadLocomotor::control_loop_timer_
protected

Definition at line 202 of file double_thread_locomotor.cpp.

double locomotor::DoubleThreadLocomotor::controller_frequency_ { 20.0 }
protected

Definition at line 200 of file double_thread_locomotor.cpp.

ros::Duration locomotor::DoubleThreadLocomotor::desired_control_duration_
protected

Definition at line 201 of file double_thread_locomotor.cpp.

ros::Duration locomotor::DoubleThreadLocomotor::desired_plan_duration_
protected

Definition at line 201 of file double_thread_locomotor.cpp.

Executor locomotor::DoubleThreadLocomotor::global_planning_ex_
protected

Definition at line 205 of file double_thread_locomotor.cpp.

Executor locomotor::DoubleThreadLocomotor::local_planning_ex_
protected

Definition at line 205 of file double_thread_locomotor.cpp.

Locomotor locomotor::DoubleThreadLocomotor::locomotor_
protected

Definition at line 197 of file double_thread_locomotor.cpp.

ros::Timer locomotor::DoubleThreadLocomotor::plan_loop_timer_
protected

Definition at line 202 of file double_thread_locomotor.cpp.

double locomotor::DoubleThreadLocomotor::planner_frequency_ { 10.0 }
protected

Definition at line 200 of file double_thread_locomotor.cpp.

ros::NodeHandle locomotor::DoubleThreadLocomotor::private_nh_
protected

Definition at line 195 of file double_thread_locomotor.cpp.


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


locomotor
Author(s):
autogenerated on Sun Jan 10 2021 04:08:39