AP_UAVCAN.cpp 47 KB

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