33 #ifndef CONTROLLER_INTERFACE_CONTROLLER_BASE_H 34 #define CONTROLLER_INTERFACE_CONTROLLER_BASE_H 38 #include <boost/shared_ptr.hpp> 146 ClaimedResources& claimed_resources) = 0;
bool isRunning()
Check if the controller is running.
std::vector< hardware_interface::InterfaceResources > ClaimedResources
virtual void stopping(const ros::Time &)
This is called from within the realtime thread just after the last update call before the controller ...
virtual void update(const ros::Time &time, const ros::Duration &period)=0
This is called periodically by the realtime thread when the controller is running.
Abstract Controller Interface.
void updateRequest(const ros::Time &time, const ros::Duration &period)
Calls update only if this controller is running.
boost::shared_ptr< ControllerBase > ControllerBaseSharedPtr
virtual ~ControllerBase()
bool startRequest(const ros::Time &time)
Calls starting only if this controller is initialized or already running.
virtual bool initRequest(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources)=0
Request that the controller be initialized.
bool stopRequest(const ros::Time &time)
Calls stopping only if this controller is initialized or already running.
enum controller_interface::ControllerBase::@0 state_
The current execution state of the controller.
ControllerBase & operator=(const ControllerBase &c)
virtual void starting(const ros::Time &)
This is called from within the realtime thread just before the first call to update.