amtec_base.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2008, Robert Bosch LLC.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the Robert Bosch nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  *********************************************************************/
00036  
00037 #ifndef AMTEC_BASE_H
00038 #define AMTEC_BASE_H
00039 
00040 #ifdef __cplusplus
00041 extern "C" {
00042 #endif
00043 
00044 #include <stdio.h>
00045 #include <stdlib.h>
00046 #include <stdarg.h>
00047 #include <string.h>
00048 
00049 #define MAX_NAME_LENGTH                256
00050 #define MAX_COMMAND_LENGTH             256
00051 #define MAX_ACMD_SIZE                   48
00052 #define MAX_NUM_LOOPS                   10
00053 #define MAX_TIME_DELAY                 0.2
00054 #define MAX_STATUS_TIME                3.0
00055 
00056 #define EPSILON                     0.0001
00057 
00058 #define TIMEOUT                         -1
00059 #define WRONG                            0
00060 #define OK                               1
00061 
00062 
00063 #define INT8                             0
00064 #define UINT8                            1
00065 #define INT16                            2
00066 #define UINT16                           3
00067 #define INT32                            4
00068 #define UINT32                           5
00069 #define FLOAT                            6
00070 
00071 /*
00072  * Short state in Acknowledge
00073  */
00074 #define SHORT_NOT_OK                  0x01
00075 #define SHORT_SWR                     0x02
00076 #define SHORT_SW1                     0x04
00077 #define SHORT_SW2                     0x08
00078 #define SHORT_MOTION                  0x10
00079 #define SHORT_RAMP_END                0x20
00080 #define SHORT_INPROGRESS              0x40
00081 #define SHORT_FULLBUFFER              0x80
00082 
00083 /*
00084  * Motion modes
00085  */
00086 #define FRAMP_MODE                    0x04
00087 #define FSTEP_MODE                    0x06
00088 #define FVEL_MODE                     0x07
00089 #define FCUR_MODE                     0x08
00090 #define IRAMP_MODE                    0x09
00091 #define ISTEP_MODE                    0x0b
00092 #define IVEL_MODE                     0x0c
00093 #define ICUR_MODE                     0xd
00094 #define FCOSLOOP                      0x18
00095 #define FRAMPLOOP                     0x19
00096 
00097 /*
00098  * Module State
00099  */
00100 #define STATE_HOME_OK                 0x00000002
00101 #define STATE_HALTED                  0x00000004
00102 #define STATE_SWR                     0x00000040
00103 #define STATE_SW1                     0x00000080
00104 #define STATE_SW2                     0x00000100
00105 #define STATE_BRAKEACTIVE             0x00000200
00106 #define STATE_CURLIMIT                0x00000400
00107 #define STATE_MOTION                  0x00000800
00108 #define STATE_RAMP_ACC                0x00001000
00109 #define STATE_RAMP_STEADY             0x00002000
00110 #define STATE_RAMP_DEC                0x00004000
00111 #define STATE_RAMP_END                0x00008000
00112 #define STATE_INPROGRESS              0x00010000
00113 #define STATE_FULLBUFFER              0x00020000
00114 #define STATE_ERROR                   0x00000001
00115 #define STATE_POWERFAULT              0x00000008
00116 #define STATE_TOW_ERROR               0x00000010
00117 #define STATE_COMM_ERROR              0x00000020
00118 #define STATE_POW_VOLT_ERR            0x00040000
00119 #define STATE_POW_FET_TEMP            0x00080000
00120 #define STATE_POW_INTEGRALERR         0x00800000
00121 #define STATE_BEYOND_HARD             0x02000000
00122 #define STATE_BEYOND_SOFT             0x04000000
00123 #define STATE_LOGIC_VOLT              0x08000000
00124 
00125 /*
00126  * A frame is always starting with the character STX (02h) and finishes
00127  * with the character ETX (03h).
00128  */
00129 #define B_STX                         0x02
00130 #define B_ETX                         0x03
00131 /*
00132  * If these characters occur within the data stream they will be replaced using a
00133  * combination of two characters: DLE (10h) and (80h + character to replace). The character DLE
00134  * (10h) used in this case will thus be replaced in the same manner
00135  */
00136 #define B_DLE                         0x10
00137 #define B_ACK                         0x64
00138 
00139 /*
00140  * The data transfered first of all states the command to be processed by the module. These
00141  * commands are available:
00142  */
00143 #define CodeReset                     0x00 /* Clear error state */
00144 #define CodeHome                      0x01 /* Start Homing procedure */
00145 #define CodeHalt                      0x02 /* Stop immediately */
00146 #define CodeRecalcPIDParam            0x09 /* Recalculate the PID loop parameters */
00147 #define CodeSetExtended               0x08 /* Set parameter */
00148 #define CodeGetExtended               0x0a /* Fetch parameter */
00149 #define CodeSetMotion                 0x0b /* Set Motion command */
00150 #define CodeSetIStep                  0x0d /* Motion command in Step mode */
00151 #define CodeResetTime                 0x12 /* Reset internal clock to zero */
00152 
00153 /*
00154  * Parameter IDs
00155  */
00156 #define CodeDefHomeOffset             0x00
00157 #define CodeDefGearRatio              0x01
00158 #define CodeDefLinRatio               0x02
00159 #define CodeDefMinPos                 0x03
00160 #define CodeDefMaxPos                 0x04
00161 #define CodeDefMaxDeltaPos            0x05
00162 #define CodeDefMaxDeltaVel            0x06
00163 #define CodeDefTorqueRatio            0x07
00164 #define CodeDefCurRatio               0x08
00165 #define CodeDefMaxVel                 0x0a
00166 #define CodeDefMaxAcc                 0x0c
00167 #define CodeDefMaxCur                 0x0e
00168 #define CodeDefHomeVel                0x0f
00169 #define CodeDefHomeAcc                0x10
00170 #define CodeDefCubeSerial             0x1a
00171 #define CodeDefConfig                 0x1b
00172 #define CodeDefPulsesPerTurn          0x1c
00173 #define CodeDefCubeVersion            0x1d
00174 #define CodeDefServiceInterval        0x1e
00175 #define CodeDefBrakeTimeOut           0x1f
00176 #define CodeDefAddress                0x20
00177 #define CodeDefPrimBaud               0x22
00178 #define CodeDefScndBaud               0x23
00179 #define CodePosCount                  0x24
00180 #define CodeRefPosCount               0x25
00181 #define CodeDioSetup                  0x26
00182 #define CodeCubeState                 0x27
00183 #define CodeTargetPosInc              0x28
00184 #define CodeTargetVelInc              0x29
00185 #define CodeTargetAccInc              0x2a
00186 #define CodeStepInc                   0x2b
00187 
00188 #define CodeConfig                    0x39
00189 #define CodeActPos                    0x3c
00190 #define CodeActVel                    0x41
00191 #define CodeMinPos                    0x45
00192 #define CodeMaxPos                    0x46
00193 #define CodeMaxVel                    0x48
00194 #define CodeMaxAcc                    0x4a
00195 #define CodeMaxCur                    0x4c
00196 #define CodeCur                       0x4d
00197 #define CodeTargetVel                 0x4f
00198 #define CodeTargetAcc                 0x50
00199 #define CodeDefC0                     0x51
00200 #define CodeDefDamp                   0x52
00201 #define CodeDefA0                     0x53
00202 #define CodeActC0                     0x54
00203 #define CodeActDamp                   0x55
00204 #define CodeActA0                     0x56
00205 #define CodeDefBurnCount              0x57
00206 #define CodeSetup                     0x58
00207 #define CodeHomeOffset                0x59
00208 
00209 enum PARITY_TYPE   { N, E, O };
00210 
00211 typedef struct {
00212   char                       ttyport[MAX_NAME_LENGTH];
00213   int                        baud;
00214   enum PARITY_TYPE           parity;
00215   int                        fd;
00216   int                        databits;
00217   int                        stopbits;
00218   int                        hwf;
00219   int                        swf;
00220 } amtec_powercube_device_t, *amtec_powercube_device_p;
00221 
00222 typedef struct {
00223   double                     MinPos;
00224   double                     MaxPos;
00225   double                     MaxVel;
00226   double                     MaxAcc;
00227   double                     MaxCur;
00228   double                     TargetVel;
00229   double                     TargetAcc;
00230   int                        UseBreak;
00231 
00232   int                        C0;
00233   int                        Damp;
00234   int                        A0;
00235 } amtec_powercube_setting_t, *amtec_powercube_setting_p;
00236 
00237 typedef struct {
00238   int                        id;
00239   float                      DefHomeOffset;
00240   float                      DefGearRatio;
00241   float                      DefLinRatio;
00242   float                      DefMinPos;
00243   float                      DefMaxPos;
00244   float                      DefMaxDeltaPos;
00245   float                      DefMaxDeltaVel;
00246   float                      DefTorqueRatio;
00247   float                      DefCurRatio ;
00248   float                      DefMaxVel;
00249   float                      DefMaxAcc;
00250   float                      DefMaxCur;
00251   float                      DefHomeVel;
00252   float                      DefHomeAcc;
00253 
00254   unsigned int               DefCubeSerial;
00255   unsigned int               DefConfig;
00256   unsigned int               DefPulsesPerTurn;
00257   unsigned short             DefCubeVersion;
00258   unsigned short             DefServiceInterval;
00259   unsigned short             DefBrakeTimeOut;
00260   unsigned char              DefAddress;
00261   unsigned char              DefPrimBaud;
00262   unsigned char              DefScndBaud;
00263   int                        PosCount;
00264   int                        RefPosCount;
00265   unsigned int               DioSetup;
00266   unsigned int               CubeState;
00267   unsigned int               TargetPosInc;
00268   unsigned int               TargetVelInc;
00269   unsigned int               TargetAccInc;
00270   unsigned int               StepInc;
00271 
00272   double                     ActPos;
00273   double                     ActVel;
00274   double                     MinPos;
00275   double                     MaxPos;
00276   double                     MaxVel;
00277   double                     MaxAcc;
00278   double                     TargetVel;
00279   double                     TargetAcc;
00280   double                     MaxCur;
00281   unsigned long              Config;
00282   int                        UseBreak;
00283 
00284   int                        ActC0;
00285   int                        ActDamp;
00286   int                        ActA0;
00287 } amtec_powercube_params_t, *amtec_powercube_params_p;
00288 
00289 typedef struct {
00290   float                      pan;
00291   float                      tilt;
00292   struct timeval             time;
00293 } amtec_powercube_pos_t, *amtec_powercube_pos_p;
00294 
00295 typedef struct {
00296   amtec_powercube_device_t   dev;
00297   amtec_powercube_params_t   pan;
00298   amtec_powercube_setting_t  panset;
00299   amtec_powercube_params_t   tilt;
00300   amtec_powercube_setting_t  tiltset;
00301 } amtec_powercube_t, *amtec_powercube_p;
00302 
00303 amtec_powercube_p amtecInitialize();
00304 
00305 void amtecClear(amtec_powercube_p powercube);
00306 
00307 void amtecPrintInformation(amtec_powercube_p powercube);
00308 
00309 void amtecPrintParams(amtec_powercube_params_p params);
00310 
00311 #ifdef __cplusplus
00312 }
00313 #endif
00314 
00315 #endif
00316 


amtec
Author(s): Charles DuHadway, Benjamin Pitzer (Maintained by Benjamin Pitzer)
autogenerated on Mon Oct 6 2014 10:10:36