Devices¶
More devices can be seamlessly added in other packages.
Ampere Meter¶
Ampere Meter¶
Device type: Input device.
Message type: cras_msgs/ElectricCurrentStamped.
Pin requirements: One raw analog pin. Read required.
YAML config¶
topic: 'TOPIC NAME' # Topic for the measurements. Set to empty string to disable topic publication.
type: electronic_io.AmpereMeter
queue_size: 1 # Optional. Topic queue size.
latch: True # Optional. Topic latching status.
frame_id: 'frame' # Optional. frame_id to be used in the messages; if not set, it is taken from the readings.
variance: 1.0 # Optional, default 0.0. The reported variance of the measurements.
input_pin:
pin: 'Current1' # Raw analog pin directly reporting the electrical current in A.
-
class
electronic_io.devices.ampere_meter.
AmpereMeter
(name, config, io_board)¶ Bases:
electronic_io.device.InputDevice
Ampere meter device. Publishes messages of type cras_msgs/ElectricCurrentStamped.
-
add_read_request
(req)¶ Modify the passed read request to collect all information needed by this device.
Parameters: req (ReadRequest) – The request to modify.
-
create_message
(value, header)¶ Convert the given value to a ROS message that can be published by this device.
Parameters: - value – The value to convert.
- header (
std_msgs/Header
) – Header to be used in the message (if needed).
Returns: The ROS message.
Return type:
-
get_value
(readings)¶ Extract value of this device from the given pin readings.
Parameters: readings (Readings) – Values of pins. Returns: The value.
-
Battery¶
Battery¶
Device type: Input device.
Message type: sensor_msgs/BatteryState.
- Pin requirements: This is a composite device working on other devices (one or more Voltmeter devices; an optional
- Ampere meter device). It can also read a raw analog pin with battery percentage and a digital pin telling whether the battery is present.
YAML config¶
topic: 'TOPIC NAME' # Topic for the measurements. Set to empty string to disable topic publication.
type: electronic_io.Battery
queue_size: 1 # Optional. Topic queue size.
latch: True # Optional. Topic latching status.
frame_id: 'frame' # Optional. frame_id to be used in the messages; if not set, it is taken from the readings.
# overall_voltmeter and cell_voltmeters are optional, but at least one of them has to be specified.
overall_voltmeter: voltmeter_overall # Optional. Voltmeter device. If missing, the overall voltage will be summed
# from cells.
cell_voltmeters: # Optional. Measurements of individual cells.
- voltmeter_cell1 # Voltmeter device.
ampere_meter: ampere_meter_1 # Optional. AmpereMeter device.
percentage_pin: # Optional. Raw analog pin with percentage in 0.0 - 1.0 or 0.0 - 100.0.
pin: percentage_1
present_pin: # Optional. Digital pin. Tells whether the battery is present.
pin: input_1
-
class
electronic_io.devices.battery.
Battery
(name, config, io_board, devices)¶ Bases:
electronic_io.device.InputDevice
,electronic_io.device.MetaDevice
Battery device. Publishes messages of type sensor_msgs/BatteryState.
-
add_read_request
(req)¶ Modify the passed read request to collect all information needed by this device.
Parameters: req (ReadRequest) – The request to modify.
-
create_message
(value, header)¶ Convert the given value to a ROS message that can be published by this device.
Parameters: - value – The value to convert.
- header (
std_msgs/Header
) – Header to be used in the message (if needed).
Returns: The ROS message.
Return type:
-
get_value
(readings)¶ Extract value of this device from the given pin readings.
Parameters: readings (Readings) – Values of pins. Returns: The value.
-
Dimmable LED¶
LED light with configurable brightness¶
Device type: Output device with readback.
Set output service type: cras_msgs/SetBrightness.
Readback messages type: cras_msgs/BrightnessStamped.
Pin requirements: One raw analog pin with PWM + one optional digital pin for turning on/off of the light.
YAML config¶
topic: 'TOPIC NAME' # Base topic for readback and the services. Set to empty string to disable topics and services.
type: electronic_io.DimmableLED
queue_size: 1 # Optional. Readback topic queue size.
latch: True # Optional. Readback topic latching status.
frame_id: 'frame' # Optional. frame_id to be used in the messages; if not set, it is taken from the readings.
pwm_pin:
pin: 'PWM3' # Raw analog PWM pin (with 0.0 - 1.0 values). Write required, readback supported.
enable_pin: # Optional. This pin turns the light on/off without the need to specify PWM value.
pin: 'Output3' # Digital pin. Write required, readback supported.
inverted: False # Optional. Whether to invert values of the pin.
-
class
electronic_io.devices.dimmable_led.
DimmableLED
(name, config, io_board)¶ Bases:
electronic_io.device.OutputDevice
Dimmable LED light controlled using cras_msgs/SetBrightness service.
-
set_value_cb
(request)¶ Callback called by the ~/set service.
Parameters: request – The setter service request.
-
-
class
electronic_io.devices.dimmable_led.
DimmableLEDReadback
(name, config, io_board)¶ Bases:
electronic_io.device.InputDevice
Readback of a dimmable LED. Can also be used standalone without the write part. Publishes cras_msgs/BrightnessStamped readback messages.
-
add_read_request
(req)¶ Modify the passed read request to collect all information needed by this device.
Parameters: req (ReadRequest) – The request to modify.
-
create_message
(value, header)¶ Convert the given value to a ROS message that can be published by this device.
Parameters: - value – The value to convert.
- header (
std_msgs/Header
) – Header to be used in the message (if needed).
Returns: The ROS message.
Return type:
-
get_value
(readings)¶ Extract value of this device from the given pin readings.
Parameters: readings (Readings) – Values of pins. Returns: The value.
-
Output group¶
Group of Output Devices¶
Device type: Output device without readback.
Set output service type: Same as the service of the grouped devices.
Pin requirements: Does not use any pins itself.
This is a meta-device that offers easy synchronized control of multiple output devices of the same type.
YAML config¶
topic: 'TOPIC NAME' # Base topic for readback and the services. Set to empty string to disable topics and services.
type: electronic_io.OutputGroup
devices: # List of grouped devices. All devices must be defined in the same config and must have the same type.
- device1 # Name of the device.
-
class
electronic_io.devices.output_group.
OutputGroup
(name, config, io_board, devices)¶ Bases:
electronic_io.device.OutputDevice
,electronic_io.device.MetaDevice
A group of output devices
-
set_value_cb
(request)¶ Callback called by the ~/set service.
Parameters: request – The setter service request.
-
Power Switch¶
Power Switch (Relay)¶
Device type: Output device with readback.
Set output service type: std_srvs/SetBool.
Readback messages type: cras_msgs/PowerSwitchStateStamped.
Pin requirements: At least one digital output pin (readback supported).
YAML config¶
topic: 'TOPIC NAME' # Base topic for readback and the services. Set to empty string to disable topics and services.
type: electronic_io.DimmableLED
queue_size: 1 # Optional. Readback topic queue size.
latch: True # Optional. Readback topic latching status.
frame_id: 'frame' # Optional. frame_id to be used in the messages; if not set, it is taken from the readings.
output_pins: # One or more output pins.
- pin: 'C5' # Digital pin. Write required, readback supported.
inverted: False # Whether to invert values of the pin.
readback_pin: # Optional readback pin. If not specified, only one output pin is specified and it supports readback,
# the readback is automatically provided.
pin: 'C5' # Digital pin. Readback required.
inverted: False # Whether to invert values of the pin.
-
class
electronic_io.devices.power_switch.
PowerSwitch
(name, config, io_board)¶ Bases:
electronic_io.device.DigitalOutputDevice
Power switch controlled using std_srvs/SetBool service.
-
class
electronic_io.devices.power_switch.
PowerSwitchReadback
(name, config, io_board)¶ Bases:
electronic_io.device.InputDevice
Readback of a power switch. Can also be used standalone without the write part. Publishes cras_msgs/PowerSwitchStateStamped readback messages.
-
add_read_request
(req)¶ Modify the passed read request to collect all information needed by this device.
Parameters: req (ReadRequest) – The request to modify.
-
create_message
(value, header)¶ Convert the given value to a ROS message that can be published by this device.
Parameters: - value – The value to convert.
- header (
std_msgs/Header
) – Header to be used in the message (if needed).
Returns: The ROS message.
Return type:
-
get_value
(readings)¶ Extract value of this device from the given pin readings.
Parameters: readings (Readings) – Values of pins. Returns: The value.
-
Thermometer¶
Thermometer¶
Device type: Input device.
Message type: sensor_msgs/Temperature.
Pin requirements: One raw analog pin. Read required.
YAML config¶
topic: 'TOPIC NAME' # Topic for the measurements. Set to empty string to disable topic publication.
type: electronic_io.Thermometer
queue_size: 1 # Optional. Topic queue size.
latch: True # Optional. Topic latching status.
frame_id: 'frame' # Optional. frame_id to be used in the messages; if not set, it is taken from the readings.
variance: 1.0 # Optional, default 0.0. the reported variance of the measurements; beware this is the variance in
# Kelvins, so if you measure in degrees Fahrenheit, you need to scale the variance accordingly.
input_pin:
pin: 'Temp1' # Raw analog pin directly reporting the temperature. If the unit reported by the pin is K, F or °F,
# the value is automatically converted to °C.
-
class
electronic_io.devices.thermometer.
Thermometer
(name, config, io_board)¶ Bases:
electronic_io.device.InputDevice
Thermometer device. Publishes sensor_msgs/Temperature messages.
-
add_read_request
(req)¶ Modify the passed read request to collect all information needed by this device.
Parameters: req (ReadRequest) – The request to modify.
-
create_message
(value, header)¶ Convert the given value to a ROS message that can be published by this device.
Parameters: - value – The value to convert.
- header (
std_msgs/Header
) – Header to be used in the message (if needed).
Returns: The ROS message.
Return type:
-
get_value
(readings)¶ Extract value of this device from the given pin readings.
Parameters: readings (Readings) – Values of pins. Returns: The value.
-
Voltmeter¶
Voltmeter¶
Device type: Input device.
Message type: cras_msgs/VoltageStamped.
Pin requirements: One raw analog pin. Read required.
YAML config¶
topic: 'TOPIC NAME' # Topic for the measurements. Set to empty string to disable topic publication.
type: electronic_io.Voltmeter
queue_size: 1 # Optional. Topic queue size.
latch: True # Optional. Topic latching status.
frame_id: 'frame' # Optional. frame_id to be used in the messages; if not set, it is taken from the readings.
variance: 1.0 # Optional, default 0.0. The reported variance of the measurements.
input_pin:
pin: 'Voltage1' # Raw analog pin directly reporting the voltage in V.
-
class
electronic_io.devices.voltmeter.
Voltmeter
(name, config, io_board)¶ Bases:
electronic_io.device.InputDevice
Voltmeter device. Publishes messages of type cras_msgs/VoltageStamped.
-
add_read_request
(req)¶ Modify the passed read request to collect all information needed by this device.
Parameters: req (ReadRequest) – The request to modify.
-
create_message
(value, header)¶ Convert the given value to a ROS message that can be published by this device.
Parameters: - value – The value to convert.
- header (
std_msgs/Header
) – Header to be used in the message (if needed).
Returns: The ROS message.
Return type:
-
get_value
(readings)¶ Extract value of this device from the given pin readings.
Parameters: readings (Readings) – Values of pins. Returns: The value.
-