62 #define _CRT_SECURE_NO_WARNINGS
65 #ifndef _USE_MATH_DEFINES // to ensure that M_PI is defined
66 #define _USE_MATH_DEFINES
120 double angleInRadFromSickOrg = 0.0;
121 double angleInRadToRosCompensated = 0.0;
127 angleInRadFromSickOrg = -angleInRadFromRos + M_PI;
132 angleInRadFromSickOrg = angleInRadFromRos + M_PI/2.0;
135 double angleInRadFromSickCompensated = compensateAngleInRad(angleInRadFromSickOrg);
142 angleInRadToRosCompensated = -angleInRadFromSickCompensated + M_PI;
147 angleInRadToRosCompensated = angleInRadFromSickCompensated - M_PI/2.0;
149 return(angleInRadToRosCompensated);
158 double deg2radFactor = 0.01745329252;
165 double angleCompInRad = angleInRad - sign * deg2radFactor * amplCorr * sin(angleInRad + sign * phaseCorrInRad)-sign * offsetCorrInRad;
166 return(angleCompInRad);
182 double angleCompInDeg;
183 double deg2radFactor = 0.01745329252;
184 double angleRawInRad = deg2radFactor * angleInDeg;
185 double phaseCorrInRad= deg2radFactor * phaseCorrInDeg;
186 angleCompInDeg = angleInDeg - sign * amplCorr * sin(angleRawInRad + sign * phaseCorrInRad) - sign * offsetCorrInDeg;
187 return(angleCompInDeg);
197 std::stringstream ss(replyStr);
199 std::vector<std::string> cont;
202 while (std::getline(ss, token, delim))
204 cont.push_back(token);
210 std::string
s =
"fffefffe";
211 int x = std::stoul(
s,
nullptr, 16);
219 int32_t phase10000th;
220 int32_t offset10000th;
223 if (cont.size() == 5)
225 unsigned long helperArr[3] = {0};
226 for (
int i = 0; i < 3; i++)
228 char ch = cont [2+i][0];
229 if ((ch ==
'+') || (ch ==
'-'))
231 sscanf(cont[2+i].c_str(),
"%ld", &(helperArr[i]));
235 helperArr[i] = std::stoul(cont[2+i],
nullptr, 16);
241 ampl10000th = (int32_t)((int16_t)(0xFFFF & helperArr[0]));
242 phase10000th = (int32_t)(0xFFFFFFFF & helperArr[1]);
243 offset10000th = (int32_t)(int16_t)(0xFFFF & helperArr[2]);
247 ampl10000th = (int32_t)(0xFFFFFFFF & helperArr[0]);
248 phase10000th = (int32_t)(0xFFFFFFFF & helperArr[1]);
249 offset10000th = (int32_t)(0xFFFFFFFF & helperArr[2]);
254 amplCorr = 1/10000.0 * ampl10000th;
255 phaseCorrInDeg = 1/10000.0 * phase10000th;
256 offsetCorrInDeg = 1/10000.0 * offset10000th;
258 offsetCorrInRad = offsetCorrInDeg/180.0 * M_PI;
259 phaseCorrInRad = phaseCorrInDeg/180.0 * M_PI;
277 int sLen = (int)replyVec.size();
278 assert((sLen == 40) || (sLen == 36));
294 int offset = sLen - payLoadLen - 1;
295 assert(replyVec[offset-1] == 0x20);
297 for (
int i = 8; i < sLen - 1; i++)
301 stmp += (char)replyVec[i];
306 sprintf(szTmp,
"%02X", replyVec[i]);
310 int posCutArr[2] = {4,8};
317 if (relCnt < payLoadLen)
319 for (
int k = 0; k < 2; k++)
321 if (posCutArr[k] == relCnt)
332 for (
int i = 0; i < replyVec.size(); i++)
334 stmp += (char)replyVec[i];
337 parseAsciiReply(stmp.c_str());
344 char szDummy[1024] = {0};
346 char szLidarFamily[255] = { 0 };
350 if (useNegSign ==
true)
352 strcpy(szLidarFamily,
"NAV3xx");
356 strcpy(szLidarFamily,
"NAV210/NAV245");
359 sprintf(szDummy,
"Formula allowed for: %-20s Angle[comp.] = Angle[Raw] %c %8.6lf * sin(Angle[Raw] %c %8.6lf [deg]) %c %8.6lf",
361 szLidarFamily, useNegSign ?
'+' :
'-', amplCorr, useNegSign ?
'-' :
'+', phaseCorrInDeg, useNegSign ?
'+' :
'-', offsetCorrInDeg);
372 std::vector<unsigned char> testVec;
374 std::string
s = string(
"sRA MCAngleCompSin ");
376 for (
int iLoop = 0; iLoop < 2; iLoop++)
380 bool bFlag = (iLoop == 0) ?
false :
true;
387 unsigned char preFix[8] = {0x02,0x02,0x02,0x02,0x00,0x00,0x00,27+4};
388 for (
int i = 0; i < 8; i++)
390 testVec.push_back(preFix[i]);
393 unsigned char dataArr[] = {0x00,0x00,0x07,0x65,0xff,0xfc,0xc9,0xb9,0xff,0xff,0xff,0x0b,0xFF};
394 for (
int i = 0; i <
s.length(); i++)
396 testVec.push_back(
s[i]);
398 for (
int i = 0; i <
sizeof(dataArr)/
sizeof(dataArr[0]); i++)
400 testVec.push_back(dataArr[i]);
406 unsigned char preFix[8] = {0x02,0x02,0x02,0x02,0x00,0x00,0x00,27};
407 for (
int i = 0; i < 8; i++)
409 testVec.push_back(preFix[i]);
411 for (
int i = 0; i <
s.length(); i++)
413 testVec.push_back(
s[i]);
415 unsigned char dataArr[] = {0x03, 0x37, 0x00, 0x1d, 0x8e, 0x8d, 0x00, 0xe7, 0x87};
416 for (
int i = 0; i <
sizeof(dataArr)/
sizeof(dataArr[0]); i++)
418 testVec.push_back(dataArr[i]);
437 s =
"sRA MCAngleCompSin 765 FFFCC9B9 FFFFFF0B";
438 for (
int i = 0; i <
s.length(); i++)
440 testVec.push_back(
s[i]);
445 FILE *fout = fopen(
"angle_compensation_debug.csv",
"w");
447 fprintf(fout,
"Input ;Output ;Correction\n");
448 for (
int i =0; i <= 359; i++)
450 double rawAngle = (double)i;
453 double checkAngle = compRadAngle/M_PI*180.0;
454 fprintf(fout,
"%10.6lf;%10.6lf;%10.6lf\n", rawAngle, compAngle, compAngle - rawAngle);