48 #include <controller_interface/controller.h> 69 virtual void update(
void) = 0;
90 template<
class ControllerType>
bool getController(
const std::string& name,
int sched, ControllerType*& c)
93 ROS_ERROR(
"No valid pointer to a controller provider exists");
97 ROS_ERROR(
"Could not find controller %s", name.c_str());
101 else if (sched == AFTER_ME)
after_list_.push_back(name);
103 ROS_ERROR(
"No valid scheduling specified. Need BEFORE_ME or AFTER_ME in getController function");
bool getController(const std::string &name, int sched, ControllerType *&c)
Method to get access to another controller by name and type.
virtual void stopping()
The stopping method is called by the realtime thread just after the last update call.
void stopping(const ros::Time &time)
virtual void starting()
The starting method is called just before the first update from within the realtime thread...
enum pr2_controller_interface::Controller::@1 state_
virtual void update(void)=0
The update method is called periodically by the realtime thread when the controller is running...
ControllerProvider * contr_prov_
Controller & operator=(const Controller &c)
virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)=0
The init function is called to initialize the controller from a non-realtime thread.
bool isRunning()
Check if the controller is running.
bool getControllerByName(const std::string &name, ControllerType *&c)
std::vector< std::string > before_list_
void update(const ros::Time &time, const ros::Duration &period)
void starting(const ros::Time &time)
std::vector< std::string > after_list_
bool initRequest(ControllerProvider *cp, pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)