Collection of objects used in ROS CallbackQueue threading. More...
#include <executor.h>
Public Member Functions | |
void | addCallback (LocomotorCallback::Function f) |
Add a callback to this executor's CallbackQueue. | |
Executor (const ros::NodeHandle &base_nh, bool create_cb_queue=true) | |
Constructor. Creates new CallbackQueue or uses global CallbackQueue. | |
virtual const ros::NodeHandle & | getNodeHandle () const |
Gets NodeHandle coupled with this executor's CallbackQueue. | |
virtual | ~Executor () |
Protected Member Functions | |
virtual ros::CallbackQueue & | getQueue () |
Gets the queue for this executor. | |
Protected Attributes | |
ros::NodeHandle | ex_nh_ |
std::shared_ptr < ros::CallbackQueue > | queue_ |
std::shared_ptr < ros::AsyncSpinner > | spinner_ |
Collection of objects used in ROS CallbackQueue threading.
This light wrapper around the contained classes allows for intelligent cleanup of the objects
Definition at line 71 of file executor.h.
locomotor::Executor::Executor | ( | const ros::NodeHandle & | base_nh, |
bool | create_cb_queue = true |
||
) | [explicit] |
Constructor. Creates new CallbackQueue or uses global CallbackQueue.
base_nh | Base NodeHandle that this executor's NodeHandle will be derived from |
create_cb_queue | If true, creates a new CallbackQueue. If false, uses global CallbackQueue |
Definition at line 39 of file executor.cpp.
virtual locomotor::Executor::~Executor | ( | ) | [inline, virtual] |
Definition at line 81 of file executor.h.
void locomotor::Executor::addCallback | ( | LocomotorCallback::Function | f | ) |
Add a callback to this executor's CallbackQueue.
f | LocomotorCallback |
Definition at line 64 of file executor.cpp.
const ros::NodeHandle & locomotor::Executor::getNodeHandle | ( | ) | const [virtual] |
Gets NodeHandle coupled with this executor's CallbackQueue.
Definition at line 59 of file executor.cpp.
ros::CallbackQueue & locomotor::Executor::getQueue | ( | ) | [protected, virtual] |
Gets the queue for this executor.
Definition at line 69 of file executor.cpp.
ros::NodeHandle locomotor::Executor::ex_nh_ [protected] |
Definition at line 101 of file executor.h.
std::shared_ptr<ros::CallbackQueue> locomotor::Executor::queue_ [protected] |
Definition at line 99 of file executor.h.
std::shared_ptr<ros::AsyncSpinner> locomotor::Executor::spinner_ [protected] |
Definition at line 100 of file executor.h.