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 
49 class ActuatorState{
50 public:
51  ActuatorState() :
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 
94  int encoder_count_;
95  double position_;
96  double encoder_velocity_;
97  double velocity_;
98 
104 
105  bool is_enabled_;
106  bool halted_;
107 
108  double last_commanded_current_;
109  double last_executed_current_;
110  double last_measured_current_;
111 
112  double last_commanded_effort_;
113  double last_executed_effort_;
114  double last_measured_effort_;
115 
116  double max_effort_;
117 
118  double motor_voltage_;
119 
120  int num_encoder_errors_;
121 
122  double zero_offset_;
123 };
124 
125 class ActuatorCommand
126 {
127 public:
128  ActuatorCommand() :
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};
191  int range_;
192  int bandwidth_;
193 };
194 
195 class AccelerometerState
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 
228 class ForceTorqueCommand
229 {
230 public:
232  bool halt_on_error_;
233 };
234 
235 class ForceTorque
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 
268 class DigitalOut
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_;
288  bool pulse_replicator_;
289 };
290 
291 class ProjectorState
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_;
297  double last_executed_current_;
298  double last_measured_current_;
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_;
306  bool pulse_replicator_;
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 
348 class AnalogInState
349 {
350 public:
351  std::vector<double> state_;
352 };
353 
354 class AnalogIn
355 {
356 public:
357  std::string name_;
358  AnalogInState state_;
359  AnalogInCommand command_;
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:
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 
515  bool addPressureSensor(PressureSensor *sensor) {
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
pr2_hardware_interface
Definition: hardware_interface.h:46
pr2_hardware_interface::ActuatorState::halted_
bool halted_
indicates if the motor is halted. A motor can be halted because of voltage or communication problems
Definition: hardware_interface.h:170
pr2_hardware_interface::ForceTorqueCommand
Definition: hardware_interface.h:260
pr2_hardware_interface::AnalogInCommand
Definition: hardware_interface.h:376
pr2_hardware_interface::ProjectorState::L0_
uint8_t & L0_
Definition: hardware_interface.h:336
pr2_hardware_interface::AccelerometerCommand::BANDWIDTH_100HZ
@ BANDWIDTH_100HZ
Definition: hardware_interface.h:221
pr2_hardware_interface::ProjectorState::rising_timestamp_valid_
bool rising_timestamp_valid_
Definition: hardware_interface.h:341
pr2_hardware_interface::ForceTorqueMap
std::map< std::string, ForceTorque * > ForceTorqueMap
Definition: hardware_interface.h:409
pr2_hardware_interface::CustomHWMap
std::map< std::string, CustomHW * > CustomHWMap
Definition: hardware_interface.h:413
pr2_hardware_interface::ActuatorState::ActuatorState
ActuatorState()
Definition: hardware_interface.h:115
pr2_hardware_interface::ProjectorState::rising_timestamp_us_
uint32_t rising_timestamp_us_
Definition: hardware_interface.h:345
pr2_hardware_interface::ProjectorCommand::ProjectorCommand
ProjectorCommand(uint8_t &A, uint8_t &B, uint8_t &I, uint8_t &M, uint8_t &L0, uint8_t &L1)
Definition: hardware_interface.h:311
pr2_hardware_interface::Accelerometer::name_
std::string name_
Definition: hardware_interface.h:247
pr2_hardware_interface::HardwareInterface::analog_ins_
AnalogInMap analog_ins_
Definition: hardware_interface.h:449
pr2_hardware_interface::ActuatorState::last_executed_effort_
double last_executed_effort_
The torque applied after safety limits were enforced (in Nm)
Definition: hardware_interface.h:177
pr2_hardware_interface::DigitalOut::name_
std::string name_
Definition: hardware_interface.h:303
pr2_hardware_interface::AccelerometerState::samples_
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...
Definition: hardware_interface.h:231
pr2_hardware_interface::Projector::command_
ProjectorCommand command_
Definition: hardware_interface.h:373
pr2_hardware_interface::Accelerometer
Definition: hardware_interface.h:244
pr2_hardware_interface::HardwareInterface::addActuator
bool addActuator(Actuator *actuator)
Add an actuator to the hardware interface.
Definition: hardware_interface.h:536
pr2_hardware_interface::ActuatorState::timestamp_
double timestamp_
Definition: hardware_interface.h:154
pr2_hardware_interface::HardwareInterface::current_time_
ros::Time current_time_
The time at which the commands were sent to the hardware.
Definition: hardware_interface.h:619
pr2_hardware_interface::HardwareInterface::getCustomHW
CustomHW * getCustomHW(const std::string &name) const
Get a pointer to the Custom Hardware device by name.
Definition: hardware_interface.h:526
ros.h
pr2_hardware_interface::Actuator::Actuator
Actuator()
Definition: hardware_interface.h:182
pr2_hardware_interface::AccelerometerState
Definition: hardware_interface.h:227
pr2_hardware_interface::ActuatorState::last_measured_effort_
double last_measured_effort_
The measured torque (in Nm)
Definition: hardware_interface.h:178
pr2_hardware_interface::HardwareInterface::getForceTorque
ForceTorque * getForceTorque(const std::string &name) const
Get a pointer to the FT sensor by name.
Definition: hardware_interface.h:486
pr2_hardware_interface::PressureSensor::name_
std::string name_
Definition: hardware_interface.h:212
pr2_hardware_interface::HardwareInterface::getProjector
Projector * getProjector(const std::string &name) const
Get a pointer to the projector by name.
Definition: hardware_interface.h:506
pr2_hardware_interface::ForceTorque::state_
ForceTorqueState state_
Definition: hardware_interface.h:271
pr2_hardware_interface::DigitalOutCommand::DigitalOutCommand
DigitalOutCommand()
Definition: hardware_interface.h:279
pr2_hardware_interface::DigitalOutCommand
Definition: hardware_interface.h:276
pr2_hardware_interface::ActuatorState::encoder_velocity_
double encoder_velocity_
The velocity measured in encoder ticks per second.
Definition: hardware_interface.h:160
pr2_hardware_interface::Projector::name_
std::string name_
Definition: hardware_interface.h:371
pr2_hardware_interface::ActuatorState::last_commanded_effort_
double last_commanded_effort_
The torque requested in the previous ActuatorCommand (in Nm)
Definition: hardware_interface.h:176
pr2_hardware_interface::ProjectorState::B_
uint8_t & B_
Definition: hardware_interface.h:333
pr2_hardware_interface::ForceTorqueState::good_
bool good_
A vector of samples taken from force/torque sensor since the last iteration of the control loop (olde...
Definition: hardware_interface.h:255
pr2_hardware_interface::Actuator::state_
ActuatorState state_
Definition: hardware_interface.h:185
pr2_hardware_interface::AccelerometerCommand::range_
int range_
The range of the values to be returned (range of 0 means within +/- 2g, 1 means within +/-4g,...
Definition: hardware_interface.h:223
pr2_hardware_interface::ProjectorState
Definition: hardware_interface.h:323
pr2_hardware_interface::HardwareInterface::projectors_
ProjectorMap projectors_
Definition: hardware_interface.h:448
pr2_hardware_interface::PressureSensor::command_
PressureSensorCommand command_
Definition: hardware_interface.h:214
pr2_hardware_interface::AnalogIn::command_
AnalogInCommand command_
Definition: hardware_interface.h:391
pr2_hardware_interface::ProjectorState::falling_timestamp_us_
uint32_t falling_timestamp_us_
Definition: hardware_interface.h:346
pr2_hardware_interface::HardwareInterface
Definition: hardware_interface.h:440
pr2_hardware_interface::ProjectorCommand::enable_
bool enable_
Definition: hardware_interface.h:312
pr2_hardware_interface::ProjectorState::M_
uint8_t & M_
Definition: hardware_interface.h:335
pr2_hardware_interface::Projector::state_
ProjectorState state_
Definition: hardware_interface.h:372
pr2_hardware_interface::ActuatorState::velocity_
double velocity_
The velocity in radians per second.
Definition: hardware_interface.h:161
pr2_hardware_interface::Projector::Projector
Projector(DigitalOut &A, DigitalOut &B, DigitalOut &I, DigitalOut &M, DigitalOut &L0, DigitalOut &L1)
Definition: hardware_interface.h:370
pr2_hardware_interface::AnalogIn::state_
AnalogInState state_
Definition: hardware_interface.h:390
pr2_hardware_interface::ProjectorCommand::L0_
uint8_t & L0_
Definition: hardware_interface.h:318
pr2_hardware_interface::ActuatorState
Definition: hardware_interface.h:81
pr2_hardware_interface::AccelerometerCommand::RANGE_8G
@ RANGE_8G
Definition: hardware_interface.h:220
pr2_hardware_interface::HardwareInterface::digital_outs_
DigitalOutMap digital_outs_
Definition: hardware_interface.h:447
pr2_hardware_interface::ProjectorCommand::I_
uint8_t & I_
Definition: hardware_interface.h:316
pr2_hardware_interface::AccelerometerCommand::BANDWIDTH_190HZ
@ BANDWIDTH_190HZ
Definition: hardware_interface.h:221
pr2_hardware_interface::ActuatorState::device_id_
int device_id_
Position in EtherCAT chain.
Definition: hardware_interface.h:156
pr2_hardware_interface::ForceTorqueState
Definition: hardware_interface.h:252
pr2_hardware_interface::HardwareInterface::getAnalogIn
AnalogIn * getAnalogIn(const std::string &name) const
Get a pointer to the analog-in device by name.
Definition: hardware_interface.h:516
pr2_hardware_interface::AccelerometerCommand::AccelerometerCommand
AccelerometerCommand()
Enums for possible accelerometer bandwidth settings.
Definition: hardware_interface.h:222
pr2_hardware_interface::HardwareInterface::actuators_
ActuatorMap actuators_
Definition: hardware_interface.h:443
pr2_hardware_interface::AccelerometerCommand::bandwidth_
int bandwidth_
Accelerometer bandwidth setting. Value is passed directly to Bosch accelerometer (BMA 150)....
Definition: hardware_interface.h:224
pr2_hardware_interface::ProjectorState::max_current_
double max_current_
Current limit (Amps). Minimum of board and LED limits.
Definition: hardware_interface.h:331
pr2_hardware_interface::ProjectorCommand::M_
uint8_t & M_
Definition: hardware_interface.h:317
pr2_hardware_interface::DigitalOut::command_
DigitalOutCommand command_
Definition: hardware_interface.h:305
pr2_hardware_interface::DigitalOutState::data_
uint8_t data_
Definition: hardware_interface.h:287
pr2_hardware_interface::AnalogInState
Definition: hardware_interface.h:380
pr2_hardware_interface::ProjectorState::falling_timestamp_valid_
bool falling_timestamp_valid_
Definition: hardware_interface.h:342
pr2_hardware_interface::ProjectorCommand::B_
uint8_t & B_
Definition: hardware_interface.h:315
pr2_hardware_interface::ActuatorMap
std::map< std::string, Actuator * > ActuatorMap
Definition: hardware_interface.h:406
pr2_hardware_interface::ActuatorState::last_commanded_current_
double last_commanded_current_
The current computed based on the effort specified in the ActuatorCommand (in amps)
Definition: hardware_interface.h:172
pr2_hardware_interface::ActuatorState::calibration_falling_edge_valid_
bool calibration_falling_edge_valid_
Is the last_callibration_falling_edge_ field valid?
Definition: hardware_interface.h:165
pr2_hardware_interface::ProjectorState::last_commanded_current_
double last_commanded_current_
Definition: hardware_interface.h:328
pr2_hardware_interface::PressureSensorCommand
Definition: hardware_interface.h:189
pr2_hardware_interface::AccelerometerCommand::RANGE_2G
@ RANGE_2G
Definition: hardware_interface.h:220
pr2_hardware_interface::HardwareInterface::addAccelerometer
bool addAccelerometer(Accelerometer *accelerometer)
Add an accelerometer to the hardware interface.
Definition: hardware_interface.h:558
pr2_hardware_interface::ProjectorCommand::L1_
uint8_t & L1_
Definition: hardware_interface.h:319
pr2_hardware_interface::AccelerometerCommand::BANDWIDTH_750HZ
@ BANDWIDTH_750HZ
Definition: hardware_interface.h:221
pr2_hardware_interface::ActuatorState::last_executed_current_
double last_executed_current_
The actual current requested after safety limits were enforced (in amps)
Definition: hardware_interface.h:173
pr2_hardware_interface::ProjectorState::I_
uint8_t & I_
Definition: hardware_interface.h:334
pr2_hardware_interface::PressureSensor::state_
PressureSensorState state_
Definition: hardware_interface.h:213
pr2_hardware_interface::AnalogInState::state_
std::vector< double > state_
Definition: hardware_interface.h:383
pr2_hardware_interface::HardwareInterface::getPressureSensor
PressureSensor * getPressureSensor(const std::string &name) const
Get a pointer to the pressure sensor by name.
Definition: hardware_interface.h:466
pr2_hardware_interface::AnalogInMap
std::map< std::string, AnalogIn * > AnalogInMap
Definition: hardware_interface.h:412
pr2_hardware_interface::ActuatorState::sample_timestamp_
ros::Duration sample_timestamp_
Definition: hardware_interface.h:147
pr2_hardware_interface::ProjectorState::last_measured_current_
double last_measured_current_
Definition: hardware_interface.h:330
pr2_hardware_interface::ForceTorque
Definition: hardware_interface.h:267
pr2_hardware_interface::HardwareInterface::accelerometers_
AccelerometerMap accelerometers_
Definition: hardware_interface.h:445
pr2_hardware_interface::AccelerometerCommand::BANDWIDTH_25HZ
@ BANDWIDTH_25HZ
Definition: hardware_interface.h:221
pr2_hardware_interface::HardwareInterface::getAccelerometer
Accelerometer * getAccelerometer(const std::string &name) const
Get a pointer to the accelerometer by name.
Definition: hardware_interface.h:476
pr2_hardware_interface::ProjectorMap
std::map< std::string, Projector * > ProjectorMap
Definition: hardware_interface.h:411
pr2_hardware_interface::ForceTorqueState::samples_
std::vector< geometry_msgs::Wrench > samples_
Definition: hardware_interface.h:257
pr2_hardware_interface::AccelerometerMap
std::map< std::string, Accelerometer * > AccelerometerMap
Definition: hardware_interface.h:408
pr2_hardware_interface::ActuatorState::position_
double position_
The position of the motor (in radians)
Definition: hardware_interface.h:159
pr2_hardware_interface::DigitalOutCommand::data_
uint8_t data_
Definition: hardware_interface.h:281
pr2_hardware_interface::AccelerometerState::frame_id_
std::string frame_id_
Frame id of accelerometer.
Definition: hardware_interface.h:230
pr2_hardware_interface::ActuatorCommand::enable_
bool enable_
Enable this actuator.
Definition: hardware_interface.h:163
pr2_hardware_interface::CustomHW
Definition: hardware_interface.h:400
pr2_hardware_interface::ProjectorCommand::pulse_replicator_
bool pulse_replicator_
Definition: hardware_interface.h:320
pr2_hardware_interface::DigitalOutMap
std::map< std::string, DigitalOut * > DigitalOutMap
Definition: hardware_interface.h:410
pr2_hardware_interface::PressureSensorState::data_
std::vector< uint16_t > data_
A vector of 22 pressure readings from each sensor.
Definition: hardware_interface.h:196
pr2_hardware_interface::ForceTorque::name_
std::string name_
Definition: hardware_interface.h:270
pr2_hardware_interface::HardwareInterface::addDigitalOut
bool addDigitalOut(DigitalOut *digital_out)
Add an digital I/O to the hardware interface.
Definition: hardware_interface.h:580
pr2_hardware_interface::AccelerometerCommand::BANDWIDTH_1500HZ
@ BANDWIDTH_1500HZ
Definition: hardware_interface.h:221
pr2_hardware_interface::ActuatorState::calibration_rising_edge_valid_
bool calibration_rising_edge_valid_
Is the last_callibration_rising_edge_ field valid?
Definition: hardware_interface.h:164
pr2_hardware_interface::PressureSensor
Definition: hardware_interface.h:209
ros::Time
pr2_hardware_interface::ForceTorque::command_
ForceTorqueCommand command_
Definition: hardware_interface.h:272
pr2_hardware_interface::ProjectorState::output_
bool output_
Definition: hardware_interface.h:340
pr2_hardware_interface::AccelerometerCommand
Definition: hardware_interface.h:217
pr2_hardware_interface::ActuatorCommand::effort_
double effort_
Force to apply (in Nm)
Definition: hardware_interface.h:164
pr2_hardware_interface::ProjectorCommand
Definition: hardware_interface.h:308
pr2_hardware_interface::ProjectorCommand::current_
double current_
Definition: hardware_interface.h:313
pr2_hardware_interface::ProjectorState::last_executed_current_
double last_executed_current_
Definition: hardware_interface.h:329
pr2_hardware_interface::AccelerometerCommand::BANDWIDTH_50HZ
@ BANDWIDTH_50HZ
Definition: hardware_interface.h:221
pr2_hardware_interface::ActuatorCommand::ActuatorCommand
ActuatorCommand()
Definition: hardware_interface.h:160
pr2_hardware_interface::ProjectorState::enable_
bool enable_
Definition: hardware_interface.h:327
pr2_hardware_interface::DigitalOut
Definition: hardware_interface.h:300
pr2_hardware_interface::Accelerometer::state_
AccelerometerState state_
Definition: hardware_interface.h:248
pr2_hardware_interface::HardwareInterface::addAnalogIn
bool addAnalogIn(AnalogIn *analog_in)
Add an analog-in device to the hardware interface.
Definition: hardware_interface.h:602
pr2_hardware_interface::Accelerometer::command_
AccelerometerCommand command_
Definition: hardware_interface.h:249
pr2_hardware_interface::ProjectorState::A_
uint8_t & A_
Definition: hardware_interface.h:332
pr2_hardware_interface::AnalogIn
Definition: hardware_interface.h:386
pr2_hardware_interface::ActuatorState::last_measured_current_
double last_measured_current_
The measured current (in amps)
Definition: hardware_interface.h:174
pr2_hardware_interface::Projector
Definition: hardware_interface.h:367
pr2_hardware_interface::HardwareInterface::addForceTorque
bool addForceTorque(ForceTorque *forcetorque)
Add a FT sensor to the hardware interface.
Definition: hardware_interface.h:569
pr2_hardware_interface::ActuatorState::motor_voltage_
double motor_voltage_
Motor voltage (in volts)
Definition: hardware_interface.h:182
pr2_hardware_interface::DigitalOut::state_
DigitalOutState state_
Definition: hardware_interface.h:304
pr2_hardware_interface::HardwareInterface::addCustomHW
bool addCustomHW(CustomHW *custom_hw)
Add a Custom Hardware device to the hardware interface.
Definition: hardware_interface.h:613
pr2_hardware_interface::AccelerometerCommand::RANGE_4G
@ RANGE_4G
Definition: hardware_interface.h:220
pr2_hardware_interface::Actuator::name_
std::string name_
Definition: hardware_interface.h:184
pr2_hardware_interface::ActuatorState::calibration_reading_
bool calibration_reading_
the value of the last calibration reading: low (false) or high (true)
Definition: hardware_interface.h:163
pr2_hardware_interface::PressureSensorMap
std::map< std::string, PressureSensor * > PressureSensorMap
Definition: hardware_interface.h:407
pr2_hardware_interface::HardwareInterface::addPressureSensor
bool addPressureSensor(PressureSensor *sensor)
Add an pressure sensor to the hardware interface.
Definition: hardware_interface.h:547
pr2_hardware_interface::HardwareInterface::custom_hws_
CustomHWMap custom_hws_
Definition: hardware_interface.h:450
pr2_hardware_interface::ActuatorState::last_calibration_rising_edge_
double last_calibration_rising_edge_
The position of the motor the last time the calibration switch went from low to high.
Definition: hardware_interface.h:166
pr2_hardware_interface::ActuatorState::last_calibration_falling_edge_
double last_calibration_falling_edge_
The position of the motor the last time the calibration switch went from high to low.
Definition: hardware_interface.h:167
pr2_hardware_interface::Actuator::command_
ActuatorCommand command_
Definition: hardware_interface.h:186
pr2_hardware_interface::AccelerometerCommand::BANDWIDTH_375HZ
@ BANDWIDTH_375HZ
Definition: hardware_interface.h:221
pr2_hardware_interface::ActuatorState::is_enabled_
bool is_enabled_
Enable status.
Definition: hardware_interface.h:169
ros::Duration
pr2_hardware_interface::Actuator
Definition: hardware_interface.h:179
pr2_hardware_interface::HardwareInterface::getActuator
Actuator * getActuator(const std::string &name) const
Get a pointer to the actuator by name.
Definition: hardware_interface.h:456
pr2_hardware_interface::ProjectorState::pulse_replicator_
bool pulse_replicator_
Definition: hardware_interface.h:338
pr2_hardware_interface::ForceTorqueCommand::halt_on_error_
bool halt_on_error_
If halt_on_error_ is true, the driver with halt motors when an there is an error is detected....
Definition: hardware_interface.h:264
pr2_hardware_interface::ActuatorCommand
Definition: hardware_interface.h:157
pr2_hardware_interface::ProjectorState::L1_
uint8_t & L1_
Definition: hardware_interface.h:337
pr2_hardware_interface::ActuatorState::encoder_count_
int encoder_count_
The number of ticks as reported by the encoder.
Definition: hardware_interface.h:158
pr2_hardware_interface::HardwareInterface::addProjector
bool addProjector(Projector *projector)
Add an projector to the hardware interface.
Definition: hardware_interface.h:591
pr2_hardware_interface::PressureSensorState
Definition: hardware_interface.h:193
pr2_hardware_interface::ProjectorCommand::A_
uint8_t & A_
Definition: hardware_interface.h:314
pr2_hardware_interface::ActuatorState::num_encoder_errors_
int num_encoder_errors_
The number of invalid encoder signal transitions.
Definition: hardware_interface.h:184
pr2_hardware_interface::ActuatorState::zero_offset_
double zero_offset_
A bias applied to the position value when reported. This value is written once after calibration....
Definition: hardware_interface.h:186
pr2_hardware_interface::ProjectorState::ProjectorState
ProjectorState(uint8_t &A, uint8_t &B, uint8_t &I, uint8_t &M, uint8_t &L0, uint8_t &L1)
Definition: hardware_interface.h:326
pr2_hardware_interface::ActuatorState::max_effort_
double max_effort_
Absolute torque limit for actuator (derived from motor current limit). (in Nm)
Definition: hardware_interface.h:180
pr2_hardware_interface::HardwareInterface::getDigitalOut
DigitalOut * getDigitalOut(const std::string &name) const
Get a pointer to the digital I/O by name.
Definition: hardware_interface.h:496
pr2_hardware_interface::DigitalOutState
Definition: hardware_interface.h:284
pr2_hardware_interface::HardwareInterface::pressure_sensors_
PressureSensorMap pressure_sensors_
Definition: hardware_interface.h:444
pr2_hardware_interface::ProjectorState::timestamp_us_
uint32_t timestamp_us_
Definition: hardware_interface.h:344
pr2_hardware_interface::HardwareInterface::ft_sensors_
ForceTorqueMap ft_sensors_
Definition: hardware_interface.h:446
pr2_hardware_interface::AnalogIn::name_
std::string name_
Definition: hardware_interface.h:389


pr2_hardware_interface
Author(s): Eric Berger berger@willowgarage.com
autogenerated on Mon Mar 6 2023 03:49:16