00001
00002
00003
00004
00005
00006
00007
00008
00018 #include <assert.h>
00019 #include <errno.h>
00020 #include <stdlib.h>
00021 #include <unistd.h>
00022 #include <string.h>
00023 #include <fcntl.h>
00024 #include <termios.h>
00025
00026 #include <ros/ros.h>
00027
00028 #include "dev8x.h"
00029
00030 dev8x::dev8x(const char *pn)
00031 {
00032 state = UNREADY;
00033
00034
00035 strncpy(port_name, pn, sizeof(port_name));
00036 have_tty = (strcmp(port_name, "/dev/null") != 0);
00037 DBG("dev8x port: %s", port_name);
00038
00039
00040 sim_relays = 0;
00041 for (int i = 0; i < IOADR_MAX_INPUTS; i++)
00042 sim_port[i] = 0;
00043 }
00044
00045 int dev8x::setup()
00046 {
00047 DBG("setup()");
00048
00049 fd = open(port_name, O_RDWR | O_NOCTTY);
00050 if (fd < 0) {
00051 ROS_WARN("Couldn't open %s", port_name);
00052 return -1;
00053 }
00054
00055 relay_wait_time = 0.0;
00056 state = READY;
00057
00058
00059 DBG("Configuring the ioadr8x.");
00060 configure_port(B19200 | CS8, 0);
00061 DBG("DONE: Configuring the ioadr8x.");
00062
00063 return 0;
00064 }
00065
00066 int dev8x::shutdown()
00067 {
00068 DBG("shutdown()");
00069 int rc = close(fd);
00070 state = UNREADY;
00071 return rc;
00072 }
00073
00074 int dev8x::configure_port (int cflags, int iflags)
00075 {
00076 assert(state == READY);
00077
00078 struct termios newtio;
00079 memset(&newtio, 0, sizeof(newtio));
00080
00081
00082
00083
00084
00085
00086
00087
00088
00089 newtio.c_cflag = cflags | CLOCAL | CREAD;
00090
00091
00092
00093
00094
00095
00096
00097 newtio.c_iflag = iflags | IGNPAR;
00098
00099
00100 newtio.c_oflag = 0;
00101 newtio.c_lflag = 0;
00102
00103
00104
00105
00106
00107
00108 newtio.c_cc[VTIME] = 0;
00109 newtio.c_cc[VMIN] = 1;
00110
00111
00112
00113
00114 tcflush(fd, TCIOFLUSH);
00115
00116 return tcsetattr(fd,TCSANOW,&newtio);
00117 }
00118
00119
00120 int dev8x::query_relays(uint8_t *relays)
00121 {
00122 if (relays_busy())
00123 return EBUSY;
00124
00125
00126 buffer[0] = 254;
00127 buffer[1] = 14;
00128 buffer[2] = 24;
00129 DBG("query_relays: writing command.");
00130 int res=0;
00131 res=write(fd, buffer, 3);
00132
00133
00134 DBG("query_relays: reading result.");
00135 int rc = read(fd, buffer, 1);
00136 if (rc == 1)
00137 *relays = buffer[0];
00138 else if (have_tty == false)
00139 *relays = sim_relays;
00140 else
00141 {
00142 if (rc == 0) rc = EBUSY;
00143 ROS_WARN("ioadr8x read error: %s", strerror(rc));
00144 return rc;
00145 }
00146
00147 DBG("relay status: 0x%02x", *relays);
00148 return 0;
00149 }
00150
00151 int dev8x::read_8bit_port(int ch, int *data)
00152 {
00153 if (relays_busy())
00154 return EBUSY;
00155
00156
00157 buffer[0] = 254;
00158 buffer[1] = 6;
00159 buffer[2] = ch;
00160 int res=0;
00161 res=write(fd, buffer, 3);
00162
00163 int rc = read(fd, buffer, 1);
00164 if (rc == 1)
00165 *data = buffer[0];
00166 else if (have_tty == false)
00167 *data = sim_sawtooth(ch, 1<<8);
00168 else
00169 {
00170 ROS_WARN("ioadr8x read error: ch = %d, rc = %d", ch, rc);
00171 if (rc < 0)
00172 return errno;
00173 else
00174 return EIO;
00175 }
00176
00177 DBG("port %d returns 0x%02x", ch, *data);
00178 return 0;
00179 }
00180
00181 int dev8x::read_10bit_port(int ch, int *data)
00182 {
00183 if (relays_busy())
00184 return EBUSY;
00185
00186
00187 assert(ch >= 3);
00188
00189
00190 buffer[0] = 254;
00191 buffer[1] = 6;
00192 buffer[2] = 8 + ch - 3;
00193 int res=0;
00194 res=write(fd, buffer, 3);
00195
00196 int rc = read(fd, &buffer[1], 1);
00197 if (rc != 1 && have_tty)
00198 {
00199 ROS_WARN("ioadr8x 10-bit read error: ch = %d, rc = %d", ch, rc);
00200 if (rc < 0)
00201 return errno;
00202 else
00203 return EIO;
00204 }
00205
00206 rc = read(fd, buffer, 1);
00207 if (rc == 1)
00208 *data = (buffer[1]<<8) | buffer[0];
00209 else if (have_tty == false)
00210 *data = sim_sawtooth(ch, 1<<10);
00211 else
00212 {
00213 ROS_WARN("ioadr8x 10-bit read error: ch = %d, rc = %d", ch, rc);
00214 if (rc < 0)
00215 return errno;
00216 else
00217 return EIO;
00218 }
00219
00220 DBG("port %d returns 0x%04x", ch, *data);
00221 return 0;
00222 }
00223
00224
00225 bool dev8x::relays_busy(void)
00226 {
00227 if (state == RELAY_WAIT)
00228 {
00229 double now = ros::Time::now().toSec();
00230 if ((now - relay_wait_time) > MIN_RELAY_WAIT)
00231 {
00232 state = READY;
00233 DBG("accessing relays (time %.6f)", now);
00234 }
00235 else
00236 {
00237 DBG("tried to access relays too soon after setting them"
00238 " (time %.6f)", now);
00239 return true;
00240 }
00241 }
00242 return false;
00243 }
00244
00245
00246 int dev8x::set_relays(uint8_t bitmask)
00247 {
00248 if (relays_busy())
00249 return EBUSY;
00250
00251 DBG("setting relays to 0x%02x", bitmask);
00252
00253 if (have_tty == false)
00254 {
00255 sim_relays = bitmask;
00256 return 0;
00257 }
00258
00259 assert(state == READY);
00260 buffer[0] = 254;
00261 buffer[1] = 14;
00262 buffer[2] = 40;
00263 buffer[3] = bitmask;
00264 int rc = write(fd, buffer, 4);
00265 if (rc == 4)
00266 {
00267
00268
00269
00270
00271
00272 relay_wait_time = ros::Time::now().toSec();
00273 state = RELAY_WAIT;
00274 return 0;
00275 }
00276 else
00277 {
00278 if (rc < 0)
00279 rc = errno;
00280 else
00281 rc = EIO;
00282 ROS_WARN("write error: %s", strerror(rc));
00283 return rc;
00284 }
00285 }
00286
00287
00288
00289
00290
00291
00292 uint16_t dev8x::sim_sawtooth(int ch, uint16_t limit)
00293 {
00294 uint16_t data = sim_port[ch]++;
00295 if (sim_port[ch] >= limit)
00296 sim_port[ch] = 0;
00297 return data;
00298 }