Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <iostream>
00038 #include <cstdio>
00039 #include <cstring>
00040 #include <cstdlib>
00041
00042 #include <amtec_base.h>
00043 #include <amtec_commands.h>
00044 #include <amtec_settings.h>
00045 #include <amtec_io.h>
00046
00047 using namespace std;
00048
00049 void printModuleState(unsigned int state)
00050 {
00051 if(state&STATE_HOME_OK) std::cout << "STATE_HOME_OK" << std::endl;
00052 if(state&STATE_HALTED) std::cout << "STATE_HALTED" << std::endl;
00053 if(state&STATE_SWR) std::cout << "STATE_SWR" << std::endl;
00054 if(state&STATE_SW1) std::cout << "STATE_SW1" << std::endl;
00055 if(state&STATE_SW2) std::cout << "STATE_SW2" << std::endl;
00056 if(state&STATE_BRAKEACTIVE) std::cout << "STATE_BRAKEACTIVE" << std::endl;
00057 if(state&STATE_CURLIMIT) std::cout << "STATE_CURLIMIT" << std::endl;
00058 if(state&STATE_MOTION) std::cout << "STATE_MOTION" << std::endl;
00059 if(state&STATE_RAMP_ACC) std::cout << "STATE_RAMP_ACC" << std::endl;
00060 if(state&STATE_RAMP_STEADY) std::cout << "STATE_RAMP_STEADY" << std::endl;
00061 if(state&STATE_RAMP_DEC) std::cout << "STATE_RAMP_DEC" << std::endl;
00062 if(state&STATE_RAMP_END) std::cout << "STATE_RAMP_END" << std::endl;
00063 if(state&STATE_INPROGRESS) std::cout << "STATE_INPROGRESS" << std::endl;
00064 if(state&STATE_FULLBUFFER) std::cout << "STATE_FULLBUFFER" << std::endl;
00065 if(state&STATE_ERROR) std::cout << "STATE_ERROR" << std::endl;
00066 if(state&STATE_POWERFAULT) std::cout << "STATE_POWERFAULT" << std::endl;
00067 if(state&STATE_TOW_ERROR) std::cout << "STATE_TOW_ERROR" << std::endl;
00068 if(state&STATE_COMM_ERROR) std::cout << "STATE_COMM_ERROR" << std::endl;
00069 if(state&STATE_POW_VOLT_ERR) std::cout << "STATE_POW_VOLT_ERR" << std::endl;
00070 if(state&STATE_POW_FET_TEMP) std::cout << "STATE_POW_FET_TEMP" << std::endl;
00071 if(state&STATE_POW_INTEGRALERR) std::cout << "STATE_POW_INTEGRALERR" << std::endl;
00072 if(state&STATE_BEYOND_HARD) std::cout << "STATE_BEYOND_HARD" << std::endl;
00073 if(state&STATE_BEYOND_SOFT) std::cout << "STATE_BEYOND_SOFT" << std::endl;
00074 if(state&STATE_LOGIC_VOLT) std::cout << "STATE_LOGIC_VOLT" << std::endl;
00075 }
00076
00077 int main(int argc, char **argv)
00078 {
00079 if (argc != 3)
00080 {
00081 printf("Usage: test_amtec DEVICE BAUD_RATE\n");
00082 return 1;
00083 }
00084 std::string amtec_dev = argv[1];
00085 int amtec_baudrate = atoi(argv[2]);
00086
00087 amtec_powercube_p amtec;
00088 amtec = amtecInitialize();
00089 strcpy(amtec->dev.ttyport, amtec_dev.c_str());
00090 amtec->dev.baud = amtec_baudrate;
00091
00092 if (amtecDeviceConnectPort(&amtec->dev) < 0) {
00093 printf("Unable to connect amtec at %s\n", amtec->dev.ttyport);
00094 return -1;
00095 }
00096
00097 printf("Resetting device\n");
00098 if(!amtecReset(&amtec->dev, amtec->pan.id)) {
00099 printf("Unable to connect to pan module\n");
00100 return -1;
00101 }
00102 if(!amtecReset(&amtec->dev, amtec->tilt.id)) {
00103 printf("Unable to connect tilt module\n");
00104 return -1;
00105 }
00106
00107 printf("Retrieving module state\n");
00108 unsigned int pan_serial = amtecGetDefCubeSerial(&amtec->dev, amtec->pan.id);
00109 unsigned short pan_version = amtecGetDefCubeVersion(&amtec->dev, amtec->pan.id);
00110 unsigned int pan_state = amtecGetCubeState(&amtec->dev, amtec->pan.id);
00111
00112 std::cout << "pan serial " << pan_serial << std::endl;
00113 std::cout << "pan version " << pan_version << std::endl;
00114 std::cout << "pan state: " << std::endl;
00115 printModuleState(pan_state);
00116
00117 unsigned int tilt_serial = amtecGetDefCubeSerial(&amtec->dev, amtec->tilt.id);
00118 unsigned short tilt_version = amtecGetDefCubeVersion(&amtec->dev, amtec->tilt.id);
00119 unsigned int tilt_state = amtecGetCubeState(&amtec->dev, amtec->pan.id);
00120
00121 std::cout << "tilt serial " << tilt_serial << std::endl;
00122 std::cout << "tilt version " << tilt_version << std::endl;
00123 std::cout << "tilt state: " << std::endl;
00124 printModuleState(tilt_state);
00125
00126 float pan = amtecGetActPos(&amtec->dev, amtec->pan.id);
00127 float tilt = amtecGetActPos(&amtec->dev, amtec->tilt.id);
00128 printf("pan %f tilt %f\n",pan,tilt);
00129
00130 printf("Homing device\n");
00131 amtecHome(&amtec->dev, amtec->pan.id);
00132 amtecHome(&amtec->dev, amtec->tilt.id);
00133 printf("Done\n");
00134
00135 return 0;
00136 }
00137