AP_UAVCAN.cpp 47 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135113611371138113911401141114211431144114511461147114811491150115111521153115411551156115711581159116011611162116311641165116611671168116911701171117211731174117511761177117811791180118111821183118411851186118711881189119011911192119311941195119611971198119912001201120212031204120512061207120812091210121112121213121412151216121712181219122012211222122312241225122612271228122912301231123212331234123512361237123812391240124112421243124412451246124712481249125012511252125312541255125612571258125912601261126212631264126512661267126812691270127112721273127412751276127712781279128012811282128312841285128612871288128912901291129212931294129512961297129812991300130113021303130413051306130713081309131013111312131313141315131613171318131913201321132213231324132513261327132813291330133113321333133413351336133713381339134013411342134313441345134613471348134913501351135213531354135513561357135813591360136113621363136413651366136713681369137013711372137313741375137613771378137913801381138213831384138513861387138813891390139113921393139413951396139713981399140014011402140314041405140614071408140914101411141214131414141514161417141814191420142114221423142414251426142714281429143014311432
  1. /*
  2. * This file is free software: you can redistribute it and/or modify it
  3. * under the terms of the GNU General Public License as published by the
  4. * Free Software Foundation, either version 3 of the License, or
  5. * (at your option) any later version.
  6. *
  7. * This file is distributed in the hope that it will be useful, but
  8. * WITHOUT ANY WARRANTY; without even the implied warranty of
  9. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  10. * See the GNU General Public License for more details.
  11. *
  12. * You should have received a copy of the GNU General Public License along
  13. * with this program. If not, see <http://www.gnu.org/licenses/>.
  14. *
  15. * Author: Eugene Shamaev, Siddharth Bharat Purohit
  16. */
  17. #include <AP_Common/AP_Common.h>
  18. #include <AP_HAL/AP_HAL.h>
  19. #if HAL_WITH_UAVCAN
  20. #include "AP_UAVCAN.h"
  21. #include <GCS_MAVLink/GCS.h>
  22. #include <AP_Motors/AP_Motors.h> //电机类
  23. #include "../../ArduSub/Sub.h"
  24. #include <AP_BoardConfig/AP_BoardConfig.h>
  25. #include <AP_BoardConfig/AP_BoardConfig_CAN.h>
  26. #include <uavcan/transport/can_acceptance_filter_configurator.hpp>
  27. #include <uavcan/equipment/actuator/ArrayCommand.hpp>
  28. #include <uavcan/equipment/actuator/Command.hpp>
  29. #include <uavcan/equipment/actuator/Status.hpp>
  30. //#include <uavcan/equipment/esc/MotorCommands.hpp>
  31. #include <uavcan/equipment/esc/Motor1ResCommand.hpp>
  32. #include <uavcan/equipment/esc/SetFloatParam.hpp>
  33. #include <uavcan/equipment/esc/SingleMotorCommand.hpp>
  34. #include <uavcan/equipment/esc/GetFloatParam1.hpp>
  35. //hight volt HighVoltThrusterSetRegs.hpp
  36. #include <uavcan/equipment/esc/Bfd1.hpp>
  37. #include <uavcan/equipment/esc/Bfd2.hpp>
  38. #include <uavcan/equipment/esc/Bfd3.hpp>
  39. #include <uavcan/equipment/esc/HighVoltThrusterSetRegs.hpp>
  40. #include <uavcan/equipment/esc/HighVoltThruster1GetRegs.hpp>
  41. #include <uavcan/equipment/esc/HighVoltThruster2GetRegs.hpp>
  42. #include <uavcan/equipment/esc/HighVoltThruster3GetRegs.hpp>
  43. #include <uavcan/equipment/esc/HighVoltThruster1GetRegsFujian.hpp>
  44. #include <uavcan/equipment/esc/HighVoltThruster2GetRegsFujian.hpp>
  45. #include <uavcan/equipment/esc/HighVoltThruster3GetRegsFujian.hpp>
  46. #include <uavcan/equipment/esc/SpeedCommands.hpp>
  47. #include <uavcan/equipment/esc/HighVoltThruster1timeback.hpp>
  48. #include <uavcan/equipment/esc/HighVoltThruster2timeback.hpp>
  49. #include <uavcan/equipment/esc/HighVoltThruster3timeback.hpp>
  50. //#include <uavcan/equipment/esc/HighVoltThruster1timebackST.hpp>
  51. //#include <uavcan/equipment/esc/HighVoltThruster2timebackST.hpp>
  52. //#include <uavcan/equipment/esc/HighVoltThruster3timebackST.hpp>
  53. #include <uavcan/equipment/esc/RawCommand.hpp>
  54. #include <uavcan/equipment/indication/LightsCommand.hpp>
  55. #include <uavcan/equipment/indication/SingleLightCommand.hpp>
  56. #include <uavcan/equipment/indication/BeepCommand.hpp>
  57. #include <uavcan/equipment/indication/RGB565.hpp>
  58. #include <ardupilot/indication/SafetyState.hpp>
  59. #include <ardupilot/indication/Button.hpp>
  60. #include <AP_Baro/AP_Baro_UAVCAN.h>
  61. #include <AP_RangeFinder/AP_RangeFinder_UAVCAN.h>
  62. #include <AP_GPS/AP_GPS_UAVCAN.h>
  63. #include <AP_BattMonitor/AP_BattMonitor_UAVCAN.h>
  64. #include <AP_Compass/AP_Compass_UAVCAN.h>
  65. #include <AP_Airspeed/AP_Airspeed_UAVCAN.h>
  66. #include <SRV_Channel/SRV_Channel.h>
  67. #include <AP_OpticalFlow/AP_OpticalFlow_HereFlow.h>
  68. #define LED_DELAY_US 50000
  69. extern const AP_HAL::HAL& hal;
  70. #define debug_uavcan(level_debug, fmt, args...) do { if ((level_debug) <= AP::can().get_debug_level_driver(_driver_index)) { printf(fmt, ##args); }} while (0)
  71. // Translation of all messages from UAVCAN structures into AP structures is done
  72. // in AP_UAVCAN and not in corresponding drivers.
  73. // The overhead of including definitions of DSDL is very high and it is best to
  74. // concentrate in one place.
  75. // table of user settable CAN bus parameters
  76. const AP_Param::GroupInfo AP_UAVCAN::var_info[] = {
  77. // @Param: NODE
  78. // @DisplayName: UAVCAN node that is used for this network
  79. // @Description: UAVCAN node should be set implicitly
  80. // @Range: 1 250
  81. // @User: Advanced
  82. AP_GROUPINFO("NODE", 1, AP_UAVCAN, _uavcan_node, 10),
  83. // @Param: SRV_BM
  84. // @DisplayName: RC Out channels to be transmitted as servo over UAVCAN
  85. // @Description: Bitmask with one set for channel to be transmitted as a servo command over UAVCAN
  86. // @Bitmask: 0: Servo 1, 1: Servo 2, 2: Servo 3, 3: Servo 4, 4: Servo 5, 5: Servo 6, 6: Servo 7, 7: Servo 8, 8: Servo 9, 9: Servo 10, 10: Servo 11, 11: Servo 12, 12: Servo 13, 13: Servo 14, 14: Servo 15
  87. // @User: Advanced
  88. AP_GROUPINFO("SRV_BM", 2, AP_UAVCAN, _servo_bm, 0),
  89. // @Param: ESC_BM
  90. // @DisplayName: RC Out channels to be transmitted as ESC over UAVCAN
  91. // @Description: Bitmask with one set for channel to be transmitted as a ESC command over UAVCAN
  92. // @Bitmask: 0: ESC 1, 1: ESC 2, 2: ESC 3, 3: ESC 4, 4: ESC 5, 5: ESC 6, 6: ESC 7, 7: ESC 8, 8: ESC 9, 9: ESC 10, 10: ESC 11, 11: ESC 12, 12: ESC 13, 13: ESC 14, 14: ESC 15, 15: ESC 16
  93. // @User: Advanced
  94. AP_GROUPINFO("ESC_BM", 3, AP_UAVCAN, _esc_bm, 0),
  95. // @Param: SRV_RT
  96. // @DisplayName: Servo output rate
  97. // @Description: Maximum transmit rate for servo outputs
  98. // @Range: 1 200
  99. // @Units: Hz
  100. // @User: Advanced
  101. AP_GROUPINFO("SRV_RT", 4, AP_UAVCAN, _servo_rate_hz, 50),
  102. AP_GROUPEND
  103. };
  104. // this is the timeout in milliseconds for periodic message types. We
  105. // set this to 1 to minimise resend of stale msgs
  106. #define CAN_PERIODIC_TX_TIMEOUT_MS 2
  107. //自定义stm32 参数设置协议--------
  108. static uavcan::Publisher<uavcan::equipment::esc::HighVoltThrusterSetRegs>* HVoltThtSetReg[MAX_NUMBER_OF_CAN_DRIVERS];
  109. static uavcan::Publisher<uavcan::equipment::esc::Bfd1>* esc_Bfd1[MAX_NUMBER_OF_CAN_DRIVERS];
  110. static uavcan::Publisher<uavcan::equipment::esc::Bfd2>* esc_Bfd2[MAX_NUMBER_OF_CAN_DRIVERS];
  111. static uavcan::Publisher<uavcan::equipment::esc::Bfd3>* esc_Bfd3[MAX_NUMBER_OF_CAN_DRIVERS];
  112. //static uavcan::Publisher<uavcan::equipment::esc::MotorCommands>* esc_MotorCommands[MAX_NUMBER_OF_CAN_DRIVERS];
  113. static uavcan::Publisher<uavcan::equipment::esc::SetFloatParam>* SetFloatParam[MAX_NUMBER_OF_CAN_DRIVERS];
  114. static uavcan::Publisher<uavcan::equipment::esc::SpeedCommands>* esc_SpeedCommands[MAX_NUMBER_OF_CAN_DRIVERS];
  115. //自定义stm32 参数设置协议--------
  116. // publisher interfaces
  117. static uavcan::Publisher<uavcan::equipment::actuator::ArrayCommand>* act_out_array[MAX_NUMBER_OF_CAN_DRIVERS];
  118. static uavcan::Publisher<uavcan::equipment::esc::RawCommand>* esc_raw[MAX_NUMBER_OF_CAN_DRIVERS];
  119. static uavcan::Publisher<uavcan::equipment::indication::LightsCommand>* rgb_led[MAX_NUMBER_OF_CAN_DRIVERS];
  120. static uavcan::Publisher<uavcan::equipment::indication::BeepCommand>* buzzer[MAX_NUMBER_OF_CAN_DRIVERS];
  121. static uavcan::Publisher<ardupilot::indication::SafetyState>* safety_state[MAX_NUMBER_OF_CAN_DRIVERS];
  122. // subscribers
  123. // handler SafteyButton
  124. UC_REGISTRY_BINDER(ButtonCb, ardupilot::indication::Button);
  125. static uavcan::Subscriber<ardupilot::indication::Button, ButtonCb> *safety_button_listener[MAX_NUMBER_OF_CAN_DRIVERS];
  126. //接收局部全局变量-----------
  127. int16_t motors_receive[12]={0,0,0,0,0,0,0,0,0,0,0,0}; //STM32发来的速度
  128. uint8_t crc_motors[42];
  129. union DRIVEBOX_ABNORMAL_UNI motor_stall_state;//获取所有的堵转
  130. union PROPELLER_ABNORMAL_UNI propeller_block;//推进器缠绕等级
  131. union PROPELLER_ABNORMAL_UNI track_block;//推进器缠绕等级
  132. int16_t temperature_power = 0;//温度
  133. int16_t voltage48V= 0;//48V电源
  134. //int16_t driveleak = 0;//泄露
  135. extern mavlink_set_slave_parameter_t set_stm32_param;
  136. extern mavlink_rov_state_monitoring_t rov_message;
  137. extern mavlink_hv_reg_get_t hv_reg_get;
  138. extern mavlink_hv_reg_set_t hv_reg_set;
  139. extern mavlink_motor_speed_t mav_motor_speed;
  140. //uint8_t mode_flag = 0;
  141. uint8_t get_stm32_param_buf[7] = {0,0,0,0,0,0,0};// 板1收到的参数
  142. //hv_motor_runmode.all = 0xFFFF;
  143. uint8_t hv_motor_cmd_temp = 0;
  144. uint8_t hv_motor_cmd = 0;
  145. int16_t hv_motor_speed_32 = 0;
  146. int16_t lightstate=0;
  147. int16_t usbl_power=0;
  148. int16_t light_leak=0;
  149. #define reboot_time 3000
  150. //----------------------------------------------
  151. float getfloat(mavlink_set_slave_parameter_t par);
  152. void STM32_set_packet(uavcan::equipment::esc::SetFloatParam &_msgparam);
  153. void crc_setmotor(uavcan::equipment::esc::HighVoltThrusterSetRegs &hvmesg);
  154. void crc_ackfault(uavcan::equipment::esc::HighVoltThrusterSetRegs &hvmesg,uint8_t number);
  155. AP_UAVCAN::AP_UAVCAN() :
  156. _node_allocator()
  157. {
  158. AP_Param::setup_object_defaults(this, var_info);
  159. _singleton = this;
  160. for (uint8_t i = 0; i < UAVCAN_SRV_NUMBER; i++) {
  161. _SRV_conf[i].esc_pending = false;
  162. _SRV_conf[i].servo_pending = false;
  163. }
  164. sublightstate = 0;
  165. trackblock_flag =0;
  166. propellerblock_flag =0;
  167. motor_stall_state.all = 0;
  168. propeller_block.all = 0;
  169. track_block.all = 0;
  170. for (uint8_t cnt = 0; cnt < 12; cnt++)
  171. {
  172. motors_receive[cnt]=0;
  173. }
  174. for(uint8_t j=0;j<12;j++){
  175. motor_from_stm32[j] = 0;//读到转速
  176. }
  177. debug_uavcan(2, "AP_UAVCAN constructed\n\r");
  178. }
  179. AP_UAVCAN::~AP_UAVCAN()
  180. {
  181. }
  182. AP_UAVCAN *AP_UAVCAN::get_uavcan(uint8_t driver_index)
  183. {
  184. if (driver_index >= AP::can().get_num_drivers() ||
  185. AP::can().get_protocol_type(driver_index) != AP_BoardConfig_CAN::Protocol_Type_UAVCAN) {
  186. return nullptr;
  187. }
  188. return static_cast<AP_UAVCAN*>(AP::can().get_driver(driver_index));
  189. }
  190. //self define rec fun-------------------------------start---------------
  191. static void motor_res_st_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::Motor1ResCommand>& msg,uint8_t mgr )
  192. {//接收到的数据在这里处理,打印出来
  193. if (msg.motor_index == 0){
  194. //推进器0,1,2
  195. motors_receive[0] = msg.rpm0 & 0x0FFF;//推进器0
  196. propeller_block.bit.motor0 = (msg.rpm0 & 0xF000)>>12;
  197. motors_receive[1] = msg.rpm1 & 0x0FFF;//推进器1
  198. propeller_block.bit.motor1 = (msg.rpm1 & 0xF000)>>12;
  199. }
  200. else if(msg.motor_index == 3){
  201. //推进器0.1.履带左的给定
  202. int16_t rmp1 = msg.rpm0;
  203. int16_t rmp2 = msg.rpm1;
  204. int16_t rmp3 = msg.rpm2;
  205. static int16_t c2 = 0;
  206. c2++;
  207. if(c2>50){
  208. c2 =0 ;
  209. gcs().send_text(MAV_SEVERITY_WARNING, "motor_index == 3 %d %d %d.",(int)rmp1,(int)rmp2,(int)rmp3);
  210. }
  211. }
  212. else if(msg.motor_index == 6){
  213. int16_t rpm = msg.rpm0;//履带右的给定
  214. motors_receive[8] = msg.rpm2 & 0x0FFF;//履带1
  215. track_block.bit.motor0 = (msg.rpm2 & 0xF000)>>12;
  216. static int16_t c3 = 0;
  217. c3++;
  218. if(c3>50){
  219. c3 =0 ;
  220. gcs().send_text(MAV_SEVERITY_WARNING, "motor_index == 6 %d %d ",(int)rpm,motors_receive[8]);
  221. }
  222. }
  223. else if(msg.motor_index == 9){
  224. ////履带2
  225. motors_receive[9] = msg.rpm0 & 0x0FFF;//履带2速度
  226. track_block.bit.motor1 = (msg.rpm0 & 0xF000)>>12;
  227. static int16_t c4 = 0;
  228. c4++;
  229. if(c4>100){
  230. c4 =0 ;
  231. gcs().send_text(MAV_SEVERITY_WARNING, "motor_index == 9 %d.",(int)motors_receive[9]);
  232. }
  233. }
  234. else if(msg.motor_index == 12){
  235. ////
  236. voltage48V = msg.rpm0;
  237. temperature_power = msg.rpm1;
  238. motor_stall_state.all = msg.rpm2;//所有电机的堵转// 履带没有堵转了
  239. static int16_t c5 = 0;
  240. c5++;
  241. if(c5>100){
  242. c5 =0 ;
  243. //gcs().send_text(MAV_SEVERITY_WARNING, "motor_index == 12 %d %d %x.",(int)voltage48V,(int)temperature_power,motor_stall_state.all);
  244. }
  245. }
  246. else if(msg.motor_index == 15){
  247. ////履带2,毛刷1,毛刷2
  248. lightstate = msg.rpm0;
  249. usbl_power = msg.rpm1;
  250. light_leak = msg.rpm2;//灯 漏水
  251. }
  252. }
  253. static void motor_res_st_cb0(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::Motor1ResCommand>& msg ){
  254. motor_res_st_cb(msg,0);
  255. }
  256. static void motor_res_st_cb1(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::Motor1ResCommand>& msg ){
  257. motor_res_st_cb(msg,1);
  258. }
  259. static void (*motor_res_st_cb_arr[2])(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::Motor1ResCommand>& msg )
  260. ={motor_res_st_cb0,motor_res_st_cb1};
  261. //==========================================================================================================================
  262. //获取stm32板1参数------XXXXXXXX.YY-------------------------
  263. float getfloat(mavlink_set_slave_parameter_t par){
  264. float data =(par.XX1/16)*10000000+(par.XX1%16)*1000000 +
  265. (par.XX2/16)*100000+(par.XX2%16)*10000+
  266. (par.XX3/16)*1000+(par.XX3%16)*100 +
  267. (par.XX4/16)*10 + (par.XX4%16) +
  268. (par.YY/16)*0.1 +(par.YY%16)*0.01;
  269. return data;
  270. }
  271. static void motor_par1_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::GetFloatParam1>& msg,uint8_t mgr ){
  272. get_stm32_param_buf[0] = msg.number;
  273. get_stm32_param_buf[1] = msg.flag;
  274. get_stm32_param_buf[2] = msg.XX1;
  275. get_stm32_param_buf[3] = msg.XX2;
  276. get_stm32_param_buf[4] = msg.XX3;
  277. get_stm32_param_buf[5] = msg.XX4;
  278. get_stm32_param_buf[6] = msg.YY;
  279. }
  280. static void motor_par1_cb0(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::GetFloatParam1>& msg ){
  281. motor_par1_cb(msg,0);
  282. }
  283. static void motor_par1_cb1(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::GetFloatParam1>& msg ){
  284. motor_par1_cb(msg,1);
  285. }
  286. static void (*motor_par1_cb_arr[2])(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::GetFloatParam1>& msg )
  287. ={motor_par1_cb0,motor_par1_cb1};
  288. //高压电调1参数返回
  289. static void thruster1GetRegs_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster1GetRegsFujian>& msg,uint8_t mgr ){
  290. uint8_t buffer[7]={0,0,0,0,0,0,0};
  291. for (uint8_t i = 0; i < 7; i++)
  292. {
  293. buffer[i] = msg.BUFFER[i];
  294. }
  295. hv_reg_get.aim = 3;
  296. hv_reg_get.data[0] = (uint32_t)buffer[1] + (uint32_t)(buffer[2]<<8) + (uint32_t)(buffer[3]<<16) + (uint32_t)(buffer[4]<<24);
  297. hv_reg_get.data[1] = 0;
  298. hv_reg_get.data[2] = 0;
  299. //gcs().send_text(MAV_SEVERITY_WARNING, "thruster3 %x .",(uint32_t)hv_reg_get.data[0]);
  300. }
  301. static void Thruster1GetRegs_cb0(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster1GetRegsFujian>& msg ){
  302. thruster1GetRegs_cb(msg,0);
  303. }
  304. static void Thruster1GetRegs_cb1(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster1GetRegsFujian>& msg ){
  305. thruster1GetRegs_cb(msg,1);
  306. }
  307. static void (*Thruster1GetRegs_cb_arr[2])(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster1GetRegsFujian>& msg )
  308. ={Thruster1GetRegs_cb0,Thruster1GetRegs_cb1};
  309. //高压电调2参数返回
  310. static void thruster2GetRegs_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster2GetRegsFujian>& msg ,uint8_t mgr){
  311. uint8_t buffer[7]={0,0,0,0,0,0,0};
  312. for (uint8_t i = 0; i < 7; i++)
  313. {
  314. buffer[i] = msg.BUFFER[i];
  315. }
  316. hv_reg_get.aim = 4;
  317. hv_reg_get.data[0] = (uint32_t)buffer[1] + (uint32_t)(buffer[2]<<8) + (uint32_t)(buffer[3]<<16) + (uint32_t)(buffer[4]<<24);
  318. hv_reg_get.data[1] = 0;
  319. hv_reg_get.data[2] = 0;
  320. //gcs().send_text(MAV_SEVERITY_WARNING, "thruster4 %x .",(uint32_t)hv_reg_get.data[0]);
  321. }
  322. static void Thruster2GetRegs_cb0(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster2GetRegsFujian>& msg ){
  323. thruster2GetRegs_cb(msg,0);
  324. }
  325. static void Thruster2GetRegs_cb1(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster2GetRegsFujian>& msg ){
  326. thruster2GetRegs_cb(msg,1);
  327. }
  328. static void (*Thruster2GetRegs_cb_arr[2])(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster2GetRegsFujian>& msg )
  329. ={Thruster2GetRegs_cb0,Thruster2GetRegs_cb1};
  330. //高压电调3参数返回
  331. static void thruster3GetRegs_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster3GetRegsFujian>& msg ,uint8_t mgr){
  332. uint8_t buffer[7]={0,0,0,0,0,0,0};
  333. for (uint8_t i = 0; i < 7; i++)
  334. {
  335. buffer[i] = msg.BUFFER[i];
  336. }
  337. hv_reg_get.aim = 5;
  338. hv_reg_get.data[0] = (uint32_t)buffer[1] + (uint32_t)(buffer[2]<<8) + (uint32_t)(buffer[3]<<16) + (uint32_t)(buffer[4]<<24);
  339. hv_reg_get.data[1] = 0;
  340. hv_reg_get.data[2] = 0;
  341. //gcs().send_text(MAV_SEVERITY_WARNING, "thruster5 %x .",(uint32_t)hv_reg_get.data[0]);
  342. //gcs().send_text(MAV_SEVERITY_WARNING, "thruster3data %d %d %d %d.",(int)buffer[0],(int)buffer[1],(int)buffer[2],(int)buffer[3]);
  343. //gcs().send_text(MAV_SEVERITY_WARNING, "thruster3 %d %d %d.",hv_reg_get.aim,(int)data[0],(int)data[1]);
  344. }
  345. static void Thruster3GetRegs_cb0(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster3GetRegsFujian>& msg ){
  346. thruster3GetRegs_cb(msg,0);
  347. }
  348. static void Thruster3GetRegs_cb1(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster3GetRegsFujian>& msg ){
  349. thruster3GetRegs_cb(msg,1);
  350. }
  351. static void (*Thruster3GetRegs_cb_arr[2])(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster3GetRegsFujian>& msg )
  352. ={Thruster3GetRegs_cb0,Thruster3GetRegs_cb1};
  353. //高压电调1定时返回
  354. struct HVmes Thruster1={0,0,0,0,0,0};
  355. struct HVmes Thruster2={0,0,0,0,0,0};
  356. struct HVmes Thruster3={0,0,0,0,0,0};
  357. struct HVmotor haoye1={0,0,0,0,0,0};
  358. struct HVmotor haoye2={0,0,0,0,0,0};
  359. //static void Thruster1timeback_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster1timebackST>& msg ,uint8_t mgr){
  360. static void Thruster1timeback_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster1timeback>& msg ,uint8_t mgr){
  361. uint8_t buffer[6]={0,0,0,0,0,0};
  362. for (uint8_t i = 0; i < 6; i++)
  363. {
  364. buffer[i] = msg.BUFFER[i];
  365. }
  366. HVcycle(msg.CODE,buffer,Thruster1);
  367. //if(msg.CODE == 0x0A){
  368. //int16_t speedmes = buffer[4]+(buffer[5]<<8);
  369. static int16_t per = 0;
  370. per++;
  371. if (per>150)
  372. {
  373. per = 0;
  374. gcs().send_text(MAV_SEVERITY_INFO, "HV3 %d %d %d %d",(int)Thruster1.voltage,(int)Thruster1.speedref,(int)Thruster1.temperature,(int)Thruster1.motortemperature);
  375. }
  376. //}
  377. }
  378. //static void Thruster1timeback_cb0(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster1timebackST>& msg ){
  379. static void Thruster1timeback_cb0(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster1timeback>& msg ){
  380. Thruster1timeback_cb(msg,0);
  381. }
  382. //static void Thruster1timeback_cb1(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster1timebackST>& msg ){
  383. static void Thruster1timeback_cb1(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster1timeback>& msg ){
  384. Thruster1timeback_cb(msg,1);
  385. }
  386. //static void (*Thruster1timeback_cb_arr[2])(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster1timebackST>& msg )
  387. static void (*Thruster1timeback_cb_arr[2])(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster1timeback>& msg )
  388. ={Thruster1timeback_cb0,Thruster1timeback_cb1};
  389. //高压电调2定时返回
  390. //static void Thruster2timeback_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster2timebackST>& msg ,uint8_t mgr){
  391. static void Thruster2timeback_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster2timeback>& msg ,uint8_t mgr){
  392. uint8_t buffer[6]={0,0,0,0,0,0};
  393. for (uint8_t i = 0; i < 6; i++)
  394. {
  395. buffer[i] = msg.BUFFER[i];
  396. }
  397. HVcycle(msg.CODE,buffer,Thruster2);
  398. //if(msg.CODE == 0x0A){
  399. //int16_t speedmes = buffer[4]+(buffer[5]<<8);
  400. static int16_t per = 0;
  401. per++;
  402. if (per>150)
  403. {
  404. per = 0;
  405. gcs().send_text(MAV_SEVERITY_INFO, "HV4 %d %d %d",(int)Thruster2.voltage,(int)Thruster2.speedref,(int)Thruster2.temperature);
  406. }
  407. //}
  408. }
  409. //static void Thruster2timeback_cb0(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster2timebackST>& msg ){
  410. static void Thruster2timeback_cb0(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster2timeback>& msg ){
  411. Thruster2timeback_cb(msg,0);
  412. }
  413. //static void Thruster2timeback_cb1(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster2timebackST>& msg ){
  414. static void Thruster2timeback_cb1(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster2timeback>& msg ){
  415. Thruster2timeback_cb(msg,1);
  416. }
  417. //static void (*Thruster2timeback_cb_arr[2])(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster2timebackST>& msg )
  418. static void (*Thruster2timeback_cb_arr[2])(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster2timeback>& msg )
  419. ={Thruster2timeback_cb0,Thruster2timeback_cb1};
  420. //高压电调2定时返回
  421. //static void Thruster3timeback_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster3timebackST>& msg ,uint8_t mgr){
  422. static void Thruster3timeback_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster3timeback>& msg ,uint8_t mgr){
  423. uint8_t buffer[6]={0,0,0,0,0,0};
  424. for (uint8_t i = 0; i < 6; i++)
  425. {
  426. buffer[i] = msg.BUFFER[i];
  427. }
  428. HVcycle(msg.CODE,buffer,Thruster3);
  429. //if(msg.CODE == 0x0A){
  430. //int16_t speedmes = buffer[4]+(buffer[5]<<8);
  431. static int16_t per = 0;
  432. per++;
  433. if (per>150)
  434. {
  435. per = 0;
  436. gcs().send_text(MAV_SEVERITY_INFO, "HV5 %d %d %d ",(int)Thruster3.voltage,(int)Thruster3.speedref,(int)Thruster3.temperature);
  437. }
  438. //}
  439. }
  440. //static void Thruster3timeback_cb0(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster3timebackST>& msg ){
  441. static void Thruster3timeback_cb0(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster3timeback>& msg ){
  442. Thruster3timeback_cb(msg,0);
  443. }
  444. //static void Thruster3timeback_cb1(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster3timebackST>& msg ){
  445. static void Thruster3timeback_cb1(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster3timeback>& msg ){
  446. Thruster3timeback_cb(msg,1);
  447. }
  448. //static void (*Thruster3timeback_cb_arr[2])(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster3timebackST>& msg )
  449. static void (*Thruster3timeback_cb_arr[2])(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster3timeback>& msg )
  450. ={Thruster3timeback_cb0,Thruster3timeback_cb1};
  451. //self define rec fun-------------------------------end---------------
  452. void AP_UAVCAN::init(uint8_t driver_index, bool enable_filters)
  453. {
  454. //hal.scheduler->delay_microseconds(1000);
  455. if (_initialized) {
  456. debug_uavcan(2, "UAVCAN: init called more than once\n\r");
  457. return;
  458. }
  459. _driver_index = driver_index;
  460. AP_HAL::CANManager* can_mgr = hal.can_mgr[driver_index];
  461. if (can_mgr == nullptr) {
  462. debug_uavcan(2, "UAVCAN: init called for inexisting CAN driver\n\r");
  463. return;
  464. }
  465. if (!can_mgr->is_initialized()) {
  466. debug_uavcan(1, "UAVCAN: CAN driver not initialized\n\r");
  467. return;
  468. }
  469. uavcan::ICanDriver* driver = can_mgr->get_driver();
  470. if (driver == nullptr) {
  471. debug_uavcan(2, "UAVCAN: can't get UAVCAN interface driver\n\r");
  472. return;
  473. }
  474. _node = new uavcan::Node<0>(*driver, SystemClock::instance(), _node_allocator);
  475. if (_node == nullptr) {
  476. debug_uavcan(1, "UAVCAN: couldn't allocate node\n\r");
  477. return;
  478. }
  479. if (_node->isStarted()) {
  480. debug_uavcan(2, "UAVCAN: node was already started?\n\r");
  481. return;
  482. }
  483. uavcan::NodeID self_node_id(_uavcan_node);
  484. _node->setNodeID(self_node_id);
  485. char ndname[20];
  486. snprintf(ndname, sizeof(ndname), "org.ardupilot:%u", driver_index);
  487. uavcan::NodeStatusProvider::NodeName name(ndname);
  488. _node->setName(name);
  489. uavcan::protocol::SoftwareVersion sw_version; // Standard type uavcan.protocol.SoftwareVersion
  490. sw_version.major = AP_UAVCAN_SW_VERS_MAJOR;
  491. sw_version.minor = AP_UAVCAN_SW_VERS_MINOR;
  492. _node->setSoftwareVersion(sw_version);
  493. uavcan::protocol::HardwareVersion hw_version; // Standard type uavcan.protocol.HardwareVersion
  494. hw_version.major = AP_UAVCAN_HW_VERS_MAJOR;
  495. hw_version.minor = AP_UAVCAN_HW_VERS_MINOR;
  496. const uint8_t uid_buf_len = hw_version.unique_id.capacity();
  497. uint8_t uid_len = uid_buf_len;
  498. uint8_t unique_id[uid_buf_len];
  499. if (hal.util->get_system_id_unformatted(unique_id, uid_len)) {
  500. uavcan::copy(unique_id, unique_id + uid_len, hw_version.unique_id.begin());
  501. }
  502. _node->setHardwareVersion(hw_version);
  503. int start_res = _node->start();
  504. if (start_res < 0) {
  505. debug_uavcan(1, "UAVCAN: node start problem, error %d\n\r", start_res);
  506. return;
  507. }
  508. //Start Servers
  509. #ifdef HAS_UAVCAN_SERVERS
  510. _servers.init(*_node);
  511. #endif
  512. // Roundup all subscribers from supported drivers
  513. AP_GPS_UAVCAN::subscribe_msgs(this);
  514. AP_Compass_UAVCAN::subscribe_msgs(this);
  515. AP_Baro_UAVCAN::subscribe_msgs(this);
  516. AP_BattMonitor_UAVCAN::subscribe_msgs(this);
  517. AP_Airspeed_UAVCAN::subscribe_msgs(this);
  518. AP_OpticalFlow_HereFlow::subscribe_msgs(this);
  519. AP_RangeFinder_UAVCAN::subscribe_msgs(this);
  520. //创建设备类型------------------
  521. auto *node= get_node();
  522. uavcan::Subscriber<uavcan::equipment::esc::Motor1ResCommand>* motor_res_st;
  523. motor_res_st = new uavcan::Subscriber<uavcan::equipment::esc::Motor1ResCommand>(*node);
  524. const int motor_res_start_res = motor_res_st->start(motor_res_st_cb_arr[_driver_index]);//定义回调函数用于接收
  525. if (motor_res_start_res<0)
  526. {
  527. return;
  528. }
  529. //创建设备类型获取stm32参数1
  530. uavcan::Subscriber<uavcan::equipment::esc::GetFloatParam1>* motor_par1_st;
  531. motor_par1_st = new uavcan::Subscriber<uavcan::equipment::esc::GetFloatParam1>(*node);
  532. const int motor_par1_res = motor_par1_st->start(motor_par1_cb_arr[_driver_index]);//定义回调函数用于接收
  533. if (motor_par1_res<0)
  534. {
  535. return;
  536. }
  537. //高压电调1 参数返回
  538. uavcan::Subscriber<uavcan::equipment::esc::HighVoltThruster1GetRegsFujian>* Thruster1GetRegs;
  539. Thruster1GetRegs = new uavcan::Subscriber<uavcan::equipment::esc::HighVoltThruster1GetRegsFujian>(*node);
  540. const int Tht1GetReg = Thruster1GetRegs->start(Thruster1GetRegs_cb_arr[_driver_index]);//定义回调函数用于接收
  541. if (Tht1GetReg<0)
  542. {
  543. return;
  544. }
  545. //高压电调2 参数返回
  546. uavcan::Subscriber<uavcan::equipment::esc::HighVoltThruster2GetRegsFujian>* Thruster2GetRegs;
  547. Thruster2GetRegs = new uavcan::Subscriber<uavcan::equipment::esc::HighVoltThruster2GetRegsFujian>(*node);
  548. const int Tht2GetReg = Thruster2GetRegs->start(Thruster2GetRegs_cb_arr[_driver_index]);//定义回调函数用于接收
  549. if (Tht2GetReg<0)
  550. {
  551. return;
  552. }
  553. //高压电调3 参数返回
  554. uavcan::Subscriber<uavcan::equipment::esc::HighVoltThruster3GetRegsFujian>* Thruster3GetRegs;
  555. Thruster3GetRegs = new uavcan::Subscriber<uavcan::equipment::esc::HighVoltThruster3GetRegsFujian>(*node);
  556. const int Tht3GetReg = Thruster3GetRegs->start(Thruster3GetRegs_cb_arr[_driver_index]);//定义回调函数用于接收
  557. if (Tht3GetReg<0)
  558. {
  559. return;
  560. }
  561. //高压电调1 定时参数返回
  562. uavcan::Subscriber<uavcan::equipment::esc::HighVoltThruster1timeback>* Thruster1timeback;
  563. Thruster1timeback = new uavcan::Subscriber<uavcan::equipment::esc::HighVoltThruster1timeback>(*node);
  564. const int Tht1timecb = Thruster1timeback->start(Thruster1timeback_cb_arr[_driver_index]);//定义回调函数用于接收
  565. if (Tht1timecb<0)
  566. {
  567. return;
  568. }
  569. //高压电调2 定时参数返回
  570. uavcan::Subscriber<uavcan::equipment::esc::HighVoltThruster2timeback>* Thruster2timeback;
  571. Thruster2timeback = new uavcan::Subscriber<uavcan::equipment::esc::HighVoltThruster2timeback>(*node);
  572. const int Tht2timecb = Thruster2timeback->start(Thruster2timeback_cb_arr[_driver_index]);//定义回调函数用于接收
  573. if (Tht2timecb<0)
  574. {
  575. return;
  576. }
  577. //高压电调3 定时参数返回
  578. uavcan::Subscriber<uavcan::equipment::esc::HighVoltThruster3timeback>* Thruster3timeback;
  579. Thruster3timeback = new uavcan::Subscriber<uavcan::equipment::esc::HighVoltThruster3timeback>(*node);
  580. const int Tht3timecb = Thruster3timeback->start(Thruster3timeback_cb_arr[_driver_index]);//定义回调函数用于接收
  581. if (Tht3timecb<0)
  582. {
  583. return;
  584. }
  585. //创建发送设备类型
  586. esc_SpeedCommands[driver_index] = new uavcan::Publisher<uavcan::equipment::esc::SpeedCommands>(*_node);
  587. esc_SpeedCommands[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(2));
  588. esc_SpeedCommands[driver_index]->setPriority(uavcan::TransferPriority::OneLowerThanHighest);
  589. //HVoltThtSetReg
  590. //高压电调参数设置
  591. HVoltThtSetReg[driver_index] = new uavcan::Publisher<uavcan::equipment::esc::HighVoltThrusterSetRegs>(*_node);
  592. HVoltThtSetReg[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20));
  593. HVoltThtSetReg[driver_index]->setPriority(uavcan::TransferPriority::OneLowerThanHighest);
  594. //创建发送设备类型
  595. esc_Bfd1[driver_index] = new uavcan::Publisher<uavcan::equipment::esc::Bfd1>(*_node);
  596. esc_Bfd1[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(2));
  597. esc_Bfd1[driver_index]->setPriority(uavcan::TransferPriority::OneLowerThanHighest);
  598. esc_Bfd2[driver_index] = new uavcan::Publisher<uavcan::equipment::esc::Bfd2>(*_node);
  599. esc_Bfd2[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(2));
  600. esc_Bfd2[driver_index]->setPriority(uavcan::TransferPriority::OneLowerThanHighest);
  601. esc_Bfd3[driver_index] = new uavcan::Publisher<uavcan::equipment::esc::Bfd3>(*_node);
  602. esc_Bfd3[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(2));
  603. esc_Bfd3[driver_index]->setPriority(uavcan::TransferPriority::OneLowerThanHighest);
  604. //esc_MotorCommands[driver_index] = new uavcan::Publisher<uavcan::equipment::esc::MotorCommands>(*_node);
  605. // esc_MotorCommands[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(2));
  606. // esc_MotorCommands[driver_index]->setPriority(uavcan::TransferPriority::OneLowerThanHighest);
  607. //创建参数设置类型
  608. SetFloatParam[driver_index] = new uavcan::Publisher<uavcan::equipment::esc::SetFloatParam>(*_node);
  609. SetFloatParam[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(2));
  610. SetFloatParam[driver_index]->setPriority(uavcan::TransferPriority::OneLowerThanHighest);
  611. //-----------------------------------
  612. act_out_array[driver_index] = new uavcan::Publisher<uavcan::equipment::actuator::ArrayCommand>(*_node);
  613. act_out_array[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(2));
  614. act_out_array[driver_index]->setPriority(uavcan::TransferPriority::OneLowerThanHighest);
  615. esc_raw[driver_index] = new uavcan::Publisher<uavcan::equipment::esc::RawCommand>(*_node);
  616. esc_raw[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(2));
  617. esc_raw[driver_index]->setPriority(uavcan::TransferPriority::OneLowerThanHighest);
  618. rgb_led[driver_index] = new uavcan::Publisher<uavcan::equipment::indication::LightsCommand>(*_node);
  619. rgb_led[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20));
  620. rgb_led[driver_index]->setPriority(uavcan::TransferPriority::OneHigherThanLowest);
  621. buzzer[driver_index] = new uavcan::Publisher<uavcan::equipment::indication::BeepCommand>(*_node);
  622. buzzer[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20));
  623. buzzer[driver_index]->setPriority(uavcan::TransferPriority::OneHigherThanLowest);
  624. safety_state[driver_index] = new uavcan::Publisher<ardupilot::indication::SafetyState>(*_node);
  625. safety_state[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20));
  626. safety_state[driver_index]->setPriority(uavcan::TransferPriority::OneHigherThanLowest);
  627. safety_button_listener[driver_index] = new uavcan::Subscriber<ardupilot::indication::Button, ButtonCb>(*_node);
  628. if (safety_button_listener[driver_index]) {
  629. safety_button_listener[driver_index]->start(ButtonCb(this, &handle_button));
  630. }
  631. _led_conf.devices_count = 0;
  632. if (enable_filters) {
  633. configureCanAcceptanceFilters(*_node);
  634. }
  635. /*
  636. * Informing other nodes that we're ready to work.
  637. * Default mode is INITIALIZING.
  638. */
  639. _node->setModeOperational();
  640. // Spin node for device discovery
  641. _node->spin(uavcan::MonotonicDuration::fromMSec(5000));
  642. snprintf(_thread_name, sizeof(_thread_name), "uavcan_%u", driver_index);
  643. if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_UAVCAN::loop, void), _thread_name, 4096, AP_HAL::Scheduler::PRIORITY_CAN, 0)) {
  644. _node->setModeOfflineAndPublish();
  645. debug_uavcan(1, "UAVCAN: couldn't create thread\n\r");
  646. return;
  647. }
  648. _initialized = true;
  649. debug_uavcan(2, "UAVCAN: init done\n\r");
  650. }
  651. void STM32_set_packet(uavcan::equipment::esc::SetFloatParam &_msgparam){
  652. _msgparam.number =set_stm32_param.number;
  653. _msgparam.flag = set_stm32_param.flag;
  654. _msgparam.XX1 = set_stm32_param.XX1;
  655. _msgparam.XX2 = set_stm32_param.XX2;
  656. _msgparam.XX3 = set_stm32_param.XX3;
  657. _msgparam.XX4 = set_stm32_param.XX4;
  658. _msgparam.YY = set_stm32_param.YY;
  659. }
  660. void crc_setmotor(uavcan::equipment::esc::HighVoltThrusterSetRegs &hvmesg){
  661. uint8_t crc_dataset[10]={0,0,0,0,0,0,0,0,0,0};
  662. hvmesg.NUMBER = hv_reg_set.aim;
  663. hvmesg.TYPE = hv_reg_set.code;
  664. hvmesg.PARNUMBER = (uint16_t)hv_reg_set.data[0] + (uint16_t)(hv_reg_set.data[1]<<8);
  665. crc_dataset[0] = hvmesg.NUMBER ;
  666. crc_dataset[1] = hvmesg.TYPE;
  667. crc_dataset[2] = hv_reg_set.data[0];
  668. crc_dataset[3] = hv_reg_set.data[1];
  669. for (uint8_t j = 0; j < 6; j++)
  670. {
  671. hvmesg.DATA[j] = hv_reg_set.data[j+2];
  672. crc_dataset[j+4] = hvmesg.DATA[j];
  673. }
  674. uint16_t crcdata = calc_crc_modbus(crc_dataset,10);
  675. hvmesg.DATA[6] = (uint8_t)crcdata;
  676. hvmesg.DATA[7] = (uint8_t)(crcdata>>8);
  677. }
  678. void crc_ackfault(uavcan::equipment::esc::HighVoltThrusterSetRegs &hvmesg,uint8_t number){
  679. uint8_t crc_dataset[10]={0,0,0,0,0,0,0,0,0,0};
  680. hvmesg.NUMBER = number;
  681. hvmesg.TYPE = 0x03;
  682. hvmesg.PARNUMBER = 0x5A5A;
  683. crc_dataset[0] = hvmesg.NUMBER ;
  684. crc_dataset[1] = hvmesg.TYPE;
  685. crc_dataset[2] = 0x5A;
  686. crc_dataset[3] = 0x5A;
  687. for (uint8_t j = 0; j < 6; j++)
  688. {
  689. hvmesg.DATA[j] = 0;
  690. crc_dataset[j+4] = hvmesg.DATA[j];
  691. }
  692. uint16_t crcdata = calc_crc_modbus(crc_dataset,10);
  693. hvmesg.DATA[6] = (uint8_t)crcdata;
  694. hvmesg.DATA[7] = (uint8_t)(crcdata>>8);
  695. }
  696. uint8_t HVreset = 0;
  697. void AP_UAVCAN::loop(void)
  698. {
  699. while (true) {
  700. if (!_initialized) {
  701. hal.scheduler->delay_microseconds(1000);
  702. continue;
  703. }
  704. const int error = _node->spin(uavcan::MonotonicDuration::fromMSec(1));
  705. if (error < 0) {
  706. hal.scheduler->delay_microseconds(100);
  707. continue;
  708. }
  709. //接收的周期性数据--------------------
  710. for(uint8_t j=0;j<12;j++){
  711. motor_from_stm32[j] = motors_receive[j];//读到转速
  712. }
  713. motor_stall_flag = motor_stall_state.all;//堵转
  714. propellerblock_flag = propeller_block.all;//推进器缠绕等级
  715. trackblock_flag = track_block.all;//推进器缠绕等级
  716. temperature_48Vpower = temperature_power;//can获取18B20温度
  717. board_voltage = voltage48V;//can获取48V电源
  718. driverleakstate = light_leak;//灯 漏水
  719. sublightstate = lightstate;
  720. HVmotor1 = Thruster1;
  721. HVmotor2 = Thruster2;
  722. HVmotor3 = Thruster3;
  723. rov_message.hvMotorMod = 0xffff;
  724. uavcan::equipment::esc::HighVoltThrusterSetRegs hvmesg;//高压电调参数设置
  725. //2-------------------aim取值0,1,2,3 高压电调设置
  726. if(hv_reg_set.aim == 0 || (hv_reg_set.aim &0x0F) !=0){
  727. crc_setmotor(hvmesg);
  728. hv_reg_set.aim = 0xF0;
  729. HVoltThtSetReg[_driver_index]->broadcast(hvmesg);//高压电调读取或者设置参数
  730. }
  731. //----------------------------------------------------------
  732. //2---------------高压电调设置end*******************************************
  733. //---------重启设置---------------------------
  734. static uint8_t stm32_rboot = 0;
  735. if((set_stm32_param.flag == 0xF0)&&(set_stm32_param.number ==12)){
  736. set_stm32_param.flag = 0;
  737. //消除缠绕
  738. stm32_rboot = 1;
  739. //高压电调消除故障
  740. HVreset = 7;
  741. }
  742. //-------发送数据-------------------------------------------------
  743. const AP_Motors6DOF &motors6dof = AP::motors6dof();//6自由度电机计算出来的PWM
  744. uavcan::equipment::esc::SingleMotorCommand msg;
  745. uavcan::equipment::esc::SpeedCommands msgarryspeed;
  746. uavcan::equipment::esc::SetFloatParam msgparam;
  747. uavcan::equipment::esc::Bfd1 msgbfd1;
  748. uavcan::equipment::esc::Bfd2 msgbfd2;
  749. uavcan::equipment::esc::Bfd3 msgbfd3;
  750. uint32_t nowtime = AP_HAL::micros();
  751. static uint32_t last_send_time = nowtime;
  752. if (nowtime - last_send_time >1000000UL/200 )//发送周期
  753. { last_send_time = nowtime;
  754. msgbfd1.index = 0;
  755. msgbfd1.speed1 = 0;
  756. msgbfd1.speed2 = 0;
  757. if ((HVreset&0x01)==1 )
  758. {
  759. if (HVmotor1.fault!=0)
  760. {
  761. msgbfd1.speed3 = 0;
  762. }else{
  763. msgbfd1.speed3 = motors6dof.motor_to_can[2];
  764. HVreset = HVreset&0x06;
  765. }
  766. }else{
  767. msgbfd1.speed3 = motors6dof.motor_to_can[2];
  768. }
  769. esc_Bfd1[_driver_index]->broadcast(msgbfd1);//大约100HZ 在没有设置参数的情况下 发送驱动*/
  770. //-----------------------------------------------------------------------------------------------------
  771. msgbfd2.index = 0;
  772. if ((HVreset&0x02)==2 )
  773. {
  774. if (HVmotor2.fault!=0)
  775. {
  776. msgbfd2.speed1 = 0;
  777. }else{
  778. msgbfd2.speed1 = motors6dof.motor_to_can[3];
  779. HVreset =HVreset&0x05;
  780. }
  781. }else{
  782. msgbfd2.speed1 = motors6dof.motor_to_can[3];
  783. }
  784. if ((HVreset&0x04)==4 )
  785. {
  786. if (HVmotor3.fault!=0)
  787. {
  788. msgbfd2.speed2 = 0;
  789. }else{
  790. msgbfd2.speed2 = motors6dof.motor_to_can[4];
  791. HVreset = HVreset&0x03;
  792. }
  793. }else{
  794. msgbfd2.speed2 = motors6dof.motor_to_can[4];
  795. }
  796. msgbfd2.speed3 = 0;
  797. esc_Bfd2[_driver_index]->broadcast(msgbfd2);//大约100HZ 在没有设置参数的情况下 发送驱动*/
  798. //-------------------------------------------------------------------------------------------------
  799. msgbfd3.index = 0;
  800. msgbfd3.speed1 = 0;
  801. msgbfd3.speed2 = 0;
  802. msgbfd3.speed3 = 0;
  803. esc_Bfd3[_driver_index]->broadcast(msgbfd3);//大约100HZ 在没有设置参数的情况下 发送驱动*/
  804. }
  805. uint32_t nowtime2 = AP_HAL::micros();
  806. static uint32_t last_send_time2 = nowtime2;
  807. static uint32_t lasttime_reboot = 0;
  808. if(nowtime2 - last_send_time2 >1000000UL/200 )
  809. { last_send_time2 = nowtime2;
  810. if(stm32_rboot==1)
  811. {
  812. static uint8_t reboot_cnt = 0;
  813. if((motor_from_stm32[0]!=0 || motor_from_stm32[1]!=0 ||motor_from_stm32[8]!=0 ||motor_from_stm32[9]!=0)&&(reboot_cnt<170)){
  814. msgarryspeed.rpm.push_back(0);
  815. msgarryspeed.rpm.push_back(0);
  816. msgarryspeed.rpm.push_back(0);
  817. msgarryspeed.rpm.push_back(0);
  818. msgarryspeed.rpm.push_back(0);
  819. msgarryspeed.rpm.push_back(0);
  820. reboot_cnt++;
  821. esc_SpeedCommands[_driver_index]->broadcast(msgarryspeed);//大约100HZ 在没有设置参数的情况下 发送驱动
  822. }else{
  823. stm32_rboot = 0;
  824. reboot_cnt=0;
  825. lasttime_reboot = AP_HAL::millis();
  826. }
  827. }
  828. uint32_t errortime_reboot = 0;
  829. uint32_t nowtime_restart = AP_HAL::millis();//ms
  830. errortime_reboot = nowtime_restart - lasttime_reboot;//重启时间
  831. if ((errortime_reboot > reboot_time)&&(stm32_rboot==0))
  832. {
  833. int16_t pwm ;
  834. pwm = motors6dof.motor_to_can[0];
  835. msgarryspeed.rpm.push_back(pwm);
  836. pwm = motors6dof.motor_to_can[1];
  837. msgarryspeed.rpm.push_back(pwm);
  838. pwm = motors6dof.motor_to_can[8];
  839. msgarryspeed.rpm.push_back(pwm);
  840. pwm = motors6dof.motor_to_can[9];
  841. msgarryspeed.rpm.push_back(pwm);
  842. pwm = sub.lights;
  843. msgarryspeed.rpm.push_back(pwm);
  844. pwm = sub.usblpoweroff;
  845. msgarryspeed.rpm.push_back(pwm);
  846. esc_SpeedCommands[_driver_index]->broadcast(msgarryspeed);//大约100HZ 在没有设置参数的情况下 发送驱动
  847. }
  848. static int16_t c2 = 0;
  849. c2++;
  850. if(c2>200){
  851. c2 =0 ;
  852. gcs().send_text(MAV_SEVERITY_WARNING, "motorget %d %d.",(int)hv_reg_get.aim,(int)hv_reg_get.data[0]);
  853. }
  854. //+++++++++设置stm32 参数----------------------------------------
  855. // 上位机没有发送的时候不会发送 退出初始化之后才能写参数
  856. if( !sub.motors.armed()&&(((set_stm32_param.flag == 0xF0)&&(set_stm32_param.number!=16))||(set_stm32_param.flag == 0xFF)))
  857. {
  858. STM32_set_packet(msgparam);
  859. SetFloatParam[_driver_index]->broadcast(msgparam);//广播发送
  860. set_stm32_param.flag = 0x00;
  861. gcs().send_text(MAV_SEVERITY_WARNING, "set %x%x%x%x.%x .",msgparam.XX1,msgparam.XX2,msgparam.XX3,msgparam.XX4,msgparam.YY);
  862. }
  863. }
  864. }
  865. }
  866. ///// SRV output /////
  867. void AP_UAVCAN::SRV_send_actuator(void)
  868. {
  869. uint8_t starting_servo = 0;
  870. bool repeat_send;
  871. WITH_SEMAPHORE(SRV_sem);
  872. do {
  873. repeat_send = false;
  874. uavcan::equipment::actuator::ArrayCommand msg;
  875. uint8_t i;
  876. // UAVCAN can hold maximum of 15 commands in one frame
  877. for (i = 0; starting_servo < UAVCAN_SRV_NUMBER && i < 15; starting_servo++) {
  878. uavcan::equipment::actuator::Command cmd;
  879. /*
  880. * Servo output uses a range of 1000-2000 PWM for scaling.
  881. * This converts output PWM from [1000:2000] range to [-1:1] range that
  882. * is passed to servo as unitless type via UAVCAN.
  883. * This approach allows for MIN/TRIM/MAX values to be used fully on
  884. * autopilot side and for servo it should have the setup to provide maximum
  885. * physically possible throws at [-1:1] limits.
  886. */
  887. if (_SRV_conf[starting_servo].servo_pending && ((((uint32_t) 1) << starting_servo) & _servo_bm)) {
  888. cmd.actuator_id = starting_servo + 1;
  889. // TODO: other types
  890. cmd.command_type = uavcan::equipment::actuator::Command::COMMAND_TYPE_UNITLESS;
  891. // TODO: failsafe, safety
  892. cmd.command_value = constrain_float(((float) _SRV_conf[starting_servo].pulse - 1000.0) / 500.0 - 1.0, -1.0, 1.0);
  893. msg.commands.push_back(cmd);
  894. i++;
  895. }
  896. }
  897. if (i > 0) {
  898. act_out_array[_driver_index]->broadcast(msg);
  899. if (i == 15) {
  900. repeat_send = true;
  901. }
  902. }
  903. } while (repeat_send);
  904. }
  905. void AP_UAVCAN::SRV_send_esc(void)
  906. {
  907. static const int cmd_max = uavcan::equipment::esc::RawCommand::FieldTypes::cmd::RawValueType::max();
  908. uavcan::equipment::esc::RawCommand esc_msg;
  909. uint8_t active_esc_num = 0, max_esc_num = 0;
  910. uint8_t k = 0;
  911. WITH_SEMAPHORE(SRV_sem);
  912. // find out how many esc we have enabled and if they are active at all
  913. for (uint8_t i = 0; i < UAVCAN_SRV_NUMBER; i++) {
  914. if ((((uint32_t) 1) << i) & _esc_bm) {
  915. max_esc_num = i + 1;
  916. if (_SRV_conf[i].esc_pending) {
  917. active_esc_num++;
  918. }
  919. }
  920. }
  921. // if at least one is active (update) we need to send to all
  922. if (active_esc_num > 0) {
  923. k = 0;
  924. for (uint8_t i = 0; i < max_esc_num && k < 20; i++) {
  925. if ((((uint32_t) 1) << i) & _esc_bm) {
  926. // TODO: ESC negative scaling for reverse thrust and reverse rotation
  927. float scaled = cmd_max * (hal.rcout->scale_esc_to_unity(_SRV_conf[i].pulse) + 1.0) / 2.0;
  928. scaled = constrain_float(scaled, 0, cmd_max);
  929. esc_msg.cmd.push_back(static_cast<int>(scaled));
  930. } else {
  931. esc_msg.cmd.push_back(static_cast<unsigned>(0));
  932. }
  933. k++;
  934. }
  935. esc_raw[_driver_index]->broadcast(esc_msg);
  936. }
  937. }
  938. void AP_UAVCAN::SRV_push_servos()
  939. {
  940. WITH_SEMAPHORE(SRV_sem);
  941. for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
  942. // Check if this channels has any function assigned
  943. if (SRV_Channels::channel_function(i)) {
  944. _SRV_conf[i].pulse = SRV_Channels::srv_channel(i)->get_output_pwm();
  945. _SRV_conf[i].esc_pending = true;
  946. _SRV_conf[i].servo_pending = true;
  947. }
  948. }
  949. _SRV_armed = hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED;
  950. }
  951. ///// LED /////
  952. void AP_UAVCAN::led_out_send()
  953. {
  954. uint64_t now = AP_HAL::micros64();
  955. if ((now - _led_conf.last_update) < LED_DELAY_US) {
  956. return;
  957. }
  958. uavcan::equipment::indication::LightsCommand msg;
  959. {
  960. WITH_SEMAPHORE(_led_out_sem);
  961. if (_led_conf.devices_count == 0) {
  962. return;
  963. }
  964. uavcan::equipment::indication::SingleLightCommand cmd;
  965. for (uint8_t i = 0; i < _led_conf.devices_count; i++) {
  966. cmd.light_id =_led_conf.devices[i].led_index;
  967. cmd.color.red = _led_conf.devices[i].red >> 3;
  968. cmd.color.green = _led_conf.devices[i].green >> 2;
  969. cmd.color.blue = _led_conf.devices[i].blue >> 3;
  970. msg.commands.push_back(cmd);
  971. }
  972. }
  973. rgb_led[_driver_index]->broadcast(msg);
  974. _led_conf.last_update = now;
  975. }
  976. bool AP_UAVCAN::led_write(uint8_t led_index, uint8_t red, uint8_t green, uint8_t blue)
  977. {
  978. if (_led_conf.devices_count >= AP_UAVCAN_MAX_LED_DEVICES) {
  979. return false;
  980. }
  981. WITH_SEMAPHORE(_led_out_sem);
  982. // check if a device instance exists. if so, break so the instance index is remembered
  983. uint8_t instance = 0;
  984. for (; instance < _led_conf.devices_count; instance++) {
  985. if (_led_conf.devices[instance].led_index == led_index) {
  986. break;
  987. }
  988. }
  989. // load into the correct instance.
  990. // if an existing instance was found in above for loop search,
  991. // then instance value is < _led_conf.devices_count.
  992. // otherwise a new one was just found so we increment the count.
  993. // Either way, the correct instance is the current value of instance
  994. _led_conf.devices[instance].led_index = led_index;
  995. _led_conf.devices[instance].red = red;
  996. _led_conf.devices[instance].green = green;
  997. _led_conf.devices[instance].blue = blue;
  998. if (instance == _led_conf.devices_count) {
  999. _led_conf.devices_count++;
  1000. }
  1001. return true;
  1002. }
  1003. // buzzer send
  1004. void AP_UAVCAN::buzzer_send()
  1005. {
  1006. uavcan::equipment::indication::BeepCommand msg;
  1007. WITH_SEMAPHORE(_buzzer.sem);
  1008. uint8_t mask = (1U << _driver_index);
  1009. if ((_buzzer.pending_mask & mask) == 0) {
  1010. return;
  1011. }
  1012. _buzzer.pending_mask &= ~mask;
  1013. msg.frequency = _buzzer.frequency;
  1014. msg.duration = _buzzer.duration;
  1015. buzzer[_driver_index]->broadcast(msg);
  1016. }
  1017. // buzzer support
  1018. void AP_UAVCAN::set_buzzer_tone(float frequency, float duration_s)
  1019. {
  1020. WITH_SEMAPHORE(_buzzer.sem);
  1021. _buzzer.frequency = frequency;
  1022. _buzzer.duration = duration_s;
  1023. _buzzer.pending_mask = 0xFF;
  1024. }
  1025. // SafetyState send
  1026. void AP_UAVCAN::safety_state_send()
  1027. {
  1028. ardupilot::indication::SafetyState msg;
  1029. uint32_t now = AP_HAL::millis();
  1030. if (now - _last_safety_state_ms < 500) {
  1031. // update at 2Hz
  1032. return;
  1033. }
  1034. _last_safety_state_ms = now;
  1035. switch (hal.util->safety_switch_state()) {
  1036. case AP_HAL::Util::SAFETY_ARMED:
  1037. msg.status = ardupilot::indication::SafetyState::STATUS_SAFETY_OFF;
  1038. break;
  1039. case AP_HAL::Util::SAFETY_DISARMED:
  1040. msg.status = ardupilot::indication::SafetyState::STATUS_SAFETY_ON;
  1041. break;
  1042. default:
  1043. // nothing to send
  1044. return;
  1045. }
  1046. safety_state[_driver_index]->broadcast(msg);
  1047. }
  1048. /*
  1049. handle Button message
  1050. */
  1051. void AP_UAVCAN::handle_button(AP_UAVCAN* ap_uavcan, uint8_t node_id, const ButtonCb &cb)
  1052. {
  1053. switch (cb.msg->button) {
  1054. case ardupilot::indication::Button::BUTTON_SAFETY: {
  1055. AP_BoardConfig *brdconfig = AP_BoardConfig::get_singleton();
  1056. if (brdconfig && brdconfig->safety_button_handle_pressed(cb.msg->press_time)) {
  1057. AP_HAL::Util::safety_state state = hal.util->safety_switch_state();
  1058. if (state == AP_HAL::Util::SAFETY_ARMED) {
  1059. hal.rcout->force_safety_on();
  1060. } else {
  1061. hal.rcout->force_safety_off();
  1062. }
  1063. }
  1064. break;
  1065. }
  1066. }
  1067. }
  1068. AP_UAVCAN *AP_UAVCAN::_singleton;
  1069. namespace AP {
  1070. AP_UAVCAN &uavcan()
  1071. {
  1072. return *AP_UAVCAN::get_singleton();
  1073. }
  1074. };
  1075. #endif // HAL_WITH_UAVCAN