controller.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 #pragma once
35 /***************************************************/
43 /***************************************************/
44 
45 #include <ros/node_handle.h>
48 #include <controller_interface/controller.h>
49 
51 {
52 
53 class Controller : public controller_interface::Controller<pr2_mechanism_model::RobotState >
54 {
55 public:
57 
59  virtual ~Controller(){}
60 
61  void starting(const ros::Time& time) { starting(); }
62  void update (const ros::Time& time, const ros::Duration& period) { update(); }
63  void stopping(const ros::Time& time) { stopping(); }
64 
66  virtual void starting() {};
67 
69  virtual void update(void) = 0;
70 
72  virtual void stopping() {};
73 
87  virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) = 0;
88 
90  template<class ControllerType> bool getController(const std::string& name, int sched, ControllerType*& c)
91  {
92  if (contr_prov_ == NULL){
93  ROS_ERROR("No valid pointer to a controller provider exists");
94  return false;
95  }
96  if (!contr_prov_->getControllerByName(name, c)){
97  ROS_ERROR("Could not find controller %s", name.c_str());
98  return false;
99  }
100  if (sched == BEFORE_ME) before_list_.push_back(name);
101  else if (sched == AFTER_ME) after_list_.push_back(name);
102  else{
103  ROS_ERROR("No valid scheduling specified. Need BEFORE_ME or AFTER_ME in getController function");
104  return false;
105  }
106  return true;
107  }
108 
110  bool isRunning()
111  {
112  return (state_ == RUNNING);
113  }
114 
116  {
117  if (state_ == RUNNING)
118  update();
119  }
120 
122  {
123  // start succeeds even if the controller was already started
124  if (state_ == RUNNING || state_ == INITIALIZED){
125  starting();
126  state_ = RUNNING;
127  return true;
128  }
129  else
130  return false;
131  }
132 
133 
134  bool stopRequest()
135  {
136  // stop succeeds even if the controller was already stopped
137  if (state_ == RUNNING || state_ == INITIALIZED){
138  stopping();
140  return true;
141  }
142  else
143  return false;
144  }
145 
147  {
148  contr_prov_ = cp;
149 
150  if (state_ != CONSTRUCTED)
151  return false;
152  else
153  {
154  // initialize
155  if (!init(robot, n))
156  return false;
158 
159  return true;
160  }
161  }
162 
163 
164  std::vector<std::string> before_list_, after_list_;
165 
167 
168 private:
169  Controller(const Controller &c);
170  Controller& operator =(const Controller &c);
172 
173 };
174 
175 }
pr2_controller_interface::Controller::before_list_
std::vector< std::string > before_list_
Definition: controller.h:164
node_handle.h
pr2_controller_interface::Controller::startRequest
bool startRequest()
Definition: controller.h:121
pr2_controller_interface::Controller::update
virtual void update(void)=0
The update method is called periodically by the realtime thread when the controller is running.
pr2_controller_interface::Controller::AFTER_ME
@ AFTER_ME
Definition: controller.h:56
pr2_controller_interface::Controller::Controller
Controller()
Definition: controller.h:58
pr2_controller_interface::Controller::updateRequest
void updateRequest()
Definition: controller.h:115
pr2_controller_interface::Controller::isRunning
bool isRunning()
Check if the controller is running.
Definition: controller.h:110
pr2_controller_interface::Controller::CONSTRUCTED
@ CONSTRUCTED
Definition: controller.h:166
pr2_controller_interface::Controller::getController
bool getController(const std::string &name, int sched, ControllerType *&c)
Method to get access to another controller by name and type.
Definition: controller.h:90
pr2_controller_interface::Controller::RUNNING
@ RUNNING
Definition: controller.h:166
pr2_controller_interface::Controller::BEFORE_ME
@ BEFORE_ME
Definition: controller.h:56
controller_interface::Controller
pr2_controller_interface::Controller::~Controller
virtual ~Controller()
Definition: controller.h:59
pr2_controller_interface::Controller::stopRequest
bool stopRequest()
Definition: controller.h:134
pr2_controller_interface::Controller::after_list_
std::vector< std::string > after_list_
Definition: controller.h:164
pr2_controller_interface::Controller::state_
enum pr2_controller_interface::Controller::@1 state_
pr2_mechanism_model::RobotState
pr2_controller_interface
Definition: controller.h:50
ROS_ERROR
#define ROS_ERROR(...)
pr2_controller_interface::ControllerProvider::getControllerByName
bool getControllerByName(const std::string &name, ControllerType *&c)
Definition: controller_provider.h:59
pr2_controller_interface::Controller::initRequest
bool initRequest(ControllerProvider *cp, pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
Definition: controller.h:146
pr2_controller_interface::Controller
Definition: controller.h:53
pr2_controller_interface::Controller::stopping
virtual void stopping()
The stopping method is called by the realtime thread just after the last update call.
Definition: controller.h:72
pr2_controller_interface::Controller::update
void update(const ros::Time &time, const ros::Duration &period)
Definition: controller.h:62
pr2_controller_interface::Controller::starting
void starting(const ros::Time &time)
Definition: controller.h:61
ros::Time
pr2_controller_interface::Controller::stopping
void stopping(const ros::Time &time)
Definition: controller.h:63
pr2_controller_interface::Controller::operator=
Controller & operator=(const Controller &c)
pr2_controller_interface::Controller::init
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.
pr2_controller_interface::Controller::starting
virtual void starting()
The starting method is called just before the first update from within the realtime thread.
Definition: controller.h:66
pr2_controller_interface::Controller::INITIALIZED
@ INITIALIZED
Definition: controller.h:166
pr2_controller_interface::ControllerProvider
Definition: controller_provider.h:53
controller_provider.h
ros::Duration
ros::NodeHandle
robot.h
pr2_controller_interface::Controller::contr_prov_
ControllerProvider * contr_prov_
Definition: controller.h:171


pr2_controller_interface
Author(s): Wim Meeussen
autogenerated on Mon Mar 6 2023 03:49:18