ljacklm_wrapper.cpp
Go to the documentation of this file.
00001 
00030 #include "maggie_labjack_drivers/ljacklm_wrapper.h"
00031 
00033 
00034 long LjacklmWrapper::config()
00035 {
00036     long error = 0;
00037     char errors[50];
00038 
00039     // D0 to 1 for not activate the watchdog, rest to 0
00040     long stateD = 0x0001;
00041     // output state of IO2 and IO3 to 0 for beginning in SLEEP state,
00042     // IO1 to 1 for not activate the emergency
00043     long stateIO = 0x0002;
00044 
00045     long trisD = CONFIG_D;
00046     long trisIO = CONFIG_IO;
00047 
00048     // when the watchdog is launched, the line goes to low
00049     error = writeDIOs(&trisD, &trisIO, &stateD, &stateIO);
00050     if (error != 0) {
00051         GetErrorString(error, errors);
00052         ROS_ERROR("[LJACKLM_WRAPPER] Error: %s", errors);
00053     }
00054 
00055     return error;
00056 }
00057 
00059 
00060 long LjacklmWrapper::reset()
00061 {
00062     long error = 0;
00063 
00064     long idlj = ID_LJ;
00065 
00066     error = Reset(&idlj);
00067 
00068     return error;
00069 }
00070 
00072 
00073 long LjacklmWrapper::readIO(long channel, long * state)
00074 {
00075     long error = 0;
00076 
00077     long idlj = ID_LJ;
00078 
00079     if (channel < 0 || channel > 3) {
00080         error = ERROR_PARAM;
00081         ROS_ERROR("[LJACKLM_WRAPPER] Error in readIO: channel out of range");
00082     }
00083     else {
00084         error = EDigitalIn(&idlj, DEMO_MODE, channel, 0, state);
00085     }
00086 
00087     return error;
00088 }
00089 
00091 
00092 long LjacklmWrapper::writeIO(long channel, long state)
00093 {
00094     long error = 0;
00095 
00096     long idlj = ID_LJ;
00097 
00098     if (channel < 0 || channel > 3) {
00099         error = ERROR_PARAM;
00100         ROS_ERROR("[LJACKLM_WRAPPER] Error in writeIO: channel out of range");
00101     }
00102     else {
00103         error = EDigitalOut(&idlj, DEMO_MODE, channel, 0, state);
00104         ROS_DEBUG("[LJACKLM_WRAPPER] Channel: %ld, State: %ld, Error: %ld\n", channel, state, error);
00105     }
00106 
00107     return error;
00108 }
00109 
00111 
00112 long LjacklmWrapper::readDIOs(long * stateD, long * stateIO)
00113 {
00114     long error = 0;
00115 
00116     long idlj = ID_LJ;
00117     long trisD = 0;     // necessary but not used
00118     long trisIO = 0;    // necessary but not used
00119     long outputD = 0;
00120 
00121     *stateD = *stateIO = 0;
00122 
00123     error = DigitalIO(&idlj, DEMO_MODE, &trisD, trisIO, stateD, stateIO, 0, &outputD);
00124 
00125     return error;
00126 }
00127 
00129 
00130 long LjacklmWrapper::writeDIOs(long * direcD, long * direcIO, long * stateD, long * stateIO)
00131 {
00132     long error = 0;
00133 
00134     long idlj = ID_LJ;
00135     long outputD = 0;   // necessary but not used
00136 
00137     if (*direcD > 0xFFFF
00138         || *direcD < 0x0
00139         || *stateD > 0xFFFF
00140         || *stateD < 0x0
00141         || *direcIO > 0xF
00142         || *direcIO < 0x0
00143         || *stateIO > 0xFFFF
00144         || *stateIO < 0x0) {
00145         error = ERROR_PARAM;
00146     }
00147     else {
00148         error = DigitalIO(&idlj, DEMO_MODE, direcD, *direcIO, stateD, stateIO, 1, &outputD);
00149     }
00150 
00151     return error;
00152 }
00153 
00155 
00156 long LjacklmWrapper::writeDIOsCONFIG(long * stateD, long * stateIO)
00157 {
00158     long error = 0;
00159 
00160     long idlj = ID_LJ;
00161     long trisD = CONFIG_D;
00162     long trisIO = CONFIG_IO;
00163     long outputD = 0;       // necessary but not used
00164 
00165     if (*stateD > 0xFFFF || *stateD < 0x0 || *stateIO > 0xFFFF || *stateIO < 0x0) {
00166         error = ERROR_PARAM;
00167     }
00168     else {
00169         error = DigitalIO(&idlj, DEMO_MODE, &trisD, trisIO, stateD, stateIO, 1, &outputD);
00170     }
00171 
00172     return error;
00173 }
00174 
00176 
00177 long LjacklmWrapper::readD(long channel, long * state)
00178 {
00179     long error = 0;
00180 
00181     long idlj = ID_LJ;
00182 
00183     if (channel < 0 || channel > 15) {
00184         error = ERROR_PARAM;
00185         ROS_ERROR("[LJACKLM_WRAPPER] Error in readD: channel out of range");
00186     }
00187     else {
00188         error = EDigitalIn(&idlj, DEMO_MODE, channel, 1, state);
00189     }
00190 
00191     return error;
00192 }
00193 
00195 
00196 long LjacklmWrapper::writeD(long channel, long state)
00197 {
00198     long error = 0;
00199 
00200     long idlj = ID_LJ;
00201 
00202     if (channel < 0 || channel > 15) {
00203         error = ERROR_PARAM;
00204         ROS_ERROR("[LJACKLM_WRAPPER] Error in writeD: channel out of range");
00205     }
00206     else {
00207         ROS_DEBUG("[LJACKLM_WRAPPER] channel=%ld , state=%ld\n", channel, state);
00208 
00209         error = EDigitalOut(&idlj, DEMO_MODE, channel, 1, state);
00210     }
00211 
00212     return error;
00213 }
00214 
00216 
00217 long LjacklmWrapper::writeDCONFIG(long channel, long state)
00218 {
00219     long error = 0;
00220 
00221     long idlj = ID_LJ;
00222     long stateD = 0, stateIO = 0, outputD = 0;
00223     long trisD = CONFIG_D;
00224     long trisIO = CONFIG_IO;
00225     long mask = 0x0001; // 0x0001 = 0000 0000 0000 0001
00226 
00227     if (channel < 0 || channel > 15) {
00228         error = ERROR_PARAM;
00229         ROS_ERROR("[LJACKLM_WRAPPER] Error in writeDCONFIG: channel out of range");
00230     }
00231     else {
00232         ROS_DEBUG("[LJACKLM_WRAPPER] channel=%ld, state=%ld\n", channel, state);
00233 
00234         mask <<= channel; // change the mask to point to the line we want to write
00235 
00236         error = DigitalIO(&idlj, DEMO_MODE, &trisD, trisIO, &stateD, &stateIO, 0, &outputD);
00237 
00238         if (state) {
00239             // write '1'
00240             stateD = stateD | mask;
00241         }
00242         else {
00243             // write '0'
00244             stateD = stateD & (~mask);
00245         }
00246 
00247         error = DigitalIO(&idlj, DEMO_MODE, &trisD, trisIO, &stateD, &stateIO, 1, &outputD);
00248     }
00249 
00250     return error;
00251 }
00252 
00254 
00255 long LjacklmWrapper::readAI(long channel, float * voltage)
00256 {
00257     long error = 0;
00258 
00259     long idlj = ID_LJ;
00260     long overVoltage = 0;
00261 
00262     if (channel >= 0 && channel <= 7) {
00263         error = EAnalogIn(&idlj, DEMO_MODE, channel, GAIN, &overVoltage, voltage);
00264     }
00265 
00266     return error;
00267 }
00268 
00270 
00271 long LjacklmWrapper::readAIs(long num_channels, long * channels, float * voltages)
00272 {
00273     long error = 0;
00274 
00275     long idlj = ID_LJ;
00276     long stateIO = 0;   // necessary but not used
00277     long updateIO = 0;  // do a reading
00278     long gains[4] = {0,
00279                      0,
00280                      0,
00281                      0};
00282     long disableCal = 0;
00283     long overVoltage;
00284 
00285     // check parameters
00286     if (num_channels != 1 && num_channels != 2 && num_channels != 4) {
00287         error = ERROR_PARAM;
00288         ROS_ERROR("[LJACKLM_WRAPPER] Error in readAIs: channel different to 1, 2, 4");
00289     }
00290     else {
00291         for (long i = 0; i < num_channels; i++) {
00292             if (channels[i] < 0 || channels[i] > 7) {
00293                 error = ERROR_PARAM;
00294                 ROS_ERROR("[LJACKLM_WRAPPER] Error in readAIs: channel out of range");
00295                 break;
00296             }
00297         }
00298     }
00299 
00300     if (!error) {
00301         // init array before using, necessary for AISample
00302         for (long i = 0; i < num_channels; i++) {
00303             voltages[i] = 0;
00304         }
00305 
00306         error = AISample(&idlj, DEMO_MODE, &stateIO, updateIO, 1, num_channels, channels, gains, disableCal,
00307                          &overVoltage, voltages);
00308 
00309         if (error) {
00310             ROS_ERROR("[LJACKLM_WRAPPER] Error in AISample:");
00311             ROS_ERROR("[LJACKLM_WRAPPER] AISample:");
00312         }
00313     }
00314 
00315     return error;
00316 }
00317 
00319 
00320 long LjacklmWrapper::readDifferentialAI(long channel, float * voltage)
00321 {
00322     long error = 0;
00323 
00324     long idlj = ID_LJ;
00325     long overVoltage = 0;
00326 
00327     if (channel >= 8 && channel <= 11) {
00328         error = EAnalogIn(&idlj, DEMO_MODE, channel, 1, &overVoltage, voltage);
00329     }
00330 
00331     return error;
00332 }
00333 
00335 
00336 long LjacklmWrapper::writeAO(int channel, float voltage)
00337 {
00338     long error = 0;
00339 
00340     long idlj = ID_LJ;
00341     float analogOut0 = -1.0, analogOut1 = -1.0;
00342 
00343     // check the channel
00344     if (channel == 0) {
00345         analogOut0 = voltage;
00346     }
00347     else if (channel == 1) {
00348         analogOut1 = voltage;
00349     }
00350     else if (channel == 2) {
00351         analogOut0 = analogOut1 = voltage;
00352     }
00353     else {
00354         error = ERROR_PARAM;
00355     }
00356 
00357     // check the voltage value
00358     if (voltage < 0.0 || voltage > 5.0) {
00359         error = ERROR_PARAM;
00360         ROS_ERROR("[LJACKLM_WRAPPER] Error in writeAO: voltage out of range");
00361     }
00362     else {
00363         error = EAnalogOut(&idlj, DEMO_MODE, analogOut0, analogOut1);
00364     }
00365 
00366     return error;
00367 }
00368 
00370 
00371 long LjacklmWrapper::writeAOs(float voltageAO0, float voltageAO1)
00372 {
00373     long error = 0;
00374 
00375     long idlj = ID_LJ;
00376 
00377     // check the correct voltages
00378     if (voltageAO0 < 0.0 || voltageAO0 > 5.0 || voltageAO1 < 0.0 || voltageAO1 > 5.0) {
00379         error = ERROR_PARAM;
00380     }
00381     else {
00382         error = EAnalogOut(&idlj, DEMO_MODE, voltageAO0, voltageAO1);
00383     }
00384 
00385     return error;
00386 }
00387 
00389 
00390 long LjacklmWrapper::enableWatchdog(long timeout, int activeD, long state)
00391 {
00392     long error = 0;
00393 
00394     long idlj = ID_LJ;
00395     long activeD0, activeD1, activeD8, stateD0, stateD1, stateD8;
00396     activeD0 = activeD1 = activeD8 = stateD0 = stateD1 = stateD8 = 0;
00397 
00398     if (timeout < 1 || timeout > 715 || state < 0 || (activeD != 0 && activeD != 1 && activeD != 8)) {
00399         error = ERROR_PARAM;
00400     }
00401     else {
00402         if (activeD == 0) {
00403             activeD0 = 1;
00404             stateD0 = state;
00405         }
00406         else if (activeD == 1) {
00407             activeD1 = 1;
00408             stateD1 = state;
00409         }
00410         // activeD = 8
00411         else {
00412             activeD8 = 1;
00413             stateD8 = state;
00414         }
00415 
00416         error = Watchdog(&idlj, DEMO_MODE, 1, timeout, 0, activeD0, activeD1, activeD8, stateD0, stateD1, stateD8);
00417     }
00418 
00419     return error;
00420 }
00421 
00423 
00424 long LjacklmWrapper::disableWatchdog(int activeD)
00425 {
00426     long error = 0;
00427 
00428     long idlj = ID_LJ;
00429     long timeout = 5; // a whatever value
00430     long activeD0, activeD1, activeD8, stateD0, stateD1, stateD8;
00431     activeD0 = activeD1 = activeD8 = stateD0 = stateD1 = stateD8 = 0;
00432 
00433     ROS_DEBUG("[LJACKLM_WRAPPER] timeout=%ld , activeD%d=%ld\n", timeout, activeD, stateD0);
00434 
00435     if (activeD != 0 && activeD != 1 && activeD != 8) {
00436         error = ERROR_PARAM;
00437     }
00438     else {
00439         if (activeD == 0) {
00440             activeD0 = 1;
00441         }
00442         else if (activeD == 1) {
00443             activeD1 = 1;
00444         }
00445         else {
00446             // activeD = 8
00447             activeD8 = 1;
00448         }
00449 
00450         error = Watchdog(&idlj, DEMO_MODE, 0, timeout, 0, activeD0, activeD1, activeD8, stateD0, stateD1, stateD8);
00451     }
00452 
00453     return error;
00454 }
00455 
00457 
00458 long LjacklmWrapper::writePulse(long pulse_level, long line, long pulse_time, long line_type)
00459 {
00460     long error = 0;
00461 
00462     // D lines
00463     if (line_type == 0) {
00464         if (line < 0 || line > 15 || pulse_time < 1 || pulse_time > 2000000) {
00465             error = ERROR_PARAM;
00466         }
00467         else {
00468             if (pulse_level > 0) {
00469                 if ((error = writeD(line, 0)) != 0)
00470                     return error;
00471                 if ((error = writeD(line, 1)) != 0)
00472                     return error;
00473                 usleep(pulse_time);
00474                 if ((error = writeD(line, 0)) != 0)
00475                     return error;
00476             }
00477             else { // pulse_level <= 0
00478                 if ((error = writeD(line, 1)) != 0)
00479                     return error;
00480                 if ((error = writeD(line, 0)) != 0)
00481                     return error;
00482                 usleep(pulse_time);
00483                 if ((error = writeD(line, 1)) != 0)
00484                     return error;
00485             }
00486         }
00487     }
00488     // IO lines
00489     else if (line_type == 1) {
00490         if (line < 0 || line > 3 || pulse_time < 1 || pulse_time > 2000000) {
00491             error = ERROR_PARAM;
00492         }
00493         else {
00494             if (pulse_level > 0) {
00495                 if ((error = writeIO(line, 0)) != 0)
00496                     return error;
00497                 if ((error = writeIO(line, 1)) != 0)
00498                     return error;
00499                 usleep(pulse_time);
00500                 if ((error = writeIO(line, 0)) != 0)
00501                     return error;
00502             }
00503             // pulse_level <= 0
00504             else {
00505                 if ((error = writeIO(line, 1)) != 0)
00506                     return error;
00507                 if ((error = writeIO(line, 0)) != 0)
00508                     return error;
00509                 usleep(pulse_time);
00510                 if ((error = writeIO(line, 1)) != 0)
00511                     return error;
00512             }
00513         }
00514     }
00515     else {
00516         error = ERROR_PARAM;
00517     }
00518 
00519     return error;
00520 }
00521 
00523 
00524 long LjacklmWrapper::readDirectionDs(long * directions)
00525 {
00526     long error = 0;
00527 
00528     long idlj = ID_LJ;
00529     long trisIO = 0;        // necessary but not used
00530     long outputD = 0;       // necessary but not used
00531     long stateD = 0;        // necessary but not used
00532     long stateIO = 0;       // necessary but not used
00533 
00534     *directions = 0;
00535 
00536     error = DigitalIO(&idlj, DEMO_MODE, directions, trisIO, &stateD, &stateIO, 0, &outputD);
00537 
00538     return error;
00539 }
00540 


maggie_labjack_drivers
Author(s): Raul Perula-Martinez
autogenerated on Mon Sep 14 2015 03:06:34