Go to the documentation of this file.00001 
00021 #include <cp1616/cp1616_io_controller.h>
00022 #include <cp1616/cp1616_io_controller_callbacks.h>
00023 #include <cp1616/cp1616_io_device.h>
00024 #include <cp1616/cp1616_io_device_callbacks.h>
00025 
00026 #define IO_CONTROLLER_MODE
00027 
00028 
00029 int main(int argc, char **argv)
00030 {
00031   ros::init(argc,argv, "cp1616");
00032   ros::NodeHandle nh;
00033   ros::NodeHandle priv_nh_;
00034 
00035 #ifdef IO_CONTROLLER_MODE
00036 
00037   cp1616::Cp1616IOController *cp1616_object;
00038   cp1616_object = cp1616::Cp1616IOController::getControllerInstance();
00039 
00040   
00041   cp1616_object->addOutputModule(4,4116);
00042   cp1616_object->addOutputModule(4,4120);
00043   cp1616_object->addOutputModule(4,4124);
00044   cp1616_object->addOutputModule(16,4128);
00045 
00046   cp1616_object->addInputModule(4,4132);
00047   cp1616_object->addInputModule(4,4136);
00048   cp1616_object->addInputModule(4,4140);
00049   cp1616_object->addInputModule(16,4144);
00050 
00051   
00052   cp1616_object->init();
00053 
00054   if(cp1616_object->getCpReady() != 0)
00055   {
00056     PNIO_UINT8 do_value = 1;
00057     PNIO_UINT32 error_code = PNIO_OK;
00058 
00059     
00060     for(int i = 0; i < 20; i++)
00061     {
00062       for(int j = 0; j < 7; j++)
00063       {
00064         
00065         do_value = do_value << 1;
00066         cp1616_object->output_module_data_[0][0] = do_value;
00067 
00068         
00069         cp1616_object->printOutputData(0);
00070         cp1616_object->printOutputData(1);
00071         cp1616_object->printOutputData(2);
00072         cp1616_object->printOutputData(3);
00073         cp1616_object->printInputData(0);
00074         cp1616_object->printInputData(1);
00075         cp1616_object->printInputData(2);
00076         cp1616_object->printInputData(3);
00077 
00078         error_code = cp1616_object->updateCyclicOutputData();
00079         if(error_code != PNIO_OK)
00080         {
00081           ROS_INFO("Not able to update output data: Error 0x%x\n", (int)error_code);
00082         }
00083         usleep(100000);
00084       }
00085       for(int j = 0; j < 7; j++)
00086       {
00087         
00088         do_value = do_value >> 1;
00089         cp1616_object->output_module_data_[0][0] = do_value;
00090 
00091         
00092         cp1616_object->printOutputData(0);
00093         cp1616_object->printOutputData(1);
00094         cp1616_object->printOutputData(2);
00095         cp1616_object->printOutputData(3);
00096         cp1616_object->printInputData(0);
00097         cp1616_object->printInputData(1);
00098         cp1616_object->printInputData(2);
00099         cp1616_object->printInputData(3);
00100 
00101         error_code = cp1616_object->updateCyclicOutputData();
00102         if(error_code != PNIO_OK)
00103         {
00104           ROS_INFO("Not able to update input data: Error 0x%x\n", (int)error_code);
00105         }
00106         usleep(100000);
00107       }
00108     }
00109  }
00110   
00111   cp1616_object->uinit();
00112 
00113 #endif
00114 
00115 #ifdef IO_DEVICE_MODE
00116 
00117   cp1616::Cp1616IODevice *cp1616_object;
00118   cp1616_object = cp1616::Cp1616IODevice::getDeviceInstance();
00119 
00120   int error_code;
00121 
00122   
00123   cp1616_object->configureDeviceData();
00124   error_code = cp1616_object->init();
00125   error_code = cp1616_object->addApi();
00126   error_code = cp1616_object->addModSubMod();
00127   error_code = cp1616_object->startOperation();
00128 
00129   if(error_code == PNIO_OK) 
00130   {
00131     int slot = 2;
00132     int subslot = 1;
00133     int triangle = 0;
00134     bool raise_flag = true;
00135 
00136     for(int i = 0; i < 30; i++)
00137     {
00138       
00139       cp1616_object->updateCyclicOutputData();
00140 
00141       
00142       if((raise_flag == true) && (triangle < 100))
00143         triangle++;
00144       if((raise_flag == false) && (triangle > 0))
00145         triangle--;
00146 
00147       if(triangle == 100) raise_flag = false;
00148       if(triangle == 0)   raise_flag = true;
00149 
00150       
00151       cp1616_object->input_data_[slot][subslot][0] = triangle;
00152 
00153       
00154       cp1616_object->updateCyclicInputData();
00155 
00156       usleep(100000);
00157     }
00158   }
00159   else
00160       ROS_ERROR("CP not initialized properly: Error 0x%x", (int)error_code);
00161 
00162   
00163   cp1616_object->stopOperation();
00164   cp1616_object->removeModSubMod();
00165   cp1616_object->removeApi();
00166   cp1616_object->uinit();
00167 
00168 #endif
00169 
00170     return(EXIT_SUCCESS);
00171 }