actuator_state_interface.h
Go to the documentation of this file.
1 // Copyright (C) 2012, hiDOF INC.
3 // Copyright (C) 2013, PAL Robotics S.L.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright notice,
8 // this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of hiDOF, Inc. nor the names of its
13 // contributors may be used to endorse or promote products derived from
14 // this software without specific prior written permission.
15 //
16 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
17 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
19 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
20 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
21 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
23 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
24 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
25 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26 // POSSIBILITY OF SUCH DAMAGE.
28 
30 
31 #pragma once
32 
33 
35 #include <string>
36 
37 namespace hardware_interface
38 {
39 
46 {
47 public:
48  ActuatorStateHandle() = default;
49 
56  ActuatorStateHandle(const std::string& name, const double* pos, const double* vel, const double* eff)
57  : name_(name), pos_(pos), vel_(vel), eff_(eff)
58  {
59  if (!pos)
60  {
61  throw HardwareInterfaceException("Cannot create handle '" + name + "'. Position data pointer is null.");
62  }
63  if (!vel)
64  {
65  throw HardwareInterfaceException("Cannot create handle '" + name + "'. Velocity data pointer is null.");
66  }
67  if (!eff)
68  {
69  throw HardwareInterfaceException("Cannot create handle '" + name + "'. Effort data pointer is null.");
70  }
71  }
72 
81  ActuatorStateHandle(const std::string& name, const double* pos, const double* vel, const double* eff,
82  const double* absolute_pos, const double* torque_sensor)
83  : name_(name), pos_(pos), vel_(vel), eff_(eff), absolute_pos_(absolute_pos), torque_sensor_(torque_sensor)
84  {
85  if (!pos)
86  {
87  throw HardwareInterfaceException("Cannot create handle '" + name + "'. Position data pointer is null.");
88  }
89  if (!vel)
90  {
91  throw HardwareInterfaceException("Cannot create handle '" + name + "'. Velocity data pointer is null.");
92  }
93  if (!eff)
94  {
95  throw HardwareInterfaceException("Cannot create handle '" + name + "'. Effort data pointer is null.");
96  }
97 
98  if (!absolute_pos)
99  {
100  throw HardwareInterfaceException("Cannot create handle '" + name + "'. Absolute data pointer is null.");
101  }
102  if (!torque_sensor)
103  {
104  throw HardwareInterfaceException("Cannot create handle '" + name + "'. Torque sensor data pointer is null.");
105  }
106  }
107 
115  ActuatorStateHandle(const std::string& name, const double* pos, const double* vel, const double* eff,
116  const double* absolute_pos)
117  : name_(name), pos_(pos), vel_(vel), eff_(eff), absolute_pos_(absolute_pos)
118  {
119  if (!pos)
120  {
121  throw HardwareInterfaceException("Cannot create handle '" + name + "'. Position data pointer is null.");
122  }
123  if (!vel)
124  {
125  throw HardwareInterfaceException("Cannot create handle '" + name + "'. Velocity data pointer is null.");
126  }
127  if (!eff)
128  {
129  throw HardwareInterfaceException("Cannot create handle '" + name + "'. Effort data pointer is null.");
130  }
131  if (!absolute_pos)
132  {
133  throw HardwareInterfaceException("Cannot create handle '" + name + "'. Absolute data pointer is null.");
134  }
135  }
136 
145  ActuatorStateHandle(const std::string& name, const double* pos, const double* vel, const double* eff,
146  const double* torque_sensor, bool)
147  : name_(name), pos_(pos), vel_(vel), eff_(eff), torque_sensor_(torque_sensor)
148  {
149  if (!pos)
150  {
151  throw HardwareInterfaceException("Cannot create handle '" + name + "'. Position data pointer is null.");
152  }
153  if (!vel)
154  {
155  throw HardwareInterfaceException("Cannot create handle '" + name + "'. Velocity data pointer is null.");
156  }
157  if (!eff)
158  {
159  throw HardwareInterfaceException("Cannot create handle '" + name + "'. Effort data pointer is null.");
160  }
161  if (!torque_sensor)
162  {
163  throw HardwareInterfaceException("Cannot create handle '" + name + "'. Torque sensor data pointer is null.");
164  }
165  }
166 
167  std::string getName() const {return name_;}
168  double getPosition() const {assert(pos_); return *pos_;}
169  double getVelocity() const {assert(vel_); return *vel_;}
170  double getEffort() const {assert(eff_); return *eff_;}
171 
172  double getAbsolutePosition() const
173  {
174  if(!hasAbsolutePosition())
175  {
176  throw std::runtime_error("Actuator does not support absolute encoders");
177  }
178  return *absolute_pos_;
179  }
180 
181  double getTorqueSensor() const
182  {
183  if(!hasTorqueSensor())
184  {
185  throw std::runtime_error("Actuator does not support torque sensors");
186  }
187  return *torque_sensor_;
188  }
189 
190  const double* getPositionPtr() const {return pos_;}
191  const double* getVelocityPtr() const {return vel_;}
192  const double* getEffortPtr() const {return eff_;}
193 
194  const double* getAbsolutePositionPtr() const
195  {
196  if(!hasAbsolutePosition())
197  {
198  throw std::runtime_error("Actuator does not support absolute encoders");
199  }
200  return absolute_pos_;
201  }
202 
203  const double* getTorqueSensorPtr() const
204  {
205  if(!hasTorqueSensor())
206  {
207  throw std::runtime_error("Actuator does not support torque sensors");
208  }
209  return torque_sensor_;
210  }
211 
212  bool hasAbsolutePosition() const {return absolute_pos_;}
213  bool hasTorqueSensor() const {return torque_sensor_;}
214 
215 private:
216  std::string name_;
217  const double* pos_ = {nullptr};
218  const double* vel_ = {nullptr};
219  const double* eff_ = {nullptr};
220  const double* absolute_pos_ = {nullptr};
221  const double* torque_sensor_ = {nullptr};
222 };
223 
231 class ActuatorStateInterface : public HardwareResourceManager<ActuatorStateHandle> {};
232 
233 }
ActuatorStateHandle(const std::string &name, const double *pos, const double *vel, const double *eff, const double *torque_sensor, bool)
An exception related to a HardwareInterface.
ActuatorStateHandle(const std::string &name, const double *pos, const double *vel, const double *eff, const double *absolute_pos, const double *torque_sensor)
Hardware interface to support reading the state of an array of actuators.
A handle used to read the state of a single actuator. Currently, position, velocity and effort fields...
Base class for handling hardware resources.
ActuatorStateHandle(const std::string &name, const double *pos, const double *vel, const double *eff)
ActuatorStateHandle(const std::string &name, const double *pos, const double *vel, const double *eff, const double *absolute_pos)


hardware_interface
Author(s): Wim Meeussen, Adolfo Rodriguez Tsouroukdissian
autogenerated on Mon Feb 28 2022 23:30:10