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


hardware_interface
Author(s): Wim Meeussen, Adolfo Rodriguez Tsouroukdissian
autogenerated on Tue Oct 15 2024 02:08:19