ctrlcmd2decition.cpp 5.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166
  1. #include "ctrlcmd2decition.h"
  2. #include <iostream>
  3. #include <math.h>
  4. ctrlcmd2decition::ctrlcmd2decition()
  5. {
  6. mpLT = new LookupTable();
  7. ModuleFun xFunctrlcmd = std::bind(&ctrlcmd2decition::ListenCtrlCmd,this,std::placeholders::_1,std::placeholders::_2,std::placeholders::_3,std::placeholders::_4,std::placeholders::_5);
  8. mpactrlcmd = iv::modulecomm::RegisterRecvPlus("ctrlcmd",xFunctrlcmd);
  9. mpadecision = iv::modulecomm::RegisterSend("deciton",1000,1);
  10. ModuleFun xFunGPSIMU = std::bind(&ctrlcmd2decition::ListenGPSIMU,this,std::placeholders::_1,std::placeholders::_2,std::placeholders::_3,std::placeholders::_4,std::placeholders::_5);
  11. mpagpsimu = iv::modulecomm::RegisterRecvPlus("hcp2_gpsimu",xFunGPSIMU);
  12. }
  13. ctrlcmd2decition::~ctrlcmd2decition()
  14. {
  15. iv::modulecomm::Unregister(mpagpsimu);
  16. iv::modulecomm::Unregister(mpadecision);
  17. iv::modulecomm::Unregister(mpactrlcmd);
  18. delete mpLT;
  19. }
  20. void ctrlcmd2decition::ListenGPSIMU(const char *strdata, const unsigned int nSize, const unsigned int index, const QDateTime *dt, const char *strmemname)
  21. {
  22. (void)index;
  23. (void)dt;
  24. (void)strmemname;
  25. iv::gps::gpsimu xgpsimu;
  26. if(xgpsimu.ParseFromArray(strdata,nSize))
  27. {
  28. mfVelNow = sqrt(pow(xgpsimu.ve(),2) + pow(xgpsimu.vn(),2));
  29. }
  30. else
  31. {
  32. std::cout<<" ctrlcmd2decition::ListenGPSIMU Parse Fail ." <<std::endl;
  33. }
  34. }
  35. void ctrlcmd2decition::ListenCtrlCmd(const char *strdata, const unsigned int nSize, const unsigned int index, const QDateTime *dt, const char *strmemname)
  36. {
  37. (void)index;
  38. (void)dt;
  39. (void)strmemname;
  40. iv::autoware::autowarectrlcmd xctrlcmd;
  41. if(!xctrlcmd.ParseFromArray(strdata,nSize))
  42. {
  43. std::cout<<" ctrlcmd2decition::ListenCtrlCmd Parse Fail"<<std::endl;
  44. return;
  45. }
  46. iv::brain::decition xdecition;
  47. double facc = 0;
  48. double ftorque = 0;
  49. double fbrake = 0;
  50. double fwheelangle = 0;
  51. std::cout<<" cmd acc: "<<xctrlcmd.linear_acceleration()<<std::endl;
  52. if(xctrlcmd.linear_velocity() > 1.0)
  53. {
  54. if(xctrlcmd.linear_velocity()>mfVelNow)
  55. {
  56. if(xctrlcmd.linear_velocity()>(mfVelNow + 0.1))
  57. {
  58. if(xctrlcmd.linear_velocity()>(mfVelNow + 0.3))
  59. {
  60. facc =0.3+ 1.0* (xctrlcmd.linear_velocity() -mfVelNow)/xctrlcmd.linear_velocity() ;
  61. }
  62. else
  63. facc =1.6 * (xctrlcmd.linear_velocity() -mfVelNow)/xctrlcmd.linear_velocity() ;
  64. }
  65. else
  66. {
  67. facc = 0.0;
  68. }
  69. }
  70. else
  71. {
  72. if(xctrlcmd.linear_velocity()>(mfVelNow-0.3))
  73. {
  74. facc = 0.0;
  75. }
  76. else
  77. {
  78. facc = -1.5;
  79. }
  80. }
  81. }
  82. else
  83. {
  84. if(xctrlcmd.linear_velocity()>mfVelNow)
  85. {
  86. facc = 1.0;
  87. }
  88. else
  89. {
  90. facc = -1.0;
  91. }
  92. }
  93. facc = xctrlcmd.linear_acceleration();
  94. if(mpLT->IsINterpolationOK())
  95. {
  96. mpLT->GetTorqueBrake(xctrlcmd.linear_velocity()*3.6,facc,ftorque,fbrake);
  97. }
  98. else
  99. {
  100. double fVehWeight = 1800;
  101. double fg = 9.8;
  102. double fRollForce = 50;
  103. const double fRatio = 2.5;
  104. double fNeed = fRollForce + fVehWeight*facc;
  105. ftorque = fNeed/fRatio;
  106. fbrake = 0;
  107. if(ftorque<0)
  108. {
  109. fbrake = facc;
  110. ftorque = 0;
  111. }
  112. }
  113. // facc = xctrlcmd.linear_acceleration();
  114. fwheelangle = xctrlcmd.steering_angle() * (180.0/M_PI) * 15.0;
  115. if(fwheelangle>430)fwheelangle = 430;
  116. if(fwheelangle<-430)fwheelangle = -430;
  117. std::cout<<" acc: "<<facc<<" wheel: "<<fwheelangle<<std::endl;
  118. xdecition.set_accelerator(facc);
  119. xdecition.set_brake(fbrake);
  120. xdecition.set_leftlamp(false);
  121. xdecition.set_rightlamp(false);
  122. xdecition.set_speed(xctrlcmd.linear_velocity() * 3.6);
  123. xdecition.set_wheelangle(fwheelangle);
  124. xdecition.set_wheelspeed(300);
  125. xdecition.set_torque(ftorque);
  126. xdecition.set_mode(1);
  127. xdecition.set_gear(1);
  128. xdecition.set_handbrake(0);
  129. xdecition.set_grade(1);
  130. xdecition.set_engine(0);
  131. xdecition.set_brakelamp(false);
  132. xdecition.set_ttc(15);
  133. // xdecition.set_air_enable(decition->air_enable);
  134. // xdecition.set_air_temp(decition->air_temp);
  135. // xdecition.set_air_mode(decition->air_mode);
  136. // xdecition.set_wind_level(decition->wind_level);
  137. xdecition.set_roof_light(0);
  138. xdecition.set_home_light(0);
  139. // xdecition.set_air_worktime(decition->air_worktime);
  140. // xdecition.set_air_offtime(decition->air_offtime);
  141. // xdecition.set_air_on(decition->air_on);
  142. xdecition.set_door(0);
  143. xdecition.set_dippedlight(0);
  144. int nbytesize = (int)xdecition.ByteSize();
  145. std::shared_ptr<char> pstr_ptr = std::shared_ptr<char>(new char[nbytesize]);
  146. if(!xdecition.SerializeToArray(pstr_ptr.get(),nbytesize))
  147. {
  148. std::cout<<" ctrlcmd2decition::ListenCtrlCmd Serialize Fail. "<<std::endl;
  149. return;
  150. }
  151. iv::modulecomm::ModuleSendMsg(mpadecision,pstr_ptr.get(),nbytesize);
  152. }