hardware_interface.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 
35 #ifndef HARDWARE_INTERFACE_H
36 #define HARDWARE_INTERFACE_H
37 
38 #include <string>
39 #include <vector>
40 
41 #include <ros/ros.h>
42 
43 #include <geometry_msgs/Vector3.h>
44 #include <geometry_msgs/Wrench.h>
45 
47 
48 
50 public:
52  timestamp_(0),
53  device_id_(0),
54  encoder_count_(0),
55  position_(0),
57  velocity_(0),
63  is_enabled_(0),
64  halted_(0),
71  motor_voltage_(0),
73  zero_offset_(0)
74  {}
75 
84 
90  double timestamp_;
91 
92  int device_id_;
93 
95  double position_;
97  double velocity_;
98 
104 
105  bool is_enabled_;
106  bool halted_;
107 
111 
115 
116  double max_effort_;
117 
118  double motor_voltage_;
119 
121 
122  double zero_offset_;
123 };
124 
126 {
127 public:
129  enable_(0), effort_(0)
130  {}
131  bool enable_;
132  double effort_;
133 };
134 
147 class Actuator
148 {
149 public:
150  Actuator() {};
151  Actuator(std::string name) : name_(name) {}
152  std::string name_;
155 };
156 
158 {
159 };
160 
162 {
163 public:
164  std::vector<uint16_t> data_;
165 };
166 
178 {
179 public:
180  std::string name_;
183 };
184 
186 {
187 public:
188  enum {RANGE_2G=0, RANGE_4G=1, RANGE_8G=2};
189  enum {BANDWIDTH_1500HZ=6, BANDWIDTH_750HZ=5, BANDWIDTH_375HZ=4, BANDWIDTH_190HZ=3, BANDWIDTH_100HZ=2, BANDWIDTH_50HZ=1, BANDWIDTH_25HZ=0};
190  AccelerometerCommand() : range_(RANGE_2G), bandwidth_(BANDWIDTH_1500HZ) {}
191  int range_;
193 };
194 
196 {
197 public:
198  std::string frame_id_;
199  std::vector<geometry_msgs::Vector3> samples_;
200 };
201 
213 {
214 public:
215  std::string name_;
218 };
219 
221 {
222 public:
223  bool good_;
224  std::vector<geometry_msgs::Wrench> samples_;
226 };
227 
229 {
230 public:
233 };
234 
236 {
237 public:
238  std::string name_;
241 };
242 
243 
245 {
246 public:
247  DigitalOutCommand() : data_(false) {}
248  DigitalOutCommand(bool data) : data_(data) {}
249  uint8_t data_;
250 };
251 
253 {
254 public:
255  uint8_t data_;
256 };
257 
269 {
270 public:
271  std::string name_;
274 };
275 
277 {
278 public:
279  ProjectorCommand(uint8_t &A, uint8_t &B, uint8_t &I, uint8_t &M, uint8_t &L0, uint8_t &L1) : enable_(0), current_(0), A_(A), B_(B), I_(I), M_(M), L0_(L0), L1_(L1) {}
280  bool enable_;
281  double current_;
282  uint8_t &A_;
283  uint8_t &B_;
284  uint8_t &I_;
285  uint8_t &M_;
286  uint8_t &L0_;
287  uint8_t &L1_;
289 };
290 
292 {
293 public:
294  ProjectorState(uint8_t &A, uint8_t &B, uint8_t &I, uint8_t &M, uint8_t &L0, uint8_t &L1) : A_(A), B_(B), I_(I), M_(M), L0_(L0), L1_(L1) {}
295  bool enable_;
299  double max_current_;
300  uint8_t &A_;
301  uint8_t &B_;
302  uint8_t &I_;
303  uint8_t &M_;
304  uint8_t &L0_;
305  uint8_t &L1_;
307 
308  bool output_;
311 
312  uint32_t timestamp_us_;
315 };
316 
336 {
337 public:
338  Projector(DigitalOut &A, DigitalOut &B, DigitalOut &I, DigitalOut &M, DigitalOut &L0, DigitalOut &L1) : state_(A.state_.data_, B.state_.data_, I.state_.data_, M.state_.data_, L0.state_.data_, L1.state_.data_), command_(A.command_.data_, B.command_.data_, I.command_.data_, M.command_.data_, L0.command_.data_, L1.command_.data_) {}
339  std::string name_;
342 };
343 
345 {
346 };
347 
349 {
350 public:
351  std::vector<double> state_;
352 };
353 
354 class AnalogIn
355 {
356 public:
357  std::string name_;
360 };
361 
368 class CustomHW
369 {
370 public:
371  std::string name_;
372 };
373 
374 typedef std::map<std::string, Actuator*> ActuatorMap;
375 typedef std::map<std::string, PressureSensor*> PressureSensorMap;
376 typedef std::map<std::string, Accelerometer*> AccelerometerMap;
377 typedef std::map<std::string, ForceTorque*> ForceTorqueMap;
378 typedef std::map<std::string, DigitalOut*> DigitalOutMap;
379 typedef std::map<std::string, Projector*> ProjectorMap;
380 typedef std::map<std::string, AnalogIn*> AnalogInMap;
381 typedef std::map<std::string, CustomHW*> CustomHWMap;
382 
409 {
410 public:
411  ActuatorMap actuators_;
412  PressureSensorMap pressure_sensors_;
413  AccelerometerMap accelerometers_;
414  ForceTorqueMap ft_sensors_;
415  DigitalOutMap digital_outs_;
416  ProjectorMap projectors_;
417  AnalogInMap analog_ins_;
418  CustomHWMap custom_hws_;
424  Actuator* getActuator(const std::string &name) const {
425  ActuatorMap::const_iterator it = actuators_.find(name);
426  return it != actuators_.end() ? it->second : NULL;
427  }
428 
434  PressureSensor* getPressureSensor(const std::string &name) const {
435  PressureSensorMap::const_iterator it = pressure_sensors_.find(name);
436  return it != pressure_sensors_.end() ? it->second : NULL;
437  }
438 
444  Accelerometer* getAccelerometer(const std::string &name) const {
445  AccelerometerMap::const_iterator it = accelerometers_.find(name);
446  return it != accelerometers_.end() ? it->second : NULL;
447  }
448 
454  ForceTorque* getForceTorque(const std::string &name) const {
455  ForceTorqueMap::const_iterator it = ft_sensors_.find(name);
456  return it != ft_sensors_.end() ? it->second : NULL;
457  }
458 
464  DigitalOut* getDigitalOut(const std::string &name) const {
465  DigitalOutMap::const_iterator it = digital_outs_.find(name);
466  return it != digital_outs_.end() ? it->second : NULL;
467  }
468 
474  Projector* getProjector(const std::string &name) const {
475  ProjectorMap::const_iterator it = projectors_.find(name);
476  return it != projectors_.end() ? it->second : NULL;
477  }
478 
484  AnalogIn* getAnalogIn(const std::string &name) const {
485  AnalogInMap::const_iterator it = analog_ins_.find(name);
486  return it != analog_ins_.end() ? it->second : NULL;
487  }
488 
494  CustomHW* getCustomHW(const std::string &name) const {
495  CustomHWMap::const_iterator it = custom_hws_.find(name);
496  return it != custom_hws_.end() ? it->second : NULL;
497  }
498 
504  bool addActuator(Actuator *actuator) {
505  std::pair<ActuatorMap::iterator, bool> p;
506  p = actuators_.insert(ActuatorMap::value_type(actuator->name_, actuator));
507  return p.second;
508  }
509 
516  std::pair<PressureSensorMap::iterator, bool> p;
517  p = pressure_sensors_.insert(PressureSensorMap::value_type(sensor->name_, sensor));
518  return p.second;
519  }
520 
526  bool addAccelerometer(Accelerometer *accelerometer) {
527  std::pair<AccelerometerMap::iterator, bool> p;
528  p = accelerometers_.insert(AccelerometerMap::value_type(accelerometer->name_, accelerometer));
529  return p.second;
530  }
531 
537  bool addForceTorque(ForceTorque *forcetorque) {
538  std::pair<ForceTorqueMap::iterator, bool> p;
539  p = ft_sensors_.insert(ForceTorqueMap::value_type(forcetorque->name_, forcetorque));
540  return p.second;
541  }
542 
548  bool addDigitalOut(DigitalOut *digital_out) {
549  std::pair<DigitalOutMap::iterator, bool> p;
550  p = digital_outs_.insert(DigitalOutMap::value_type(digital_out->name_, digital_out));
551  return p.second;
552  }
553 
559  bool addProjector(Projector *projector) {
560  std::pair<ProjectorMap::iterator, bool> p;
561  p = projectors_.insert(ProjectorMap::value_type(projector->name_, projector));
562  return p.second;
563  }
564 
570  bool addAnalogIn(AnalogIn *analog_in) {
571  std::pair<AnalogInMap::iterator, bool> p;
572  p = analog_ins_.insert(AnalogInMap::value_type(analog_in->name_, analog_in));
573  return p.second;
574  }
575 
581  bool addCustomHW(CustomHW *custom_hw) {
582  std::pair<CustomHWMap::iterator, bool> p;
583  p = custom_hws_.insert(CustomHWMap::value_type(custom_hw->name_, custom_hw));
584  return p.second;
585  }
586 
588 };
589 }
590 
591 #endif
bool addActuator(Actuator *actuator)
Add an actuator to the hardware interface.
ForceTorque * getForceTorque(const std::string &name) const
Get a pointer to the FT sensor by name.
CustomHW * getCustomHW(const std::string &name) const
Get a pointer to the Custom Hardware device by name.
double last_measured_effort_
The measured torque (in Nm)
bool addCustomHW(CustomHW *custom_hw)
Add a Custom Hardware device to the hardware interface.
Accelerometer * getAccelerometer(const std::string &name) const
Get a pointer to the accelerometer by name.
double last_calibration_rising_edge_
The position of the motor the last time the calibration switch went from low to high.
double effort_
Force to apply (in Nm)
int encoder_count_
The number of ticks as reported by the encoder.
std::map< std::string, Actuator * > ActuatorMap
int num_encoder_errors_
The number of invalid encoder signal transitions.
double max_effort_
Absolute torque limit for actuator (derived from motor current limit). (in Nm)
std::map< std::string, PressureSensor * > PressureSensorMap
double encoder_velocity_
The velocity measured in encoder ticks per second.
ProjectorState(uint8_t &A, uint8_t &B, uint8_t &I, uint8_t &M, uint8_t &L0, uint8_t &L1)
double last_executed_effort_
The torque applied after safety limits were enforced (in Nm)
bool addPressureSensor(PressureSensor *sensor)
Add an pressure sensor to the hardware interface.
int bandwidth_
Accelerometer bandwidth setting. Value is passed directly to Bosch accelerometer (BMA 150)...
bool addAccelerometer(Accelerometer *accelerometer)
Add an accelerometer to the hardware interface.
AnalogIn * getAnalogIn(const std::string &name) const
Get a pointer to the analog-in device by name.
double velocity_
The velocity in radians per second.
double last_commanded_effort_
The torque requested in the previous ActuatorCommand (in Nm)
std::map< std::string, Accelerometer * > AccelerometerMap
std::map< std::string, ForceTorque * > ForceTorqueMap
Actuator * getActuator(const std::string &name) const
Get a pointer to the actuator by name.
std::map< std::string, DigitalOut * > DigitalOutMap
DigitalOut * getDigitalOut(const std::string &name) const
Get a pointer to the digital I/O by name.
double last_executed_current_
The actual current requested after safety limits were enforced (in amps)
std::map< std::string, Projector * > ProjectorMap
double max_current_
Current limit (Amps). Minimum of board and LED limits.
bool halt_on_error_
If halt_on_error_ is true, the driver with halt motors when an there is an error is detected...
bool good_
A vector of samples taken from force/torque sensor since the last iteration of the control loop (olde...
int device_id_
Position in EtherCAT chain.
Projector(DigitalOut &A, DigitalOut &B, DigitalOut &I, DigitalOut &M, DigitalOut &L0, DigitalOut &L1)
bool calibration_rising_edge_valid_
Is the last_callibration_rising_edge_ field valid?
PressureSensor * getPressureSensor(const std::string &name) const
Get a pointer to the pressure sensor by name.
std::string frame_id_
Frame id of accelerometer.
AccelerometerCommand()
Enums for possible accelerometer bandwidth settings.
double last_commanded_current_
The current computed based on the effort specified in the ActuatorCommand (in amps) ...
bool calibration_falling_edge_valid_
Is the last_callibration_falling_edge_ field valid?
bool addProjector(Projector *projector)
Add an projector to the hardware interface.
bool addAnalogIn(AnalogIn *analog_in)
Add an analog-in device to the hardware interface.
ProjectorCommand(uint8_t &A, uint8_t &B, uint8_t &I, uint8_t &M, uint8_t &L0, uint8_t &L1)
double last_measured_current_
The measured current (in amps)
std::vector< uint16_t > data_
A vector of 22 pressure readings from each sensor.
int range_
The range of the values to be returned (range of 0 means within +/- 2g, 1 means within +/-4g...
double last_calibration_falling_edge_
The position of the motor the last time the calibration switch went from high to low.
std::map< std::string, CustomHW * > CustomHWMap
double position_
The position of the motor (in radians)
double zero_offset_
A bias applied to the position value when reported. This value is written once after calibration...
std::map< std::string, AnalogIn * > AnalogInMap
double motor_voltage_
Motor voltage (in volts)
ros::Time current_time_
The time at which the commands were sent to the hardware.
bool calibration_reading_
the value of the last calibration reading: low (false) or high (true)
bool halted_
indicates if the motor is halted. A motor can be halted because of voltage or communication problems ...
bool addForceTorque(ForceTorque *forcetorque)
Add a FT sensor to the hardware interface.
bool addDigitalOut(DigitalOut *digital_out)
Add an digital I/O to the hardware interface.
std::vector< geometry_msgs::Vector3 > samples_
A vector of samples taken from the accelerometer (in m/s/s) since the last iteration of the control l...
Projector * getProjector(const std::string &name) const
Get a pointer to the projector by name.


pr2_hardware_interface
Author(s): Eric Berger berger@willowgarage.com
autogenerated on Mon Jun 10 2019 14:19:00