Go to the documentation of this file.
35 #ifndef HARDWARE_INTERFACE_H
36 #define HARDWARE_INTERFACE_H
43 #include <geometry_msgs/Vector3.h>
44 #include <geometry_msgs/Wrench.h>
199 std::vector<geometry_msgs::Vector3>
samples_;
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) {}
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) {}
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_) {}
351 std::vector<double>
state_;
374 typedef std::map<std::string, Actuator*>
ActuatorMap;
381 typedef std::map<std::string, CustomHW*>
CustomHWMap;
425 ActuatorMap::const_iterator it =
actuators_.find(name);
426 return it !=
actuators_.end() ? it->second : NULL;
455 ForceTorqueMap::const_iterator it =
ft_sensors_.find(name);
475 ProjectorMap::const_iterator it =
projectors_.find(name);
485 AnalogInMap::const_iterator it =
analog_ins_.find(name);
495 CustomHWMap::const_iterator it =
custom_hws_.find(name);
505 std::pair<ActuatorMap::iterator, bool> p;
516 std::pair<PressureSensorMap::iterator, bool> p;
527 std::pair<AccelerometerMap::iterator, bool> p;
538 std::pair<ForceTorqueMap::iterator, bool> p;
539 p =
ft_sensors_.insert(ForceTorqueMap::value_type(forcetorque->
name_, forcetorque));
549 std::pair<DigitalOutMap::iterator, bool> p;
550 p =
digital_outs_.insert(DigitalOutMap::value_type(digital_out->name_, digital_out));
560 std::pair<ProjectorMap::iterator, bool> p;
561 p =
projectors_.insert(ProjectorMap::value_type(projector->name_, projector));
571 std::pair<AnalogInMap::iterator, bool> p;
572 p =
analog_ins_.insert(AnalogInMap::value_type(analog_in->name_, analog_in));
582 std::pair<CustomHWMap::iterator, bool> p;
583 p =
custom_hws_.insert(CustomHWMap::value_type(custom_hw->name_, custom_hw));
bool halted_
indicates if the motor is halted. A motor can be halted because of voltage or communication problems
bool rising_timestamp_valid_
std::map< std::string, ForceTorque * > ForceTorqueMap
std::map< std::string, CustomHW * > CustomHWMap
uint32_t rising_timestamp_us_
ProjectorCommand(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)
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...
ProjectorCommand command_
bool addActuator(Actuator *actuator)
Add an actuator to the hardware interface.
ros::Time current_time_
The time at which the commands were sent to the hardware.
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)
ForceTorque * getForceTorque(const std::string &name) const
Get a pointer to the FT sensor by name.
Projector * getProjector(const std::string &name) const
Get a pointer to the projector by name.
double encoder_velocity_
The velocity measured in encoder ticks per second.
double last_commanded_effort_
The torque requested in the previous ActuatorCommand (in Nm)
bool good_
A vector of samples taken from force/torque sensor since the last iteration of the control loop (olde...
int range_
The range of the values to be returned (range of 0 means within +/- 2g, 1 means within +/-4g,...
PressureSensorCommand command_
uint32_t falling_timestamp_us_
double velocity_
The velocity in radians per second.
Projector(DigitalOut &A, DigitalOut &B, DigitalOut &I, DigitalOut &M, DigitalOut &L0, DigitalOut &L1)
DigitalOutMap digital_outs_
int device_id_
Position in EtherCAT chain.
AnalogIn * getAnalogIn(const std::string &name) const
Get a pointer to the analog-in device by name.
AccelerometerCommand()
Enums for possible accelerometer bandwidth settings.
int bandwidth_
Accelerometer bandwidth setting. Value is passed directly to Bosch accelerometer (BMA 150)....
double max_current_
Current limit (Amps). Minimum of board and LED limits.
DigitalOutCommand command_
bool falling_timestamp_valid_
std::map< std::string, Actuator * > ActuatorMap
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?
double last_commanded_current_
bool addAccelerometer(Accelerometer *accelerometer)
Add an accelerometer to the hardware interface.
double last_executed_current_
The actual current requested after safety limits were enforced (in amps)
PressureSensorState state_
std::vector< double > state_
PressureSensor * getPressureSensor(const std::string &name) const
Get a pointer to the pressure sensor by name.
std::map< std::string, AnalogIn * > AnalogInMap
ros::Duration sample_timestamp_
double last_measured_current_
AccelerometerMap accelerometers_
Accelerometer * getAccelerometer(const std::string &name) const
Get a pointer to the accelerometer by name.
std::map< std::string, Projector * > ProjectorMap
std::vector< geometry_msgs::Wrench > samples_
std::map< std::string, Accelerometer * > AccelerometerMap
double position_
The position of the motor (in radians)
std::string frame_id_
Frame id of accelerometer.
bool enable_
Enable this actuator.
std::map< std::string, DigitalOut * > DigitalOutMap
std::vector< uint16_t > data_
A vector of 22 pressure readings from each sensor.
bool addDigitalOut(DigitalOut *digital_out)
Add an digital I/O to the hardware interface.
bool calibration_rising_edge_valid_
Is the last_callibration_rising_edge_ field valid?
ForceTorqueCommand command_
double effort_
Force to apply (in Nm)
double last_executed_current_
AccelerometerState state_
bool addAnalogIn(AnalogIn *analog_in)
Add an analog-in device to the hardware interface.
AccelerometerCommand command_
double last_measured_current_
The measured current (in amps)
bool addForceTorque(ForceTorque *forcetorque)
Add a FT sensor to the hardware interface.
double motor_voltage_
Motor voltage (in volts)
bool addCustomHW(CustomHW *custom_hw)
Add a Custom Hardware device to the hardware interface.
bool calibration_reading_
the value of the last calibration reading: low (false) or high (true)
std::map< std::string, PressureSensor * > PressureSensorMap
bool addPressureSensor(PressureSensor *sensor)
Add an pressure sensor to the hardware interface.
double last_calibration_rising_edge_
The position of the motor the last time the calibration switch went from low to high.
double last_calibration_falling_edge_
The position of the motor the last time the calibration switch went from high to low.
bool is_enabled_
Enable status.
Actuator * getActuator(const std::string &name) const
Get a pointer to the actuator by name.
bool halt_on_error_
If halt_on_error_ is true, the driver with halt motors when an there is an error is detected....
int encoder_count_
The number of ticks as reported by the encoder.
bool addProjector(Projector *projector)
Add an projector to the hardware interface.
int num_encoder_errors_
The number of invalid encoder signal transitions.
double zero_offset_
A bias applied to the position value when reported. This value is written once after calibration....
ProjectorState(uint8_t &A, uint8_t &B, uint8_t &I, uint8_t &M, uint8_t &L0, uint8_t &L1)
double max_effort_
Absolute torque limit for actuator (derived from motor current limit). (in Nm)
DigitalOut * getDigitalOut(const std::string &name) const
Get a pointer to the digital I/O by name.
PressureSensorMap pressure_sensors_
ForceTorqueMap ft_sensors_
pr2_hardware_interface
Author(s): Eric Berger berger@willowgarage.com
autogenerated on Mon Mar 6 2023 03:49:16