Go to the documentation of this file.
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.");
void updateRequest(const ros::Time &time, const ros::Duration &period)
Calls update only if this controller is 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 unless this controller is just constructed.
ControllerState state_
The current execution state of the controller.
std::vector< hardware_interface::InterfaceResources > ClaimedResources
virtual void starting(const ros::Time &)
This is called from within the realtime thread just before the first call to update.
bool isInitialized() const
Check if the controller is initialized.
Abstract Controller Interface.
ControllerBase & operator=(const ControllerBase &)=delete
virtual void waiting(const ros::Time &)
This is called from within the realtime thread while the controller is waiting to start.
bool abortRequest(const ros::Time &time)
Calls abort unless this controller is just constructed.
bool startRequest(const ros::Time &time)
Calls starting unless this controller is just constructed.
bool isRunning() const
Check if the controller is running.
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.
bool isStopped() const
Check if the controller is stopped.
bool waitRequest(const ros::Time &time)
Calls waiting unless this controller is just constructed.
std::shared_ptr< ControllerBase > ControllerBaseSharedPtr
virtual void aborting(const ros::Time &)
This is called from within the realtime thread when the controller needs to be aborted.
virtual ~ControllerBase()=default
bool isWaiting() const
Check if the controller is waiting.
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 ...