Process.cpp 6.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260
  1. #include "Process.h"
  2. #include "qmessagebox.h"
  3. #include "TaskQueue/TQFactory.h"
  4. #include "mainwindow.h"
  5. CProcess::CProcess(Automatic::stCalibParam param, void* mainWnd)
  6. {
  7. m_laser_calib_param = param;
  8. m_laser = NULL;
  9. m_main_wnd = mainWnd;
  10. m_thread_queue=0;
  11. m_locater=0;
  12. connect(this,SIGNAL(MainWndSignal(QVariant)),
  13. (MainWindow*)m_main_wnd,SLOT(ProcessSlot(QVariant)));
  14. }
  15. CProcess::~CProcess()
  16. {
  17. const int n = m_laser_calib_param.laser_size();
  18. for (int i = 0; i < n; ++i)
  19. {
  20. std::string type = m_laser_calib_param.laser(i).type();
  21. if (type.find("Livox") != type.npos)
  22. {
  23. Uninit();
  24. break;
  25. }
  26. }
  27. if(m_thread_queue)
  28. {
  29. m_thread_queue->Stop();
  30. delete m_thread_queue;
  31. m_thread_queue=0;
  32. }
  33. if (m_laser)
  34. {
  35. for (int i = 0; i < n; ++i)
  36. {
  37. if (m_laser[i])
  38. {
  39. m_laser[i]->Disconnect();
  40. delete m_laser[i];
  41. m_laser[i] = NULL;
  42. }
  43. }
  44. delete[] m_laser;
  45. m_laser = NULL;
  46. }
  47. if (m_laser_calib_param.is_calib() == false)
  48. {
  49. if(m_locater)
  50. delete m_locater;
  51. }
  52. }
  53. bool CProcess::Init()
  54. {
  55. m_thread_queue=tq::TQFactory::CreateDefaultQueue();
  56. m_thread_queue->Start(3);
  57. if (NULL == m_laser)
  58. {
  59. const int n = m_laser_calib_param.laser_size();
  60. m_laser = new CLaser*[n];
  61. for (int i = 0; i < n; ++i)
  62. {
  63. std::string type = m_laser_calib_param.laser(i).type();
  64. ////�ж��Ƿ��Ǵ��ļ���
  65. if (type.find("File") != type.npos)
  66. {
  67. LOG(INFO) << "create fileLaser";
  68. std::string dir = m_laser_calib_param.debug_file();
  69. m_laser_calib_param.mutable_laser(i)->set_laser_ip(dir);
  70. }
  71. //����laser
  72. m_laser[i] = LaserRegistory::CreateLaser(type, i, m_laser_calib_param.laser(i));
  73. if (m_laser[i] == NULL)
  74. {
  75. char buf[255] = { 0 };
  76. sprintf(buf, " Laser type : %s is not exits...", type.c_str());
  77. m_last_error=buf;
  78. return false;
  79. }
  80. if (!m_laser[i]->Connect())
  81. {
  82. char error[255] = { 0 };
  83. sprintf(error, "laser %d connect failed...", i);
  84. m_last_error = error;
  85. return false;
  86. }
  87. double mat[12] = { 0 };
  88. if (m_laser_calib_param.is_calib()==false)
  89. {
  90. create_mat_param(m_laser_calib_param.laser(i), mat);
  91. m_laser[i]->SetMetrix(mat);
  92. }
  93. }
  94. for (int i = 0; i < n; ++i)
  95. {
  96. std::string type = m_laser_calib_param.laser(i).type();
  97. if (type.find("Livox") != type.npos)
  98. {
  99. if (Start() == false)
  100. {
  101. Uninit();
  102. m_last_error=("Livox laser init failed...");
  103. return false;
  104. }
  105. break;
  106. }
  107. }
  108. }
  109. // ���ӵ�PLC,����locate
  110. if (m_laser_calib_param.is_calib() == false)
  111. {
  112. if (0 != m_monitor.connect(m_laser_calib_param.plc().plc_ip().c_str(), m_laser_calib_param.plc().plc_port(), 1))
  113. {
  114. m_last_error=(" connect PLC failed...");
  115. return false;
  116. }
  117. else
  118. {
  119. m_monitor.set_callback(action_callback, monitor_callback,this);
  120. }
  121. if (m_locater == 0)
  122. {
  123. m_locater = new CLocater();
  124. }
  125. }
  126. return true;
  127. }
  128. void CProcess::PushTask(uint16_t param, int action_type,bool test)
  129. {
  130. char plate = 0;
  131. uint16_t laserID = param;
  132. memcpy(&plate, &param, 1);
  133. m_plate_index = plate;
  134. std::vector<CLaser*> lasers;
  135. for (int i = 0; i < 8; ++i)
  136. {
  137. if (((0x01 << i)&laserID) > 0)
  138. {
  139. const int n = m_laser_calib_param.laser_size();
  140. if (i >= 0 && i < n)
  141. lasers.push_back(m_laser[i]);
  142. }
  143. }
  144. //������ɨ��������
  145. modbus::CPLCMonitor* plc = 0;
  146. if (test == false)
  147. plc = &(m_monitor);
  148. tq::BaseTask* task = 0;
  149. if(action_type==1)
  150. task= new MeasureTask(lasers, /*m_locater*/0, int(plate),plc, m_laser_calib_param);
  151. /*else if(action_type==2)
  152. task = new CFenceTask(lasers, m_locater, int(plate), plc, m_laser_calib_param);*/
  153. ((MeasureTask*)task)->SetResultCallback(this, monitor_callback);
  154. m_thread_queue->AddTask(task);
  155. }
  156. void CProcess::action_callback(bool bOn, uint16_t param, void* pointer, int action_type)
  157. {
  158. CProcess* process = reinterpret_cast<CProcess*>(pointer);
  159. if(bOn)
  160. process->PushTask(param, action_type);
  161. }
  162. void CProcess::monitor_callback(QtMessageData data, void* pointer)
  163. {
  164. static QtMessageData msg;
  165. memcpy(&msg,&data,sizeof(data));
  166. CProcess* process = reinterpret_cast<CProcess*>(pointer);
  167. static QVariant var;
  168. var.setValue(msg);
  169. emit process->MainWndSignal(var);
  170. }
  171. void CProcess::create_mat_param(Automatic::stLaserCalibParam laser, double* buf)
  172. {
  173. std::string type = laser.type();
  174. if (type.find("Linear") != type.npos)
  175. {
  176. double x_angle = laser.axis_x_theta() / 180.0*PI;
  177. double y_angle = laser.axis_y_theta() / 180.0*PI;
  178. double z_angle = laser.axis_z_theta() / 180.0*PI;
  179. double t_x = laser.translation_x();
  180. double t_y = laser.translation_y();
  181. double t_z = laser.translation_z();
  182. Eigen::AngleAxisd rollAngle(x_angle, Eigen::Matrix<double, 3, 1>::UnitX());
  183. Eigen::AngleAxisd pitchAngle(y_angle, Eigen::Matrix<double, 3, 1>::UnitY());
  184. Eigen::AngleAxisd yawAngle(z_angle, Eigen::Matrix<double, 3, 1>::UnitZ());
  185. Eigen::Quaterniond q = yawAngle * pitchAngle * rollAngle;
  186. Eigen::Matrix<double, 3, 3> rotationMatrix = q.toRotationMatrix();
  187. Eigen::Matrix<double, 3, 4> transform;
  188. Eigen::Matrix<double, 3, 1> translation;
  189. translation << t_x, t_y, t_z;
  190. transform << rotationMatrix, translation;
  191. buf[0] = transform(0, 0);
  192. buf[1] = transform(0, 1);
  193. buf[2] = transform(0, 2);
  194. buf[3] = transform(0, 3);
  195. buf[4] = transform(1, 0);
  196. buf[5] = transform(1, 1);
  197. buf[6] = transform(1, 2);
  198. buf[7] = transform(1, 3);
  199. buf[8] = transform(2, 0);
  200. buf[9] = transform(2, 1);
  201. buf[10] = transform(2, 2);
  202. buf[11] = transform(2, 3);
  203. }
  204. else
  205. {
  206. buf[0] = laser.mat_r00();
  207. buf[1] = laser.mat_r01();
  208. buf[2] = laser.mat_r02();
  209. buf[3] = laser.mat_r03();
  210. buf[4] = laser.mat_r10();
  211. buf[5] = laser.mat_r11();
  212. buf[6] = laser.mat_r12();
  213. buf[7] = laser.mat_r13();
  214. buf[8] = laser.mat_r20();
  215. buf[9] = laser.mat_r21();
  216. buf[10] = laser.mat_r22();
  217. buf[11] = laser.mat_r23();
  218. }
  219. }
  220. /*#include "MsgDef.h"
  221. void CProcess::result_callback(Locate_Message msg, void* ptr)
  222. {
  223. CProcess* process = reinterpret_cast<CProcess*>(ptr);
  224. std::lock_guard<std::mutex> lk(process->m_mutex);
  225. process->m_locate_msg = msg;
  226. if(process->m_main_wnd)
  227. ::PostMessage(process->m_main_wnd->m_hWnd, WM_MSG_MainWnd, WPARAM(WM_Draw_cloud), 0);
  228. }*/