AGV_controller.cpp 8.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324
  1. #include <webots/Robot.hpp>
  2. #include <webots/Motor.hpp>
  3. #include <webots/PositionSensor.hpp>
  4. #include <webots/GPS.hpp>
  5. #include <webots/Gyro.hpp>
  6. #include <webots/InertialUnit.hpp>
  7. #include "emqx-client/mqttmsg.h"
  8. #include "emqx-client/paho_client.h"
  9. #include <unistd.h>
  10. #include <chrono>
  11. #include <random>
  12. #include "timedlockdata.hpp"
  13. // All the webots classes are defined in the "webots" namespace
  14. using namespace webots;
  15. Paho_client* client_= nullptr;
  16. TimedLockData<NavMessage::ToAgvCmd> g_speed;
  17. void SpeedChangeCallback(std::string topic,int QOS,MqttMsg& msg,void* context)
  18. {
  19. NavMessage::ToAgvCmd speed;
  20. msg.toProtoMessage(speed);
  21. g_speed.reset(speed,0.3);
  22. }
  23. double generae_random(std::default_random_engine& generator,double mean,double sigma)
  24. {
  25. std::normal_distribution<double> distribution(mean, sigma);
  26. return distribution(generator);
  27. }
  28. bool init_mqtt(std::string ip,int port,std::string nodeId,std::string subtopic)
  29. {
  30. if(client_!= nullptr)
  31. {
  32. client_->disconnect();
  33. delete client_;
  34. }
  35. client_=new Paho_client(nodeId);
  36. bool ret= client_->connect(ip,port);
  37. if(ret)
  38. {
  39. while(!client_->isconnected()) usleep(1000);
  40. client_->subcribe(subtopic,1,SpeedChangeCallback, nullptr);
  41. }
  42. return ret;
  43. }
  44. void Rotating(double wmg,double w,double l,
  45. double& R1,double& R2,double& R3,double& R4,
  46. double& L1,double& L2,double& L3,double& L4)
  47. {
  48. double theta=atan(l/w);
  49. R1=(-theta);
  50. R2=(theta);
  51. R3=(theta);
  52. R4=(-theta);
  53. double velocity=wmg*sqrt(w*w+l*l);
  54. L1=(-velocity);
  55. L2=(velocity);
  56. L3=(-velocity);
  57. L4=(velocity);
  58. }
  59. void Vrtical(double velocity,double wmg,double w,double l,double& R1,double& R2,double& R3,double& R4,
  60. double& L1,double& L2,double& L3,double& L4) {
  61. if (fabs(wmg) < 0.0001) {
  62. R1 = R2 = R3 = R4 = 0;
  63. L1 = L2 = L3 = L4 = velocity;
  64. printf("virtical111 R1-R4:%.5f %.5f %.5f %.5f L1-L4:%.5f %.5f %.5f %.5f \n",
  65. R1,R2,R3,R4,L1,L2,L3,L4);
  66. } else {//有角速度
  67. double base = pow(velocity / wmg, 2) - (l * l / 4);
  68. //满足运动方程
  69. if (base >= 0.0001) {
  70. double BaseR = sqrt(base) - w / 2;
  71. if (BaseR < 0.05)
  72. BaseR = 0.05;
  73. //printf("BaseR : %f \n",BaseR);
  74. if (BaseR > 0) {
  75. if (wmg * velocity >= 0) {
  76. R1 = atan(l / BaseR);
  77. R2 = atan(l / (BaseR + w));
  78. L3 = BaseR * wmg;
  79. L4 = (BaseR + w) * wmg;
  80. R3 = 0;
  81. R4 = 0;
  82. L1 = L3 / cos(R1);
  83. L2 = L4 / cos(R2);
  84. } else {
  85. R1 = -atan(l / (BaseR + w));
  86. R2 = -atan(l / BaseR);
  87. L3 = -(BaseR + w) * wmg;
  88. L4 = -BaseR * wmg;
  89. R3 = 0;
  90. R4 = 0;
  91. L1 = L3 / cos(R1);
  92. L2 = L4 / cos(R2);
  93. }
  94. printf("virtical222 R1-R4:%.5f %.5f %.5f %.5f L1-L4:%.5f %.5f %.5f %.5f \n",
  95. R1,R2,R3,R4,L1,L2,L3,L4);
  96. }
  97. }
  98. }
  99. }
  100. void Horizontal(double velocity,double wmg,double w,double l,double& R1,double& R2,double& R3,double& R4,
  101. double& L1,double& L2,double& L3,double& L4)
  102. {
  103. Vrtical(velocity,wmg,w,l,R3,R1,R4,R2,L3,L1,L4,L2);
  104. if (fabs(wmg) < 0.0001) {
  105. R1 = -M_PI / 2.0;
  106. R2 = M_PI / 2.0;
  107. R3 = M_PI / 2.0;
  108. R4 = -M_PI / 2.0;
  109. L1 = -velocity;
  110. L2 = velocity;
  111. L3 = velocity;
  112. L4 = -velocity;
  113. }else{
  114. R1-=M_PI/2.0;
  115. R2+=M_PI/2.0;
  116. R3+=M_PI/2.0;
  117. R4-=M_PI/2.0;
  118. L1=-L1;
  119. L4=-L4;
  120. }
  121. }
  122. int main(int argc, char **argv) {
  123. //init mqtt
  124. if(false==init_mqtt("127.0.0.1",1883,"webots_main","MainPLC/speedcmd"))
  125. {
  126. printf(" Init mqtt failed...\n");
  127. return -1;
  128. }
  129. //随机数
  130. unsigned seed = std::chrono::system_clock::now().time_since_epoch().count();
  131. std::default_random_engine generator(seed);
  132. // create the Robot instance.
  133. Robot *robot = new Robot();
  134. // get the time step of the current world.
  135. int timeStep = (int)robot->getBasicTimeStep();
  136. webots::Motor* RM1=robot->getMotor("R1_motor");
  137. webots::Motor* RM2=robot->getMotor("R2_motor");
  138. webots::Motor* RM3=robot->getMotor("R3_motor");
  139. webots::Motor* RM4=robot->getMotor("R4_motor");
  140. //R1->getPositionSensor()->enable(timeStep);
  141. webots::Motor* R1_l=robot->getMotor("L1_motor");
  142. webots::Motor* R2_l=robot->getMotor("L2_motor");
  143. webots::Motor* R3_l=robot->getMotor("L3_motor");
  144. webots::Motor* R4_l=robot->getMotor("L4_motor");
  145. RM1->setPosition(0);
  146. RM2->setPosition(0);
  147. RM3->setPosition(0);
  148. RM4->setPosition(0);
  149. R1_l->setPosition(INFINITY);
  150. R2_l->setPosition(INFINITY);
  151. R3_l->setPosition(INFINITY);
  152. R4_l->setPosition(INFINITY);
  153. /*RM1->setTorque(100);
  154. RM2->setTorque(100);
  155. RM3->setTorque(100);
  156. RM4->setTorque(100);*/
  157. R1_l->setVelocity(0.0);
  158. R2_l->setVelocity(0.0);
  159. R3_l->setVelocity(0.0);
  160. R4_l->setVelocity(0.0);
  161. webots::GPS* gps=robot->getGPS("gps");
  162. webots::InertialUnit* imu=robot->getInertialUnit("imu");
  163. webots::Gyro* gyr=robot->getGyro("gyro");
  164. gyr->enable(timeStep);
  165. gps->enable(timeStep);
  166. imu->enable(timeStep);
  167. double w=2.5;
  168. double l=1.3;
  169. double radius=0.1915;
  170. double K=1.0/radius;
  171. auto last=std::chrono::steady_clock::now();
  172. while (robot->step(timeStep) != -1) {
  173. auto now=std::chrono::steady_clock::now();
  174. auto duration = std::chrono::duration_cast<std::chrono::microseconds>(now - last);
  175. double time = double(duration.count()) * std::chrono::microseconds::period::num /
  176. std::chrono::microseconds::period::den;
  177. ////发布:
  178. //增加高斯分布
  179. double x=gps->getValues()[2]+ generae_random(generator,0,0.005);
  180. double y=gps->getValues()[0] + generae_random(generator,0,0.005);
  181. double theta=imu->getRollPitchYaw()[2]+generae_random(generator,0,0.1*M_PI/180.0);
  182. //获取gps速度,判断朝向
  183. double vm1=R3_l->getVelocity()*radius;
  184. double vm2=-R2_l->getVelocity()*radius;
  185. double v=gps->getSpeed();
  186. if(vm1+vm2<0.0)
  187. v=-v;
  188. //陀螺仪角速度
  189. double vth=gyr->getValues()[1];
  190. if(time>0.2)
  191. {
  192. printf(" publish delay................ time:%f -------------------------------------\n",time);
  193. }
  194. /*printf("dt:%f x y:%f %f, yaw:%f velocity:%f vth:%f %f %f\n",time,
  195. x,y,theta,
  196. v,gyr->getValues()[0],gyr->getValues()[1],gyr->getValues()[2]);*/
  197. last=now;
  198. if(client_)
  199. {
  200. MqttMsg msg;
  201. NavMessage::LidarOdomStatu odom;
  202. odom.set_x(x);
  203. odom.set_y(y);
  204. odom.set_theta(theta);
  205. odom.set_v(v);
  206. odom.set_vth(vth);
  207. msg.fromProtoMessage(odom);
  208. client_->publish("lidar_odom/main",1,msg);
  209. NavMessage::AgvStatu speed;
  210. speed.set_v(v);
  211. speed.set_w(vth);
  212. speed.set_clamp(0);
  213. speed.set_clamp_other(0);
  214. msg.fromProtoMessage(speed);
  215. client_->publish("MainPLC/speed",1,msg);
  216. }
  217. if(g_speed.timeout())
  218. {
  219. RM1->setPosition(0);
  220. RM2->setPosition(0);
  221. RM3->setPosition(0);
  222. RM4->setPosition(0);
  223. R1_l->setVelocity(0);
  224. R2_l->setVelocity(0);
  225. R3_l->setVelocity(0);
  226. R4_l->setVelocity(0);
  227. continue;
  228. }
  229. //变速----------------------------------
  230. double cmd_v=g_speed.Get().v();
  231. double cmd_vth=g_speed.Get().w();
  232. //初始值
  233. double R1=0,R2=0,R3=0,R4=0;
  234. double L1=cmd_v;
  235. double L2=cmd_v;
  236. double L3=cmd_v;
  237. double L4=cmd_v;
  238. if(g_speed.Get().t()==1) //原地旋转
  239. {
  240. printf("旋转:");
  241. if (fabs(cmd_vth) > 0.0001)
  242. Rotating(cmd_vth, w / 2.0, l / 2.0, R1, R2, R3, R4, L1, L2, L3, L4);
  243. }
  244. else if(g_speed.Get().t()==2) //横移
  245. {
  246. printf("横移:");
  247. if (fabs(cmd_vth) > 0.4) {
  248. cmd_vth = cmd_vth > 0 ? 0.4 : -0.4;
  249. }
  250. Horizontal(cmd_v,cmd_vth,l,w,R1, R2, R3, R4, L1, L2, L3, L4);
  251. }
  252. else if(g_speed.Get().t()==3){ //巡线/前进
  253. printf("前进:");
  254. if (fabs(cmd_vth) > 0.4) {
  255. cmd_vth = cmd_vth > 0 ? 0.4 : -0.4;
  256. }
  257. Vrtical(cmd_v,cmd_vth,w,l,R1,R2,R3,R4,L1,L2,L3,L4);
  258. }
  259. printf("Child R1-R4:%.5f %.5f %.5f %.5f L1-L4:%.5f %.5f %.5f %.5f V:%.5f Vth:%.5f\n",
  260. R1,R2,R3,R4,L1,L2,L3,L4,cmd_v,cmd_vth);
  261. RM1->setPosition(R1);
  262. RM2->setPosition(R2);
  263. RM3->setPosition(R3);
  264. RM4->setPosition(R4);
  265. R1_l->setVelocity(L1*K);
  266. R2_l->setVelocity(-L2*K);
  267. R3_l->setVelocity(L3*K);
  268. R4_l->setVelocity(-L4*K);
  269. };
  270. // Enter here exit cleanup code.
  271. delete robot;
  272. return 0;
  273. }