NCD IOADR8x multipurpose I/O board driver. More...
#include <ros/ros.h>
#include <art_msgs/ArtHertz.h>
#include <art/conversions.h>
#include <art_msgs/Shifter.h>
#include <art_msgs/IOadrCommand.h>
#include <art_msgs/IOadrState.h>
#include "dev8x.h"
Go to the source code of this file.
Classes | |
class | IOadr |
struct | IOadr::poll_parms_t |
Functions | |
IOadr::poll_parms_t * | LookupInput (const char *name) |
int | main (int argc, char **argv) |
Variables | |
static IOadr::poll_parms_t | poll_parms_table [] |
static const uint8_t | relay_value_ [5] = {0x00, 0x02, 0x04, 0x08, 0x10} |
NCD IOADR8x multipurpose I/O board driver.
This driver provides an interface to a National Control Devices IOADR8x hybrid relay and A/D controller board. This hybrid device provides eight relays and five analog to digital converters. The driver publishes their current values and handles commands to set the relays.
Our vehicle currently has two IOADR8x boards. Each is controlled by a separate ROS node. The node name determines the input and output messages:
Sets the state of a relay. The "id" is a bit number (0 to 7) for the relay. If the "voltage" is close to 0.0, the corresponding relay will be set off, otherwise it is set on.
Definition in file ioadr.cc.
IOadr::poll_parms_t* LookupInput | ( | const char * | name | ) |
IOadr::poll_parms_t poll_parms_table[] [static] |
{ {"AnalogA", &IOadr::poll_Analog_8bit, 3, 0}, {"AnalogA(10bit)", &IOadr::poll_Analog_10bit, 3, 0}, {"AnalogB", &IOadr::poll_Analog_8bit, 4, 1}, {"AnalogB(10bit)", &IOadr::poll_Analog_10bit, 4, 1}, {"AnalogC", &IOadr::poll_Analog_8bit, 5, 2}, {"AnalogC(10bit)", &IOadr::poll_Analog_10bit, 5, 2}, {"DigitalB", &IOadr::poll_Digital, 1, -1}, {"ShifterInd", &IOadr::poll_ShifterInd, 1, -1}, {"", NULL, -1, -1}, {NULL, NULL, -1, -1}, }
const uint8_t relay_value_[5] = {0x00, 0x02, 0x04, 0x08, 0x10} [static] |