$search
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 #include "amtec_base.h" 00038 #include "amtec_io.h" 00039 #include "amtec_commands.h" 00040 #include "amtec_conversion.h" 00041 #include "amtec_settings.h" 00042 00043 void AMTEC_set_settings(amtec_powercube_device_p dev, amtec_powercube_setting_p settings, amtec_powercube_params_p params) 00044 { 00045 if(params->MinPos != settings->MinPos) { 00046 amtecSetMinPos(dev, params->id, settings->MinPos); 00047 params->MinPos = settings->MinPos; 00048 } 00049 if(params->MaxPos != settings->MaxPos) { 00050 amtecSetMaxPos(dev, params->id, settings->MaxPos); 00051 params->MaxPos = settings->MaxPos; 00052 } 00053 if(params->MaxAcc != settings->MaxAcc) { 00054 amtecSetMaxAcc(dev, params->id, settings->MaxAcc); 00055 params->MaxAcc = settings->MaxAcc; 00056 } 00057 if(params->MaxVel != settings->MaxVel) { 00058 amtecSetMaxVel(dev, params->id, settings->MaxVel); 00059 params->MaxVel = settings->MaxVel; 00060 } 00061 if(params->TargetAcc != settings->TargetAcc) { 00062 amtecSetTargetAcc(dev, params->id, settings->TargetAcc); 00063 params->TargetAcc = settings->TargetAcc; 00064 } 00065 if(params->TargetVel != settings->TargetVel) { 00066 amtecSetTargetVel(dev, params->id, settings->TargetVel); 00067 params->TargetVel = settings->TargetVel; 00068 } 00069 if(params->MaxCur != settings->MaxCur) { 00070 amtecSetMaxCur(dev, params->id, settings->MaxCur); 00071 params->MaxCur = settings->MaxCur; 00072 } 00073 00074 if (settings->C0 != 0 && params->ActC0 != settings->C0) { 00075 amtecSetActC0(dev, params->id, settings->C0); 00076 } 00077 if (settings->Damp != 0 && params->ActDamp != settings->Damp) { 00078 amtecSetActDamp(dev, params->id, settings->Damp); 00079 } 00080 if (settings->A0 != 0 && params->ActA0 != settings->A0) { 00081 amtecSetActA0(dev, params->id, settings->A0); 00082 } 00083 00084 amtecRecalcPIDParam(dev, params->id); 00085 /* 00086 if(settings->UseBreak) { 00087 params->Config = amtecGetConfig(dev, params->id); 00088 params->Config = params->Config | 8; 00089 amtecSetConfig(dev, params->id, params->Config); 00090 }*/ 00091 } 00092 00093 void amtecSetSettings(amtec_powercube_p powercube) 00094 { 00095 AMTEC_set_settings(&powercube->dev, &powercube->panset, &powercube->pan); 00096 AMTEC_set_settings(&powercube->dev, &powercube->tiltset, &powercube->tilt); 00097 } 00098 00099 void AMTEC_get_params(amtec_powercube_device_p dev, amtec_powercube_params_p params) 00100 { 00101 params->DefHomeOffset = amtecGetDefHomeOffset(dev, params->id); 00102 params->DefGearRatio = amtecGetDefGearRatio(dev, params->id); 00103 params->DefLinRatio = amtecGetDefLinRatio(dev, params->id); 00104 params->DefMinPos = amtecGetDefMinPos(dev, params->id); 00105 params->DefMaxPos = amtecGetDefMaxPos(dev, params->id); 00106 params->DefMaxDeltaVel = amtecGetDefMaxDeltaVel(dev, params->id); 00107 params->DefTorqueRatio = amtecGetDefTorqueRatio(dev, params->id); 00108 params->DefCurRatio = amtecGetDefCurRatio(dev, params->id); 00109 params->DefMaxVel = amtecGetDefMaxVel(dev, params->id); 00110 params->DefMaxAcc = amtecGetDefMaxAcc(dev, params->id); 00111 params->DefMaxCur = amtecGetDefMaxCur(dev, params->id); 00112 params->DefHomeVel = amtecGetDefHomeVel(dev, params->id); 00113 params->DefHomeAcc = amtecGetDefHomeAcc(dev, params->id); 00114 00115 params->DefCubeSerial = amtecGetDefCubeSerial(dev, params->id); 00116 params->DefConfig = amtecGetDefConfig(dev, params->id); 00117 params->DefPulsesPerTurn = amtecGetDefPulsesPerTurn(dev, params->id); 00118 params->DefCubeVersion = amtecGetDefCubeVersion(dev, params->id); 00119 params->DefServiceInterval = amtecGetDefServiceInterval(dev, params->id); 00120 params->DefBrakeTimeOut = amtecGetDefBrakeTimeOut(dev, params->id); 00121 params->DefAddress = amtecGetDefAddress(dev, params->id); 00122 params->DefPrimBaud = amtecGetDefPrimBaud(dev, params->id); 00123 //params->DefScndBaud = amtecGetDefScndBaud(dev, params->id); 00124 params->PosCount = amtecGetPosCount(dev, params->id); 00125 params->RefPosCount = amtecGetRefPosCount(dev, params->id); 00126 params->DioSetup = amtecGetDioSetup(dev, params->id); 00127 params->CubeState = amtecGetCubeState(dev, params->id); 00128 params->TargetPosInc = amtecGetTargetPosInc(dev, params->id); 00129 params->TargetVelInc = amtecGetTargetVelInc(dev, params->id); 00130 params->TargetAccInc = amtecGetTargetAccInc(dev, params->id); 00131 params->StepInc = amtecGetStepInc(dev, params->id); 00132 00133 00134 params->ActPos = amtecGetActPos(dev, params->id); 00135 params->ActVel = amtecGetActVel(dev, params->id); 00136 params->MinPos = amtecGetMinPos(dev, params->id); 00137 params->MaxPos = amtecGetMaxPos(dev, params->id); 00138 params->MaxVel = amtecGetMaxVel(dev, params->id); 00139 params->MaxAcc = amtecGetMaxAcc(dev, params->id); 00140 // params->TargetVel = amtecGetTargetVel(dev, params->id); 00141 // params->TargetAcc = amtecGetTargetAcc(dev, params->id); 00142 params->MaxCur = amtecGetMaxCur(dev, params->id); 00143 params->Config = amtecGetConfig(dev, params->id); 00144 params->UseBreak = (int)(((params->Config)>>3)&1); 00145 00146 params->ActC0 = amtecGetActC0(dev, params->id); 00147 params->ActDamp = amtecGetActDamp(dev, params->id); 00148 params->ActA0 = amtecGetActA0(dev, params->id); 00149 } 00150 00151 void amtecGetParams(amtec_powercube_p powercube) 00152 { 00153 AMTEC_get_params(&powercube->dev, &powercube->pan); 00154 AMTEC_get_params(&powercube->dev, &powercube->tilt); 00155 } 00156 00157 void PRINT_CubeState(unsigned long state) 00158 { 00159 int i; 00160 unsigned long v = state; 00161 00162 for(i = 0; i < 32; i++) 00163 fprintf(stderr, " %s", (v>>i & 1)==1?"+":"-"); 00164 fprintf(stderr, "\r"); 00165 } 00166 00167 00168 00169 00170