UserCan.cpp 9.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295
  1. #include <AP_Common/AP_Common.h>
  2. #include <AP_HAL/AP_HAL.h>
  3. #include <AP_Scheduler/AP_Scheduler.h>
  4. #include <GCS_MAVLink/GCS.h>
  5. #include <AP_HAL/utility/sparse-endian.h>
  6. #include "Sub.h"
  7. extern const AP_HAL::HAL& hal;
  8. #if HAL_WITH_UAVCAN
  9. #include "UserCAN.h"
  10. #define CAN_PACKET_SET_DUTY 0
  11. #define CAN_PACKET_SET_RPM 3
  12. #define CAN_PACKET_CONF_STORE_CURRENT_LIMITS 22
  13. #define CAN_PACKET_CONF_STORE_CURRENT_LIMITS_IN 24
  14. #define CAN_PACKET_STATUS 9
  15. #define CAN_PACKET_STATUS_3 15
  16. #define CAN_PACKET_STATUS_4 16
  17. #define CAN_PACKET_STATUS_5 27
  18. extern mavlink_motor_speed_t mav_motor_speed;
  19. static const uint16_t USERCAN_SEND_TIMEOUT_US = 500;
  20. //static const uint16_t COMMAND_MOTOR1 = 0x0301;
  21. //static const uint16_t COMMAND_MOTOR1_RETURN = 0x0281;
  22. static const uint16_t COMMAND_MOTOR1_ID = 0x01;
  23. static const uint16_t COMMAND_MOTOR2_ID = 0x02;
  24. static const uint8_t CAN_IFACE_INDEX = 0;
  25. UserCAN::UserCAN()
  26. {
  27. update_count_sent = 1;
  28. update_count_buffered = 1;
  29. send_ID = 0;
  30. }
  31. void UserCAN::init(uint8_t driver_index, bool enable_filters)
  32. {
  33. _driver_index = driver_index;
  34. if (_initialized) {
  35. return;
  36. }
  37. AP_HAL::CANManager* can_mgr = hal.can_mgr[driver_index];
  38. if (can_mgr == nullptr) {
  39. return;
  40. }
  41. if (!can_mgr->is_initialized()) {
  42. return;
  43. }
  44. _can_driver = can_mgr->get_driver();
  45. if (_can_driver == nullptr) {
  46. return;
  47. }
  48. // start calls to loop in separate thread
  49. if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&UserCAN::loop, void), _thread_name, 4096, AP_HAL::Scheduler::PRIORITY_MAIN, 1)) {
  50. return;
  51. }
  52. _initialized = true;
  53. return;
  54. }
  55. void UserCAN::loop()
  56. {
  57. uavcan::MonotonicTime timeout;
  58. const uint32_t timeout_us = MIN(AP::scheduler().get_loop_period_us(), USERCAN_SEND_TIMEOUT_US);
  59. while (true) {
  60. if (!_initialized) {
  61. // if not initialised wait 5ms
  62. hal.scheduler->delay_microseconds(5000);
  63. continue;
  64. }
  65. if (1) {
  66. hal.scheduler->delay_microseconds(50);
  67. // continue;
  68. }
  69. uavcan::CanFrame recv_frame;
  70. if(read_frame(recv_frame, timeout)) {
  71. motor_reply_data1_t reply_data;
  72. memcpy(reply_data.data, recv_frame.data, sizeof(reply_data.data));
  73. if((recv_frame.id & 0x000000FF)>=1 && (recv_frame.id & 0x000000FF)<=6){//6个电调的ID分别为1,2,3,4,5,6
  74. for (uint8_t i = 1; i < 7; i++)
  75. {
  76. uint8_t COMMAND_MOTOR_ID=i;
  77. if((recv_frame.id&0x1FFFFFFFU) == (CAN_PACKET_STATUS<<8|COMMAND_MOTOR_ID)){
  78. int32_t temp = (int32_t)(reply_data.data[0]<<24)+(int32_t)(reply_data.data[1]<<16)+(int32_t)(reply_data.data[2]<<8)+(int32_t)reply_data.data[3];
  79. sub._telemetry[i-1].rpm =temp;
  80. sub._telemetry[i-1].totalcurrent = (int16_t)(reply_data.data[4]<<8)+(int16_t)reply_data.data[5];//总电流*10
  81. sub._telemetry[i-1].dutycycle = (int16_t)(reply_data.data[6]<<8)+(int16_t)reply_data.data[7];//占空比*1000
  82. //break;
  83. }
  84. if((recv_frame.id&0x1FFFFFFFU) == ((CAN_PACKET_STATUS_4<<8|COMMAND_MOTOR_ID)&0x1FFFFFFFU)){
  85. sub._telemetry[i-1].toalcurrentIn =(int16_t)(reply_data.data[4]<<8)+(int16_t)reply_data.data[5]; //总输入电流
  86. sub._telemetry[i-1].mostemperature =(int16_t)(reply_data.data[0]<<8)+(int16_t)reply_data.data[1];//mos温度
  87. sub._telemetry[i-1].mottremperature = (int16_t)(reply_data.data[2]<<8)+(int16_t)reply_data.data[3];//电机温度
  88. //break;
  89. }
  90. if((recv_frame.id&0x1FFFFFFFU) == ((CAN_PACKET_STATUS_5<<8|COMMAND_MOTOR_ID)&0x1FFFFFFFU)){
  91. sub._telemetry[i-1].voltage = (int16_t)(reply_data.data[4]<<8)+(int16_t)reply_data.data[5];//总电压
  92. //break;
  93. }
  94. }
  95. }
  96. }
  97. uint32_t nowtime = AP_HAL::micros();
  98. static uint32_t last_send_time = nowtime;
  99. if(nowtime - last_send_time >1000000UL/400 )//发送周期
  100. { last_send_time = nowtime;
  101. send_ID++;
  102. const AP_Motors6DOF &motors6dof = AP::motors6dof();//6自由度电机计算出来的PWM
  103. //motor_rotation_cmd_t mot_rot_cmd1={0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00};
  104. sent_command mot_rot_cmd1={0x00,0x00,0x00,0x00};
  105. if (send_ID<7)
  106. {
  107. static int k = 0;
  108. k++;
  109. if(k>400)
  110. {
  111. gcs().send_text(MAV_SEVERITY_INFO, "motor_out1 %d %d %d \n", (int)motors6dof.motor_to_can[0],(int)motors6dof.motor_to_can[1],(int)motors6dof.motor_to_can[2]);
  112. gcs().send_text(MAV_SEVERITY_INFO, "motor_out2 %d %d %d \n", (int)motors6dof.motor_to_can[3],(int)motors6dof.motor_to_can[4],(int)motors6dof.motor_to_can[5]);
  113. //gcs().send_text(MAV_SEVERITY_INFO, "motor_out %f %f %d \f", (float)motor_to_can[3],(float)motor_to_can[4], (float)motor_to_can[5]);
  114. k=0;
  115. }
  116. mot_rot_cmd1.data[0] = (uint8_t)(motors6dof.motor_to_can[send_ID-1]>>24);
  117. mot_rot_cmd1.data[1] = (uint8_t)(motors6dof.motor_to_can[send_ID-1]>>16);
  118. mot_rot_cmd1.data[2] = (uint8_t)(motors6dof.motor_to_can[send_ID-1]>>8);
  119. mot_rot_cmd1.data[3] = (uint8_t)motors6dof.motor_to_can[send_ID-1];
  120. //mot_rot_frame1 = {((CAN_PACKET_SET_DUTY<<8 |send_ID) | 0x80000000U), mot_rot_cmd1.data, sizeof(mot_rot_cmd1.data)};
  121. mot_rot_frame1 = {((CAN_PACKET_SET_RPM<<8 |send_ID) | 0x80000000U), mot_rot_cmd1.data, sizeof(mot_rot_cmd1.data)};
  122. timeout = uavcan::MonotonicTime::fromUSec(AP_HAL::micros64() + timeout_us);
  123. if (!write_frame(mot_rot_frame1, timeout)) {
  124. continue;
  125. }
  126. }
  127. else{
  128. send_ID = 0;
  129. }
  130. }
  131. /*if ((be16toh)(reply_data.packed_data.command_code) == 0x5156)//be16toh改变字节顺序
  132. {
  133. sub._telemetry[0].rpm =((be32toh)(reply_data.packed_data.data_reply));//速度 //(int32_t)(reply_data.data[4]<<24)+(int32_t)(reply_data.data[5]<<16)+(int32_t)(reply_data.data[6]<<8)+(int32_t)reply_data.data[7];//
  134. }else if((be16toh)(reply_data.packed_data.command_code) == 0x5143){
  135. sub._telemetry[0].current =(float)((be32toh)(reply_data.packed_data.data_reply))/10;//电流
  136. }else if((be16toh)(reply_data.packed_data.command_code) == 0x5150){
  137. sub._telemetry[0].voltage =(float)((be32toh)(reply_data.packed_data.data_reply))/10;//电压
  138. }else if((be16toh)(reply_data.packed_data.command_code) == 0x5154){
  139. sub._telemetry[0].temperature =((be32toh)(reply_data.packed_data.data_reply));//温度
  140. }else if((be16toh)(reply_data.packed_data.command_code) == 0x4546){
  141. sub._telemetry[0].EF =((be16toh)(reply_data.packed_data.data_reply));//故障
  142. }*/
  143. /*static int f = 0;
  144. f++;
  145. if(f>200)
  146. {
  147. gcs().send_text(MAV_SEVERITY_INFO, " oshen_motor_show %d %f,%f ",(int)sub._telemetry[0].rpm,(float)sub._telemetry[0].current,(float)sub._telemetry[0].voltage);
  148. gcs().send_text(MAV_SEVERITY_INFO, " oshen_motor_show %d %x ",(int)sub._telemetry[0].temperature,(int)sub._telemetry[0].EF);
  149. //gcs().send_text(MAV_SEVERITY_INFO, " oshen_motor_show %x %x ",(int)((be16toh)(reply_data.command_code)), (int)((be32toh)(reply_data.data_reply)));
  150. f=0;
  151. }
  152. }
  153. else{
  154. update_count2++;//没有收到指令ID
  155. }
  156. }
  157. else{
  158. update_count2++;//没有收到任何ID
  159. }
  160. if(update_count2==0 ||update_count2 >10){
  161. update_count2 = 0;
  162. send_stage=0;
  163. }
  164. //}
  165. }*/
  166. }
  167. }
  168. bool UserCAN::write_frame(uavcan::CanFrame &out_frame, uavcan::MonotonicTime timeout)
  169. {
  170. // wait for space in buffer to send command
  171. uavcan::CanSelectMasks inout_mask;
  172. do {
  173. inout_mask.read = 0;
  174. inout_mask.write = 1 << CAN_IFACE_INDEX;
  175. _select_frames[CAN_IFACE_INDEX] = &out_frame;
  176. _can_driver->select(inout_mask, _select_frames, timeout);
  177. // delay if no space is available to send
  178. if (!inout_mask.write) {
  179. hal.scheduler->delay_microseconds(50);
  180. }
  181. } while (!inout_mask.write);
  182. // send frame and return success
  183. return (_can_driver->getIface(CAN_IFACE_INDEX)->send(out_frame, timeout, uavcan::CanIOFlagAbortOnError) == 1);
  184. }
  185. bool UserCAN::read_frame(uavcan::CanFrame &recv_frame, uavcan::MonotonicTime timeout)
  186. {
  187. // wait for space in buffer to read
  188. uavcan::CanSelectMasks inout_mask;
  189. inout_mask.read = 1 << CAN_IFACE_INDEX;
  190. inout_mask.write = 0;
  191. _select_frames[CAN_IFACE_INDEX] = &recv_frame;
  192. _can_driver->select(inout_mask, _select_frames, timeout);
  193. // return false if no data is available to read
  194. if (!inout_mask.read) {
  195. return false;
  196. }
  197. uavcan::MonotonicTime time;
  198. uavcan::UtcTime utc_time;
  199. uavcan::CanIOFlags flags {};
  200. // read frame and return success
  201. return (_can_driver->getIface(CAN_IFACE_INDEX)->receive(recv_frame, time, utc_time, flags) == 1);
  202. }
  203. #endif // HAL_WITH_UAVCAN