157 ROS_FATAL(
"Failed to start controller. It is not initialized.");
174 ROS_FATAL(
"Failed to stop controller. It is not initialized.");
191 ROS_FATAL(
"Failed to wait controller. It is not initialized.");
208 ROS_FATAL(
"Failed to abort controller. It is not initialized.");
239 ClaimedResources& claimed_resources) = 0;
std::shared_ptr< ControllerBase > ControllerBaseSharedPtr
bool abortRequest(const ros::Time &time)
Calls abort unless this controller is just constructed.
std::vector< hardware_interface::InterfaceResources > ClaimedResources
bool isAborted() const
Check if the controller is aborted.
virtual void stopping(const ros::Time &)
This is called from within the realtime thread just after the last update call before the controller ...
bool waitRequest(const ros::Time &time)
Calls waiting unless this controller is just constructed.
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.
ControllerBase & operator=(const ControllerBase &)=delete
void updateRequest(const ros::Time &time, const ros::Duration &period)
Calls update only if this controller is running.
bool isStopped() const
Check if the controller is stopped.
bool startRequest(const ros::Time &time)
Calls starting unless this controller is just constructed.
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 unless this controller is just constructed.
virtual ~ControllerBase()=default
bool isWaiting() const
Check if the controller is waiting.
enum controller_interface::ControllerBase::@0 state_
The current execution state of the controller.
virtual void aborting(const ros::Time &)
This is called from within the realtime thread when the controller needs to be aborted.
virtual void waiting(const ros::Time &)
This is called from within the realtime thread while the controller is waiting to start...
virtual void starting(const ros::Time &)
This is called from within the realtime thread just before the first call to update.
bool isRunning() const
Check if the controller is running.
bool isInitialized() const
Check if the controller is initialized.