AP_UAVCAN.cpp 22 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681
  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 <AP_BoardConfig/AP_BoardConfig.h>
  24. #include <AP_BoardConfig/AP_BoardConfig_CAN.h>
  25. #include <uavcan/transport/can_acceptance_filter_configurator.hpp>
  26. #include <uavcan/equipment/actuator/ArrayCommand.hpp>
  27. #include <uavcan/equipment/actuator/Command.hpp>
  28. #include <uavcan/equipment/actuator/Status.hpp>
  29. #include <uavcan/equipment/esc/RawCommand.hpp>
  30. #include <uavcan/equipment/esc/Status.hpp>
  31. //#include <uavcan/equipment/esc/Status1.hpp>
  32. //#include <uavcan/equipment/esc/Status2.hpp>
  33. //#include <uavcan/equipment/esc/Status3.hpp>
  34. //#include <uavcan/equipment/esc/Status4.hpp>
  35. //#include <uavcan/equipment/esc/Status5.hpp>
  36. #include <uavcan/equipment/esc/RPMCommand.hpp>
  37. #include <uavcan/equipment/indication/LightsCommand.hpp>
  38. #include <uavcan/equipment/indication/SingleLightCommand.hpp>
  39. #include <uavcan/equipment/indication/BeepCommand.hpp>
  40. #include <uavcan/equipment/indication/RGB565.hpp>
  41. #include <ardupilot/indication/SafetyState.hpp>
  42. #include <ardupilot/indication/Button.hpp>
  43. #include <AP_Baro/AP_Baro_UAVCAN.h>
  44. #include <AP_RangeFinder/AP_RangeFinder_UAVCAN.h>
  45. #include <AP_GPS/AP_GPS_UAVCAN.h>
  46. #include <AP_BattMonitor/AP_BattMonitor_UAVCAN.h>
  47. #include <AP_Compass/AP_Compass_UAVCAN.h>
  48. #include <AP_Airspeed/AP_Airspeed_UAVCAN.h>
  49. #include <SRV_Channel/SRV_Channel.h>
  50. #include <AP_OpticalFlow/AP_OpticalFlow_HereFlow.h>
  51. #define LED_DELAY_US 50000
  52. extern const AP_HAL::HAL& hal;
  53. #define debug_uavcan(level_debug, fmt, args...) do { if ((level_debug) <= AP::can().get_debug_level_driver(_driver_index)) { printf(fmt, ##args); }} while (0)
  54. // Translation of all messages from UAVCAN structures into AP structures is done
  55. // in AP_UAVCAN and not in corresponding drivers.
  56. // The overhead of including definitions of DSDL is very high and it is best to
  57. // concentrate in one place.
  58. // table of user settable CAN bus parameters
  59. const AP_Param::GroupInfo AP_UAVCAN::var_info[] = {
  60. // @Param: NODE
  61. // @DisplayName: UAVCAN node that is used for this network
  62. // @Description: UAVCAN node should be set implicitly
  63. // @Range: 1 250
  64. // @User: Advanced
  65. AP_GROUPINFO("NODE", 1, AP_UAVCAN, _uavcan_node, 10),
  66. // @Param: SRV_BM
  67. // @DisplayName: RC Out channels to be transmitted as servo over UAVCAN
  68. // @Description: Bitmask with one set for channel to be transmitted as a servo command over UAVCAN
  69. // @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
  70. // @User: Advanced
  71. AP_GROUPINFO("SRV_BM", 2, AP_UAVCAN, _servo_bm, 0),
  72. // @Param: ESC_BM
  73. // @DisplayName: RC Out channels to be transmitted as ESC over UAVCAN
  74. // @Description: Bitmask with one set for channel to be transmitted as a ESC command over UAVCAN
  75. // @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
  76. // @User: Advanced
  77. AP_GROUPINFO("ESC_BM", 3, AP_UAVCAN, _esc_bm, 0),
  78. // @Param: SRV_RT
  79. // @DisplayName: Servo output rate
  80. // @Description: Maximum transmit rate for servo outputs
  81. // @Range: 1 200
  82. // @Units: Hz
  83. // @User: Advanced
  84. AP_GROUPINFO("SRV_RT", 4, AP_UAVCAN, _servo_rate_hz, 50),
  85. AP_GROUPEND
  86. };
  87. // this is the timeout in milliseconds for periodic message types. We
  88. // set this to 1 to minimise resend of stale msgs
  89. #define CAN_PERIODIC_TX_TIMEOUT_MS 2
  90. // publisher interfaces
  91. static uavcan::Publisher<uavcan::equipment::esc::RPMCommand>* vesc_rpm[MAX_NUMBER_OF_CAN_DRIVERS];
  92. static uavcan::Publisher<uavcan::equipment::actuator::ArrayCommand>* act_out_array[MAX_NUMBER_OF_CAN_DRIVERS];
  93. static uavcan::Publisher<uavcan::equipment::esc::RawCommand>* esc_raw[MAX_NUMBER_OF_CAN_DRIVERS];
  94. static uavcan::Publisher<uavcan::equipment::indication::LightsCommand>* rgb_led[MAX_NUMBER_OF_CAN_DRIVERS];
  95. static uavcan::Publisher<uavcan::equipment::indication::BeepCommand>* buzzer[MAX_NUMBER_OF_CAN_DRIVERS];
  96. static uavcan::Publisher<ardupilot::indication::SafetyState>* safety_state[MAX_NUMBER_OF_CAN_DRIVERS];
  97. // subscribers
  98. // handler SafteyButton
  99. UC_REGISTRY_BINDER(ButtonCb, ardupilot::indication::Button);
  100. static uavcan::Subscriber<ardupilot::indication::Button, ButtonCb> *safety_button_listener[MAX_NUMBER_OF_CAN_DRIVERS];
  101. struct ESCTelemetryData thruster_init = {0,0.0,0.0,0.0,0,0,0};
  102. //struct ESCTelemetryData thruster[6]={thruster_init,thruster_init,thruster_init,thruster_init,thruster_init,thruster_init};
  103. AP_UAVCAN::AP_UAVCAN() :
  104. _node_allocator()
  105. {
  106. AP_Param::setup_object_defaults(this, var_info);
  107. _singleton = this;
  108. for (uint8_t i = 0; i < UAVCAN_SRV_NUMBER; i++) {
  109. _SRV_conf[i].esc_pending = false;
  110. _SRV_conf[i].servo_pending = false;
  111. }
  112. for(uint8_t i = 0; i < 6; i++)
  113. {
  114. thruster[i]=thruster_init;
  115. }
  116. debug_uavcan(2, "AP_UAVCAN constructed\n\r");
  117. }
  118. AP_UAVCAN::~AP_UAVCAN()
  119. {
  120. }
  121. static void esc_status_st_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::Status>&msg,uint8_t mgr )
  122. {//接收到的数据在这里处理,打印出来
  123. AP_UAVCAN &uavcan = AP::uavcan();//6自由度电机计算出来的PWM
  124. uint8_t i = msg.esc_index;
  125. uavcan.thruster[i].error_count = msg.error_count;
  126. uavcan.thruster[i].voltage = (float)msg.voltage;
  127. uavcan.thruster[i].current = (float)msg.current;
  128. uavcan.thruster[i].temperature = (float)msg.temperature-273.15;
  129. uavcan.thruster[i].rpm = (int32_t)msg.rpm;
  130. uavcan.thruster[i].power_rating_pct= (uint8_t)msg.power_rating_pct;
  131. static uint8_t cnt = 0;
  132. cnt++;
  133. if (cnt>50)
  134. {
  135. gcs().send_text(MAV_SEVERITY_INFO, "motor_index = %d %d %d %d .",(int)i,(int)uavcan.thruster[i].rpm,(int)uavcan.thruster[i].power_rating_pct,(int)uavcan.thruster[i].esc_index);
  136. gcs().send_text(MAV_SEVERITY_INFO, "motor %x %f %f %f.",(int)uavcan.thruster[i].error_count,(float)uavcan.thruster[i].voltage,(float)uavcan.thruster[i].current,(float)uavcan.thruster[i].temperature);
  137. cnt=0;
  138. }
  139. /*uint8_t i = msg.esc_index;
  140. thruster[i].error_count = msg.error_count;
  141. thruster[i].voltage = (float)msg.voltage;
  142. thruster[i].current = (float)msg.current;
  143. thruster[i].temperature = (float)msg.temperature;
  144. thruster[i].rpm = (int32_t)msg.rpm;
  145. thruster[i].power_rating_pct= (uint8_t)msg.power_rating_pct;
  146. static uint8_t cnt = 0;
  147. cnt++;
  148. if (cnt>50)
  149. {
  150. gcs().send_text(MAV_SEVERITY_WARNING, "motor %x %f %f %f.",(int)thruster[i].error_count,(float)thruster[i].voltage,(float)thruster[i].current,(float)thruster[i].temperature);
  151. gcs().send_text(MAV_SEVERITY_WARNING, "motor_index = 0 %d %d %d .",(int)thruster[i].rpm,(int)thruster[i].power_rating_pct,(int)thruster[i].esc_index);
  152. cnt=0;
  153. }*/
  154. }
  155. static void esc_status_st_cb0(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::Status>&msg ){
  156. esc_status_st_cb(msg,0);
  157. }
  158. static void esc_status_st_cb1(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::Status>&msg ){
  159. esc_status_st_cb(msg,1);
  160. }
  161. static void (*esc_status_st_cb_arr[2])(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::Status>&msg )
  162. ={esc_status_st_cb0,esc_status_st_cb1};
  163. AP_UAVCAN *AP_UAVCAN::get_uavcan(uint8_t driver_index)
  164. {
  165. if (driver_index >= AP::can().get_num_drivers() ||
  166. AP::can().get_protocol_type(driver_index) != AP_BoardConfig_CAN::Protocol_Type_UAVCAN) {
  167. return nullptr;
  168. }
  169. return static_cast<AP_UAVCAN*>(AP::can().get_driver(driver_index));
  170. }
  171. void AP_UAVCAN::init(uint8_t driver_index, bool enable_filters)
  172. {
  173. if (_initialized) {
  174. debug_uavcan(2, "UAVCAN: init called more than once\n\r");
  175. return;
  176. }
  177. _driver_index = driver_index;
  178. AP_HAL::CANManager* can_mgr = hal.can_mgr[driver_index];
  179. if (can_mgr == nullptr) {
  180. debug_uavcan(2, "UAVCAN: init called for inexisting CAN driver\n\r");
  181. return;
  182. }
  183. if (!can_mgr->is_initialized()) {
  184. debug_uavcan(1, "UAVCAN: CAN driver not initialized\n\r");
  185. return;
  186. }
  187. uavcan::ICanDriver* driver = can_mgr->get_driver();
  188. if (driver == nullptr) {
  189. debug_uavcan(2, "UAVCAN: can't get UAVCAN interface driver\n\r");
  190. return;
  191. }
  192. _node = new uavcan::Node<0>(*driver, SystemClock::instance(), _node_allocator);
  193. if (_node == nullptr) {
  194. debug_uavcan(1, "UAVCAN: couldn't allocate node\n\r");
  195. return;
  196. }
  197. if (_node->isStarted()) {
  198. debug_uavcan(2, "UAVCAN: node was already started?\n\r");
  199. return;
  200. }
  201. uavcan::NodeID self_node_id(_uavcan_node);
  202. _node->setNodeID(self_node_id);
  203. char ndname[20];
  204. snprintf(ndname, sizeof(ndname), "org.ardupilot:%u", driver_index);
  205. uavcan::NodeStatusProvider::NodeName name(ndname);
  206. _node->setName(name);
  207. uavcan::protocol::SoftwareVersion sw_version; // Standard type uavcan.protocol.SoftwareVersion
  208. sw_version.major = AP_UAVCAN_SW_VERS_MAJOR;
  209. sw_version.minor = AP_UAVCAN_SW_VERS_MINOR;
  210. _node->setSoftwareVersion(sw_version);
  211. uavcan::protocol::HardwareVersion hw_version; // Standard type uavcan.protocol.HardwareVersion
  212. hw_version.major = AP_UAVCAN_HW_VERS_MAJOR;
  213. hw_version.minor = AP_UAVCAN_HW_VERS_MINOR;
  214. const uint8_t uid_buf_len = hw_version.unique_id.capacity();
  215. uint8_t uid_len = uid_buf_len;
  216. uint8_t unique_id[uid_buf_len];
  217. if (hal.util->get_system_id_unformatted(unique_id, uid_len)) {
  218. uavcan::copy(unique_id, unique_id + uid_len, hw_version.unique_id.begin());
  219. }
  220. _node->setHardwareVersion(hw_version);
  221. int start_res = _node->start();
  222. if (start_res < 0) {
  223. debug_uavcan(1, "UAVCAN: node start problem, error %d\n\r", start_res);
  224. return;
  225. }
  226. //Start Servers
  227. #ifdef HAS_UAVCAN_SERVERS
  228. _servers.init(*_node);
  229. #endif
  230. // Roundup all subscribers from supported drivers
  231. AP_GPS_UAVCAN::subscribe_msgs(this);
  232. AP_Compass_UAVCAN::subscribe_msgs(this);
  233. AP_Baro_UAVCAN::subscribe_msgs(this);
  234. AP_BattMonitor_UAVCAN::subscribe_msgs(this);
  235. AP_Airspeed_UAVCAN::subscribe_msgs(this);
  236. AP_OpticalFlow_HereFlow::subscribe_msgs(this);
  237. AP_RangeFinder_UAVCAN::subscribe_msgs(this);
  238. auto *node= get_node();
  239. uavcan::Subscriber<uavcan::equipment::esc::Status>* esc_status;
  240. esc_status = new uavcan::Subscriber<uavcan::equipment::esc::Status>(*node);
  241. const int esc_status_res = esc_status->start(esc_status_st_cb_arr[_driver_index]);//定义回调函数用于接收
  242. if (esc_status_res<0)
  243. {
  244. return;
  245. }
  246. vesc_rpm[driver_index] = new uavcan::Publisher<uavcan::equipment::esc::RPMCommand>(*_node);
  247. vesc_rpm[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(2));
  248. vesc_rpm[driver_index]->setPriority(uavcan::TransferPriority::OneLowerThanHighest);
  249. act_out_array[driver_index] = new uavcan::Publisher<uavcan::equipment::actuator::ArrayCommand>(*_node);
  250. act_out_array[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(2));
  251. act_out_array[driver_index]->setPriority(uavcan::TransferPriority::OneLowerThanHighest);
  252. esc_raw[driver_index] = new uavcan::Publisher<uavcan::equipment::esc::RawCommand>(*_node);
  253. esc_raw[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(2));
  254. esc_raw[driver_index]->setPriority(uavcan::TransferPriority::OneLowerThanHighest);
  255. rgb_led[driver_index] = new uavcan::Publisher<uavcan::equipment::indication::LightsCommand>(*_node);
  256. rgb_led[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20));
  257. rgb_led[driver_index]->setPriority(uavcan::TransferPriority::OneHigherThanLowest);
  258. buzzer[driver_index] = new uavcan::Publisher<uavcan::equipment::indication::BeepCommand>(*_node);
  259. buzzer[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20));
  260. buzzer[driver_index]->setPriority(uavcan::TransferPriority::OneHigherThanLowest);
  261. safety_state[driver_index] = new uavcan::Publisher<ardupilot::indication::SafetyState>(*_node);
  262. safety_state[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20));
  263. safety_state[driver_index]->setPriority(uavcan::TransferPriority::OneHigherThanLowest);
  264. safety_button_listener[driver_index] = new uavcan::Subscriber<ardupilot::indication::Button, ButtonCb>(*_node);
  265. if (safety_button_listener[driver_index]) {
  266. safety_button_listener[driver_index]->start(ButtonCb(this, &handle_button));
  267. }
  268. _led_conf.devices_count = 0;
  269. if (enable_filters) {
  270. configureCanAcceptanceFilters(*_node);
  271. }
  272. /*
  273. * Informing other nodes that we're ready to work.
  274. * Default mode is INITIALIZING.
  275. */
  276. _node->setModeOperational();
  277. // Spin node for device discovery
  278. _node->spin(uavcan::MonotonicDuration::fromMSec(5000));
  279. snprintf(_thread_name, sizeof(_thread_name), "uavcan_%u", driver_index);
  280. if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_UAVCAN::loop, void), _thread_name, 4096, AP_HAL::Scheduler::PRIORITY_CAN, 0)) {
  281. _node->setModeOfflineAndPublish();
  282. debug_uavcan(1, "UAVCAN: couldn't create thread\n\r");
  283. return;
  284. }
  285. _initialized = true;
  286. debug_uavcan(2, "UAVCAN: init done\n\r");
  287. }
  288. void AP_UAVCAN::loop(void)
  289. {
  290. while (true) {
  291. if (!_initialized) {
  292. hal.scheduler->delay_microseconds(1000);
  293. continue;
  294. }
  295. const int error = _node->spin(uavcan::MonotonicDuration::fromMSec(1));
  296. if (error < 0) {
  297. hal.scheduler->delay_microseconds(100);
  298. continue;
  299. }
  300. uint32_t now = AP_HAL::micros();
  301. uint32_t servo_period_us = 1000000UL / unsigned(_servo_rate_hz.get());
  302. if (now - _SRV_last_send_us >= servo_period_us){
  303. _SRV_last_send_us = now;
  304. const AP_Motors6DOF &motors6dof = AP::motors6dof();//6自由度电机计算出来的PWM
  305. uavcan::equipment::esc::RPMCommand msg;
  306. msg.rpm.push_back(motors6dof.motor_to_can[0]);
  307. msg.rpm.push_back(motors6dof.motor_to_can[1]);
  308. msg.rpm.push_back(motors6dof.motor_to_can[2]);
  309. msg.rpm.push_back(motors6dof.motor_to_can[3]);
  310. msg.rpm.push_back(motors6dof.motor_to_can[4]);
  311. msg.rpm.push_back(motors6dof.motor_to_can[5]);
  312. vesc_rpm[_driver_index]->broadcast(msg);
  313. }
  314. }
  315. }
  316. ///// SRV output /////
  317. void AP_UAVCAN::SRV_send_actuator(void)
  318. {
  319. uint8_t starting_servo = 0;
  320. bool repeat_send;
  321. WITH_SEMAPHORE(SRV_sem);
  322. do {
  323. repeat_send = false;
  324. uavcan::equipment::actuator::ArrayCommand msg;
  325. uint8_t i;
  326. // UAVCAN can hold maximum of 15 commands in one frame
  327. for (i = 0; starting_servo < UAVCAN_SRV_NUMBER && i < 15; starting_servo++) {
  328. uavcan::equipment::actuator::Command cmd;
  329. /*
  330. * Servo output uses a range of 1000-2000 PWM for scaling.
  331. * This converts output PWM from [1000:2000] range to [-1:1] range that
  332. * is passed to servo as unitless type via UAVCAN.
  333. * This approach allows for MIN/TRIM/MAX values to be used fully on
  334. * autopilot side and for servo it should have the setup to provide maximum
  335. * physically possible throws at [-1:1] limits.
  336. */
  337. if (_SRV_conf[starting_servo].servo_pending && ((((uint32_t) 1) << starting_servo) & _servo_bm)) {
  338. cmd.actuator_id = starting_servo + 1;
  339. // TODO: other types
  340. cmd.command_type = uavcan::equipment::actuator::Command::COMMAND_TYPE_UNITLESS;
  341. // TODO: failsafe, safety
  342. cmd.command_value = constrain_float(((float) _SRV_conf[starting_servo].pulse - 1000.0) / 500.0 - 1.0, -1.0, 1.0);
  343. msg.commands.push_back(cmd);
  344. i++;
  345. }
  346. }
  347. if (i > 0) {
  348. act_out_array[_driver_index]->broadcast(msg);
  349. if (i == 15) {
  350. repeat_send = true;
  351. }
  352. }
  353. } while (repeat_send);
  354. }
  355. void AP_UAVCAN::SRV_send_esc(void)
  356. {
  357. static const int cmd_max = uavcan::equipment::esc::RawCommand::FieldTypes::cmd::RawValueType::max();
  358. uavcan::equipment::esc::RawCommand esc_msg;
  359. uint8_t active_esc_num = 0, max_esc_num = 0;
  360. uint8_t k = 0;
  361. WITH_SEMAPHORE(SRV_sem);
  362. // find out how many esc we have enabled and if they are active at all
  363. for (uint8_t i = 0; i < UAVCAN_SRV_NUMBER; i++) {
  364. if ((((uint32_t) 1) << i) & _esc_bm) {
  365. max_esc_num = i + 1;
  366. if (_SRV_conf[i].esc_pending) {
  367. active_esc_num++;
  368. }
  369. }
  370. }
  371. // if at least one is active (update) we need to send to all
  372. if (active_esc_num > 0) {
  373. k = 0;
  374. for (uint8_t i = 0; i < max_esc_num && k < 20; i++) {
  375. if ((((uint32_t) 1) << i) & _esc_bm) {
  376. // TODO: ESC negative scaling for reverse thrust and reverse rotation
  377. float scaled = cmd_max * (hal.rcout->scale_esc_to_unity(_SRV_conf[i].pulse) + 1.0) / 2.0;
  378. scaled = constrain_float(scaled, 0, cmd_max);
  379. esc_msg.cmd.push_back(static_cast<int>(scaled));
  380. } else {
  381. esc_msg.cmd.push_back(static_cast<unsigned>(0));
  382. }
  383. k++;
  384. }
  385. esc_raw[_driver_index]->broadcast(esc_msg);
  386. }
  387. }
  388. void AP_UAVCAN::SRV_push_servos()
  389. {
  390. WITH_SEMAPHORE(SRV_sem);
  391. for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
  392. // Check if this channels has any function assigned
  393. if (SRV_Channels::channel_function(i)) {
  394. _SRV_conf[i].pulse = SRV_Channels::srv_channel(i)->get_output_pwm();
  395. _SRV_conf[i].esc_pending = true;
  396. _SRV_conf[i].servo_pending = true;
  397. }
  398. }
  399. _SRV_armed = hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED;
  400. }
  401. ///// LED /////
  402. void AP_UAVCAN::led_out_send()
  403. {
  404. uint64_t now = AP_HAL::micros64();
  405. if ((now - _led_conf.last_update) < LED_DELAY_US) {
  406. return;
  407. }
  408. uavcan::equipment::indication::LightsCommand msg;
  409. {
  410. WITH_SEMAPHORE(_led_out_sem);
  411. if (_led_conf.devices_count == 0) {
  412. return;
  413. }
  414. uavcan::equipment::indication::SingleLightCommand cmd;
  415. for (uint8_t i = 0; i < _led_conf.devices_count; i++) {
  416. cmd.light_id =_led_conf.devices[i].led_index;
  417. cmd.color.red = _led_conf.devices[i].red >> 3;
  418. cmd.color.green = _led_conf.devices[i].green >> 2;
  419. cmd.color.blue = _led_conf.devices[i].blue >> 3;
  420. msg.commands.push_back(cmd);
  421. }
  422. }
  423. rgb_led[_driver_index]->broadcast(msg);
  424. _led_conf.last_update = now;
  425. }
  426. bool AP_UAVCAN::led_write(uint8_t led_index, uint8_t red, uint8_t green, uint8_t blue)
  427. {
  428. if (_led_conf.devices_count >= AP_UAVCAN_MAX_LED_DEVICES) {
  429. return false;
  430. }
  431. WITH_SEMAPHORE(_led_out_sem);
  432. // check if a device instance exists. if so, break so the instance index is remembered
  433. uint8_t instance = 0;
  434. for (; instance < _led_conf.devices_count; instance++) {
  435. if (_led_conf.devices[instance].led_index == led_index) {
  436. break;
  437. }
  438. }
  439. // load into the correct instance.
  440. // if an existing instance was found in above for loop search,
  441. // then instance value is < _led_conf.devices_count.
  442. // otherwise a new one was just found so we increment the count.
  443. // Either way, the correct instance is the current value of instance
  444. _led_conf.devices[instance].led_index = led_index;
  445. _led_conf.devices[instance].red = red;
  446. _led_conf.devices[instance].green = green;
  447. _led_conf.devices[instance].blue = blue;
  448. if (instance == _led_conf.devices_count) {
  449. _led_conf.devices_count++;
  450. }
  451. return true;
  452. }
  453. // buzzer send
  454. void AP_UAVCAN::buzzer_send()
  455. {
  456. uavcan::equipment::indication::BeepCommand msg;
  457. WITH_SEMAPHORE(_buzzer.sem);
  458. uint8_t mask = (1U << _driver_index);
  459. if ((_buzzer.pending_mask & mask) == 0) {
  460. return;
  461. }
  462. _buzzer.pending_mask &= ~mask;
  463. msg.frequency = _buzzer.frequency;
  464. msg.duration = _buzzer.duration;
  465. buzzer[_driver_index]->broadcast(msg);
  466. }
  467. // buzzer support
  468. void AP_UAVCAN::set_buzzer_tone(float frequency, float duration_s)
  469. {
  470. WITH_SEMAPHORE(_buzzer.sem);
  471. _buzzer.frequency = frequency;
  472. _buzzer.duration = duration_s;
  473. _buzzer.pending_mask = 0xFF;
  474. }
  475. // SafetyState send
  476. void AP_UAVCAN::safety_state_send()
  477. {
  478. ardupilot::indication::SafetyState msg;
  479. uint32_t now = AP_HAL::millis();
  480. if (now - _last_safety_state_ms < 500) {
  481. // update at 2Hz
  482. return;
  483. }
  484. _last_safety_state_ms = now;
  485. switch (hal.util->safety_switch_state()) {
  486. case AP_HAL::Util::SAFETY_ARMED:
  487. msg.status = ardupilot::indication::SafetyState::STATUS_SAFETY_OFF;
  488. break;
  489. case AP_HAL::Util::SAFETY_DISARMED:
  490. msg.status = ardupilot::indication::SafetyState::STATUS_SAFETY_ON;
  491. break;
  492. default:
  493. // nothing to send
  494. return;
  495. }
  496. safety_state[_driver_index]->broadcast(msg);
  497. }
  498. /*
  499. handle Button message
  500. */
  501. void AP_UAVCAN::handle_button(AP_UAVCAN* ap_uavcan, uint8_t node_id, const ButtonCb &cb)
  502. {
  503. switch (cb.msg->button) {
  504. case ardupilot::indication::Button::BUTTON_SAFETY: {
  505. AP_BoardConfig *brdconfig = AP_BoardConfig::get_singleton();
  506. if (brdconfig && brdconfig->safety_button_handle_pressed(cb.msg->press_time)) {
  507. AP_HAL::Util::safety_state state = hal.util->safety_switch_state();
  508. if (state == AP_HAL::Util::SAFETY_ARMED) {
  509. hal.rcout->force_safety_on();
  510. } else {
  511. hal.rcout->force_safety_off();
  512. }
  513. }
  514. break;
  515. }
  516. }
  517. }
  518. AP_UAVCAN *AP_UAVCAN::_singleton;
  519. namespace AP {
  520. AP_UAVCAN &uavcan()
  521. {
  522. return *AP_UAVCAN::get_singleton();
  523. }
  524. };
  525. #endif // HAL_WITH_UAVCAN