2017-04-02 11:55:40 -03:00
/*
2018-07-18 06:26:48 -03:00
* This file is free software : you can redistribute it and / or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation , either version 3 of the License , or
* ( at your option ) any later version .
2017-04-02 11:55:40 -03:00
*
2018-07-18 06:26:48 -03:00
* This file is distributed in the hope that it will be useful , but
* WITHOUT ANY WARRANTY ; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE .
* See the GNU General Public License for more details .
*
* You should have received a copy of the GNU General Public License along
* with this program . If not , see < http : //www.gnu.org/licenses/>.
*
* Author : Eugene Shamaev , Siddharth Bharat Purohit
2017-04-02 11:55:40 -03:00
*/
# include <AP_Common/AP_Common.h>
# include <AP_HAL/AP_HAL.h>
2023-04-08 01:09:10 -03:00
# if HAL_ENABLE_DRONECAN_DRIVERS
2023-04-06 21:18:01 -03:00
# include "AP_DroneCAN.h"
2017-04-02 11:55:40 -03:00
# include <GCS_MAVLink/GCS.h>
2017-05-06 06:13:44 -03:00
# include <AP_BoardConfig/AP_BoardConfig.h>
2020-06-24 09:07:28 -03:00
# include <AP_CANManager/AP_CANManager.h>
2017-05-06 06:13:44 -03:00
2021-01-22 18:27:23 -04:00
# include <AP_Arming/AP_Arming.h>
2023-04-08 00:55:40 -03:00
# include <AP_GPS/AP_GPS_DroneCAN.h>
# include <AP_Compass/AP_Compass_DroneCAN.h>
# include <AP_Baro/AP_Baro_DroneCAN.h>
# include <AP_BattMonitor/AP_BattMonitor_DroneCAN.h>
# include <AP_Airspeed/AP_Airspeed_DroneCAN.h>
2023-01-04 21:09:23 -04:00
# include <AP_OpticalFlow/AP_OpticalFlow_HereFlow.h>
2023-04-08 00:55:40 -03:00
# include <AP_RangeFinder/AP_RangeFinder_DroneCAN.h>
2022-06-03 19:10:12 -03:00
# include <AP_EFI/AP_EFI_DroneCAN.h>
2023-04-08 00:55:40 -03:00
# include <AP_GPS/AP_GPS_DroneCAN.h>
2023-02-28 18:50:23 -04:00
# include <AP_GPS/AP_GPS.h>
2023-04-08 00:55:40 -03:00
# include <AP_BattMonitor/AP_BattMonitor_DroneCAN.h>
# include <AP_Compass/AP_Compass_DroneCAN.h>
# include <AP_Airspeed/AP_Airspeed_DroneCAN.h>
2023-01-04 21:09:23 -04:00
# include <AP_Proximity/AP_Proximity_DroneCAN.h>
2019-04-04 21:43:32 -03:00
# include <SRV_Channel/SRV_Channel.h>
2019-10-02 06:44:16 -03:00
# include <AP_ADSB/AP_ADSB.h>
2023-04-06 21:18:01 -03:00
# include "AP_DroneCAN_DNA_Server.h"
2020-01-03 23:52:59 -04:00
# include <AP_Logger/AP_Logger.h>
2022-02-28 21:19:20 -04:00
# include <AP_Notify/AP_Notify.h>
2022-08-06 04:27:01 -03:00
# include <AP_OpenDroneID/AP_OpenDroneID.h>
2023-01-04 21:09:23 -04:00
# include <string.h>
2018-02-16 18:32:50 -04:00
2018-07-20 10:46:29 -03:00
# define LED_DELAY_US 50000
2017-04-02 11:55:40 -03:00
extern const AP_HAL : : HAL & hal ;
2022-06-02 21:55:47 -03:00
// setup default pool size
2023-04-08 01:13:44 -03:00
# ifndef DRONECAN_NODE_POOL_SIZE
2022-03-01 12:47:00 -04:00
# if HAL_CANFD_SUPPORTED
2023-04-08 01:13:44 -03:00
# define DRONECAN_NODE_POOL_SIZE 16384
2022-03-01 12:47:00 -04:00
# else
2023-04-08 01:13:44 -03:00
# define DRONECAN_NODE_POOL_SIZE 8192
2022-03-01 12:47:00 -04:00
# endif
# endif
# if HAL_CANFD_SUPPORTED
2023-04-08 01:27:51 -03:00
# define DRONECAN_STACK_SIZE 8192
2022-03-01 12:47:00 -04:00
# else
2023-04-08 01:27:51 -03:00
# define DRONECAN_STACK_SIZE 4096
2022-03-01 12:47:00 -04:00
# endif
2023-02-13 09:49:17 -04:00
# ifndef AP_DRONECAN_VOLZ_FEEDBACK_ENABLED
# define AP_DRONECAN_VOLZ_FEEDBACK_ENABLED 0
# endif
2023-04-08 01:27:51 -03:00
# define debug_dronecan(level_debug, fmt, args...) do { AP::can().log_text(level_debug, "DroneCAN", fmt, ##args); } while (0)
2017-04-02 11:55:40 -03:00
2023-04-08 01:27:51 -03:00
// Translation of all messages from DroneCAN structures into AP structures is done
2023-04-06 21:18:01 -03:00
// in AP_DroneCAN and not in corresponding drivers.
2017-04-02 11:55:40 -03:00
// The overhead of including definitions of DSDL is very high and it is best to
// concentrate in one place.
// table of user settable CAN bus parameters
2023-04-06 21:18:01 -03:00
const AP_Param : : GroupInfo AP_DroneCAN : : var_info [ ] = {
2017-04-02 11:55:40 -03:00
// @Param: NODE
2023-04-08 01:27:51 -03:00
// @DisplayName: DroneCAN node that is used for this network
// @Description: DroneCAN node should be set implicitly
2017-04-02 11:55:40 -03:00
// @Range: 1 250
// @User: Advanced
2023-04-06 21:18:01 -03:00
AP_GROUPINFO ( " NODE " , 1 , AP_DroneCAN , _dronecan_node , 10 ) ,
2017-04-02 11:55:40 -03:00
2017-05-06 06:13:44 -03:00
// @Param: SRV_BM
2023-04-08 01:27:51 -03:00
// @DisplayName: Output channels to be transmitted as servo over DroneCAN
// @Description: Bitmask with one set for channel to be transmitted as a servo command over DroneCAN
2021-01-11 21:45:02 -04:00
// @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, 15: Servo 16, 16: Servo 17, 17: Servo 18, 18: Servo 19, 19: Servo 20, 20: Servo 21, 21: Servo 22, 22: Servo 23, 23: Servo 24, 24: Servo 25, 25: Servo 26, 26: Servo 27, 27: Servo 28, 28: Servo 29, 29: Servo 30, 30: Servo 31, 31: Servo 32
2017-05-06 06:13:44 -03:00
// @User: Advanced
2023-04-06 21:18:01 -03:00
AP_GROUPINFO ( " SRV_BM " , 2 , AP_DroneCAN , _servo_bm , 0 ) ,
2017-05-06 06:13:44 -03:00
// @Param: ESC_BM
2023-04-08 01:27:51 -03:00
// @DisplayName: Output channels to be transmitted as ESC over DroneCAN
// @Description: Bitmask with one set for channel to be transmitted as a ESC command over DroneCAN
2021-01-11 21:45:02 -04:00
// @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, 16: ESC 17, 17: ESC 18, 18: ESC 19, 19: ESC 20, 20: ESC 21, 21: ESC 22, 22: ESC 23, 23: ESC 24, 24: ESC 25, 25: ESC 26, 26: ESC 27, 27: ESC 28, 28: ESC 29, 29: ESC 30, 30: ESC 31, 31: ESC 32
2017-05-06 06:13:44 -03:00
// @User: Advanced
2023-04-06 21:18:01 -03:00
AP_GROUPINFO ( " ESC_BM " , 3 , AP_DroneCAN , _esc_bm , 0 ) ,
2017-05-06 06:13:44 -03:00
2018-05-24 07:23:00 -03:00
// @Param: SRV_RT
// @DisplayName: Servo output rate
// @Description: Maximum transmit rate for servo outputs
// @Range: 1 200
// @Units: Hz
// @User: Advanced
2023-04-06 21:18:01 -03:00
AP_GROUPINFO ( " SRV_RT " , 4 , AP_DroneCAN , _servo_rate_hz , 50 ) ,
2018-07-18 00:08:08 -03:00
2021-09-10 23:47:02 -03:00
// @Param: OPTION
2023-04-08 01:27:51 -03:00
// @DisplayName: DroneCAN options
2021-09-10 23:47:02 -03:00
// @Description: Option flags
2023-02-28 18:50:23 -04:00
// @Bitmask: 0:ClearDNADatabase,1:IgnoreDNANodeConflicts,2:EnableCanfd,3:IgnoreDNANodeUnhealthy,4:SendServoAsPWM,5:SendGNSS
2021-09-10 23:47:02 -03:00
// @User: Advanced
2023-04-06 21:18:01 -03:00
AP_GROUPINFO ( " OPTION " , 5 , AP_DroneCAN , _options , 0 ) ,
2021-09-10 23:47:02 -03:00
2021-09-15 03:48:19 -03:00
// @Param: NTF_RT
// @DisplayName: Notify State rate
// @Description: Maximum transmit rate for Notify State Message
// @Range: 1 200
// @Units: Hz
// @User: Advanced
2023-04-06 21:18:01 -03:00
AP_GROUPINFO ( " NTF_RT " , 6 , AP_DroneCAN , _notify_state_hz , 20 ) ,
2021-09-15 03:48:19 -03:00
AP_UAVCAN: added CAN_Dx_UC_ESC_OF parameter
this allows for an offset in ESC numbering for much more efficient CAN
bandwidth usage.
For example, on a coaxial OctoQuad quadplane the ESCs are typically
setup as outputs 5 to 12. An ideal setup is to split these over 2 CAN
buses, with one CAN bus for the top layer and the one bus for the
bottom layer (allowing for VTOL flight with one bus failed).
Without this offset parameter you would be sending RawCommand messages
like this:
bus1: [ 0, 0, 0, 0, ESC1, ESC2, ESC3, ESC4 ]
bus2: [ 0, 0, 0, 0, 0, 0, 0, 0, ESC1, ESC2, ESC3, ESC4 ]
this is very wasteful of bus bandwidth, with bus1 using 3x the
bandwidth it should and bus2 using 4x the bandwidth it should (the
above will take 3 can frames for bus1, and 4 can frames for bus 2)
With this patch you can set:
CAN_D1_UC_ESC_OF = 4
CAN_D2_UC_ESC_OF = 8
and you will get this on the bus:
bus1: [ ESC1, ESC2, ESC3, ESC4 ]
bus2: [ ESC1, ESC2, ESC3, ESC4 ]
that takes just 1 can frame per send on each bus
2022-05-18 03:35:28 -03:00
// @Param: ESC_OF
// @DisplayName: ESC Output channels offset
// @Description: Offset for ESC numbering in DroneCAN ESC RawCommand messages. This allows for more efficient packing of ESC command messages. If your ESCs are on servo functions 5 to 8 and you set this parameter to 4 then the ESC RawCommand will be sent with the first 4 slots filled. This can be used for more efficint usage of CAN bandwidth
// @Range: 0 18
// @User: Advanced
2023-04-06 21:18:01 -03:00
AP_GROUPINFO ( " ESC_OF " , 7 , AP_DroneCAN , _esc_offset , 0 ) ,
2022-06-02 21:55:47 -03:00
// @Param: POOL
// @DisplayName: CAN pool size
// @Description: Amount of memory in bytes to allocate for the DroneCAN memory pool. More memory is needed for higher CAN bus loads
// @Range: 1024 16384
// @User: Advanced
2023-04-08 01:13:44 -03:00
AP_GROUPINFO ( " POOL " , 8 , AP_DroneCAN , _pool_size , DRONECAN_NODE_POOL_SIZE ) ,
AP_UAVCAN: added CAN_Dx_UC_ESC_OF parameter
this allows for an offset in ESC numbering for much more efficient CAN
bandwidth usage.
For example, on a coaxial OctoQuad quadplane the ESCs are typically
setup as outputs 5 to 12. An ideal setup is to split these over 2 CAN
buses, with one CAN bus for the top layer and the one bus for the
bottom layer (allowing for VTOL flight with one bus failed).
Without this offset parameter you would be sending RawCommand messages
like this:
bus1: [ 0, 0, 0, 0, ESC1, ESC2, ESC3, ESC4 ]
bus2: [ 0, 0, 0, 0, 0, 0, 0, 0, ESC1, ESC2, ESC3, ESC4 ]
this is very wasteful of bus bandwidth, with bus1 using 3x the
bandwidth it should and bus2 using 4x the bandwidth it should (the
above will take 3 can frames for bus1, and 4 can frames for bus 2)
With this patch you can set:
CAN_D1_UC_ESC_OF = 4
CAN_D2_UC_ESC_OF = 8
and you will get this on the bus:
bus1: [ ESC1, ESC2, ESC3, ESC4 ]
bus2: [ ESC1, ESC2, ESC3, ESC4 ]
that takes just 1 can frame per send on each bus
2022-05-18 03:35:28 -03:00
2017-04-02 11:55:40 -03:00
AP_GROUPEND
} ;
2018-05-22 00:37:46 -03:00
// this is the timeout in milliseconds for periodic message types. We
// set this to 1 to minimise resend of stale msgs
2018-05-24 07:23:37 -03:00
# define CAN_PERIODIC_TX_TIMEOUT_MS 2
2018-05-22 00:37:46 -03:00
2023-04-06 21:18:01 -03:00
AP_DroneCAN : : AP_DroneCAN ( const int driver_index ) :
2023-01-04 21:09:23 -04:00
_driver_index ( driver_index ) ,
canard_iface ( driver_index ) ,
_dna_server ( * this )
2017-04-02 11:55:40 -03:00
{
AP_Param : : setup_object_defaults ( this , var_info ) ;
2023-04-08 01:27:51 -03:00
for ( uint8_t i = 0 ; i < DRONECAN_SRV_NUMBER ; i + + ) {
2018-05-24 07:23:00 -03:00
_SRV_conf [ i ] . esc_pending = false ;
_SRV_conf [ i ] . servo_pending = false ;
2017-04-02 11:55:40 -03:00
}
2023-04-08 01:27:51 -03:00
debug_dronecan ( AP_CANManager : : LOG_INFO , " AP_DroneCAN constructed \n \r " ) ;
2017-04-02 11:55:40 -03:00
}
2023-04-06 21:18:01 -03:00
AP_DroneCAN : : ~ AP_DroneCAN ( )
2017-04-02 11:55:40 -03:00
{
}
2023-04-08 01:27:51 -03:00
AP_DroneCAN * AP_DroneCAN : : get_dronecan ( uint8_t driver_index )
2018-07-20 10:46:29 -03:00
{
if ( driver_index > = AP : : can ( ) . get_num_drivers ( ) | |
2023-04-18 04:24:17 -03:00
AP : : can ( ) . get_driver_type ( driver_index ) ! = AP_CAN : : Protocol : : DroneCAN ) {
2018-07-20 10:46:29 -03:00
return nullptr ;
}
2023-04-06 21:18:01 -03:00
return static_cast < AP_DroneCAN * > ( AP : : can ( ) . get_driver ( driver_index ) ) ;
2018-07-20 10:46:29 -03:00
}
2023-04-06 21:18:01 -03:00
bool AP_DroneCAN : : add_interface ( AP_HAL : : CANIface * can_iface )
2023-01-04 21:09:23 -04:00
{
if ( ! canard_iface . add_interface ( can_iface ) ) {
2023-04-08 01:27:51 -03:00
debug_dronecan ( AP_CANManager : : LOG_ERROR , " DroneCAN: can't add DroneCAN interface \n \r " ) ;
2020-06-24 09:07:28 -03:00
return false ;
2018-03-09 04:31:17 -04:00
}
2020-06-24 09:07:28 -03:00
return true ;
}
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : init ( uint8_t driver_index , bool enable_filters )
2020-06-24 09:07:28 -03:00
{
2023-01-04 21:09:23 -04:00
if ( driver_index ! = _driver_index ) {
2023-04-08 01:27:51 -03:00
debug_dronecan ( AP_CANManager : : LOG_ERROR , " DroneCAN: init called with wrong driver_index " ) ;
2022-06-02 21:55:47 -03:00
return ;
}
2023-01-04 21:09:23 -04:00
if ( _initialized ) {
2023-04-08 01:27:51 -03:00
debug_dronecan ( AP_CANManager : : LOG_ERROR , " DroneCAN: init called more than once \n \r " ) ;
2018-02-27 20:02:09 -04:00
return ;
2018-03-09 04:31:17 -04:00
}
2020-09-26 17:12:40 -03:00
2023-04-14 20:36:19 -03:00
node_info_rsp . name . len = hal . util - > snprintf ( ( char * ) node_info_rsp . name . data , sizeof ( node_info_rsp . name . data ) , " org.ardupilot:%u " , driver_index ) ;
2020-09-26 17:12:40 -03:00
2023-04-06 21:18:01 -03:00
node_info_rsp . software_version . major = AP_DRONECAN_SW_VERS_MAJOR ;
node_info_rsp . software_version . minor = AP_DRONECAN_SW_VERS_MINOR ;
node_info_rsp . hardware_version . major = AP_DRONECAN_HW_VERS_MAJOR ;
node_info_rsp . hardware_version . minor = AP_DRONECAN_HW_VERS_MINOR ;
2020-09-26 17:12:40 -03:00
2023-01-04 21:09:23 -04:00
# if HAL_CANFD_SUPPORTED
2021-05-03 09:58:40 -03:00
if ( option_is_set ( Options : : CANFD_ENABLED ) ) {
2023-01-04 21:09:23 -04:00
canard_iface . set_canfd ( true ) ;
2021-05-03 09:58:40 -03:00
}
# endif
2023-01-04 21:09:23 -04:00
uint8_t uid_len = sizeof ( uavcan_protocol_HardwareVersion : : unique_id ) ;
uint8_t unique_id [ sizeof ( uavcan_protocol_HardwareVersion : : unique_id ) ] ;
mem_pool = new uint32_t [ _pool_size / sizeof ( uint32_t ) ] ;
if ( mem_pool = = nullptr ) {
2023-04-08 01:27:51 -03:00
debug_dronecan ( AP_CANManager : : LOG_ERROR , " DroneCAN: Failed to allocate memory pool \n \r " ) ;
2018-11-26 23:27:20 -04:00
return ;
}
2023-01-04 21:09:23 -04:00
canard_iface . init ( mem_pool , ( _pool_size / sizeof ( uint32_t ) ) * sizeof ( uint32_t ) , _dronecan_node ) ;
2018-10-12 05:15:19 -03:00
2023-01-04 21:09:23 -04:00
if ( ! hal . util - > get_system_id_unformatted ( unique_id , uid_len ) ) {
2022-04-04 07:33:33 -03:00
return ;
}
2023-01-04 21:09:23 -04:00
unique_id [ uid_len - 1 ] + = _dronecan_node ;
memcpy ( node_info_rsp . hardware_version . unique_id , unique_id , uid_len ) ;
2022-04-04 07:33:33 -03:00
2018-11-26 23:27:20 -04:00
//Start Servers
2023-01-04 21:09:23 -04:00
if ( ! _dna_server . init ( unique_id , uid_len , _dronecan_node ) ) {
2023-04-08 01:27:51 -03:00
debug_dronecan ( AP_CANManager : : LOG_ERROR , " DroneCAN: Failed to start DNA Server \n \r " ) ;
2019-09-21 00:16:06 -03:00
return ;
}
2018-07-18 06:26:48 -03:00
// Roundup all subscribers from supported drivers
2023-04-08 01:09:10 -03:00
AP_GPS_DroneCAN : : subscribe_msgs ( this ) ;
2023-04-08 00:58:13 -03:00
# if AP_COMPASS_DRONECAN_ENABLED
2023-04-08 01:09:10 -03:00
AP_Compass_DroneCAN : : subscribe_msgs ( this ) ;
2023-02-19 21:05:19 -04:00
# endif
2023-04-08 00:58:13 -03:00
# if AP_BARO_DRONECAN_ENABLED
2023-04-08 01:09:10 -03:00
AP_Baro_DroneCAN : : subscribe_msgs ( this ) ;
2022-01-26 23:58:57 -04:00
# endif
2023-04-08 01:09:10 -03:00
AP_BattMonitor_DroneCAN : : subscribe_msgs ( this ) ;
2023-04-08 00:58:13 -03:00
# if AP_AIRSPEED_DRONECAN_ENABLED
2023-04-08 01:09:10 -03:00
AP_Airspeed_DroneCAN : : subscribe_msgs ( this ) ;
2022-05-04 05:13:30 -03:00
# endif
2021-12-24 01:47:21 -04:00
# if AP_OPTICALFLOW_HEREFLOW_ENABLED
2018-11-01 08:15:33 -03:00
AP_OpticalFlow_HereFlow : : subscribe_msgs ( this ) ;
2021-12-24 01:47:21 -04:00
# endif
2023-04-08 00:58:13 -03:00
# if AP_RANGEFINDER_DRONECAN_ENABLED
2023-04-08 01:09:10 -03:00
AP_RangeFinder_DroneCAN : : subscribe_msgs ( this ) ;
2022-03-12 07:46:47 -04:00
# endif
2023-03-15 20:11:53 -03:00
# if AP_EFI_DRONECAN_ENABLED
2022-06-03 19:10:12 -03:00
AP_EFI_DroneCAN : : subscribe_msgs ( this ) ;
# endif
2017-04-02 11:55:40 -03:00
2022-12-14 04:06:07 -04:00
# if AP_PROXIMITY_DRONECAN_ENABLED
AP_Proximity_DroneCAN : : subscribe_msgs ( this ) ;
# endif
2023-01-04 21:09:23 -04:00
act_out_array . set_timeout_ms ( 2 ) ;
act_out_array . set_priority ( CANARD_TRANSFER_PRIORITY_HIGH ) ;
2018-01-17 03:18:00 -04:00
2023-01-04 21:09:23 -04:00
esc_raw . set_timeout_ms ( 2 ) ;
esc_raw . set_priority ( CANARD_TRANSFER_PRIORITY_HIGH ) ;
2017-11-15 10:36:14 -04:00
2023-01-04 21:09:23 -04:00
rgb_led . set_timeout_ms ( 20 ) ;
rgb_led . set_priority ( CANARD_TRANSFER_PRIORITY_LOW ) ;
2017-04-02 11:55:40 -03:00
2023-01-04 21:09:23 -04:00
buzzer . set_timeout_ms ( 20 ) ;
buzzer . set_priority ( CANARD_TRANSFER_PRIORITY_LOW ) ;
2019-08-31 01:30:49 -03:00
2023-01-04 21:09:23 -04:00
safety_state . set_timeout_ms ( 20 ) ;
safety_state . set_priority ( CANARD_TRANSFER_PRIORITY_LOW ) ;
2019-09-02 23:25:39 -03:00
2023-01-04 21:09:23 -04:00
arming_status . set_timeout_ms ( 20 ) ;
arming_status . set_priority ( CANARD_TRANSFER_PRIORITY_LOW ) ;
2021-01-22 18:27:23 -04:00
2023-02-28 18:50:23 -04:00
# if AP_DRONECAN_SEND_GPS
2023-01-04 21:09:23 -04:00
gnss_fix2 . set_timeout_ms ( 20 ) ;
gnss_fix2 . set_priority ( CANARD_TRANSFER_PRIORITY_LOW ) ;
2023-02-28 18:50:23 -04:00
2023-01-04 21:09:23 -04:00
gnss_auxiliary . set_timeout_ms ( 20 ) ;
gnss_auxiliary . set_priority ( CANARD_TRANSFER_PRIORITY_LOW ) ;
2023-02-28 18:50:23 -04:00
2023-01-04 21:09:23 -04:00
gnss_heading . set_timeout_ms ( 20 ) ;
gnss_heading . set_priority ( CANARD_TRANSFER_PRIORITY_LOW ) ;
2023-02-28 18:50:23 -04:00
2023-01-04 21:09:23 -04:00
gnss_status . set_timeout_ms ( 20 ) ;
gnss_status . set_priority ( CANARD_TRANSFER_PRIORITY_LOW ) ;
2023-02-28 18:50:23 -04:00
# endif
2023-01-04 21:09:23 -04:00
rtcm_stream . set_timeout_ms ( 20 ) ;
rtcm_stream . set_priority ( CANARD_TRANSFER_PRIORITY_LOW ) ;
2021-09-15 03:48:19 -03:00
2023-01-04 21:09:23 -04:00
notify_state . set_timeout_ms ( 20 ) ;
notify_state . set_priority ( CANARD_TRANSFER_PRIORITY_LOW ) ;
2021-09-15 03:48:19 -03:00
2023-01-04 21:09:23 -04:00
param_save_client . set_timeout_ms ( 20 ) ;
param_save_client . set_priority ( CANARD_TRANSFER_PRIORITY_LOW ) ;
2021-07-16 13:27:11 -03:00
2023-01-04 21:09:23 -04:00
param_get_set_client . set_timeout_ms ( 20 ) ;
param_get_set_client . set_priority ( CANARD_TRANSFER_PRIORITY_LOW ) ;
2021-07-16 13:27:11 -03:00
2023-01-04 21:09:23 -04:00
node_status . set_priority ( CANARD_TRANSFER_PRIORITY_LOWEST ) ;
node_status . set_timeout_ms ( 1000 ) ;
2023-02-13 09:49:17 -04:00
2023-01-04 21:09:23 -04:00
node_info_server . set_timeout_ms ( 20 ) ;
2020-11-29 19:47:32 -04:00
2018-03-09 04:31:17 -04:00
_led_conf . devices_count = 0 ;
2018-07-22 02:07:51 -03:00
2023-01-04 21:09:23 -04:00
// setup node status
node_status_msg . health = UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK ;
node_status_msg . mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL ;
node_status_msg . sub_mode = 0 ;
2017-04-02 11:55:40 -03:00
2018-02-27 20:02:09 -04:00
// Spin node for device discovery
2023-04-17 08:33:56 -03:00
for ( uint8_t i = 0 ; i < 5 ; i + + ) {
send_node_status ( ) ;
canard_iface . process ( 1000 ) ;
2023-01-04 21:09:23 -04:00
}
2017-04-02 11:55:40 -03:00
2023-04-14 20:36:19 -03:00
hal . util - > snprintf ( _thread_name , sizeof ( _thread_name ) , " dronecan_%u " , driver_index ) ;
2017-04-02 11:55:40 -03:00
2023-04-08 01:27:51 -03:00
if ( ! hal . scheduler - > thread_create ( FUNCTOR_BIND_MEMBER ( & AP_DroneCAN : : loop , void ) , _thread_name , DRONECAN_STACK_SIZE , AP_HAL : : Scheduler : : PRIORITY_CAN , 0 ) ) {
debug_dronecan ( AP_CANManager : : LOG_ERROR , " DroneCAN: couldn't create thread \n \r " ) ;
2018-02-27 20:02:09 -04:00
return ;
}
_initialized = true ;
2023-04-08 01:27:51 -03:00
debug_dronecan ( AP_CANManager : : LOG_INFO , " DroneCAN: init done \n \r " ) ;
2017-04-02 11:55:40 -03:00
}
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : loop ( void )
2017-04-02 11:55:40 -03:00
{
2018-07-20 10:46:29 -03:00
while ( true ) {
if ( ! _initialized ) {
hal . scheduler - > delay_microseconds ( 1000 ) ;
continue ;
}
2017-04-02 11:55:40 -03:00
2023-01-04 21:09:23 -04:00
canard_iface . process ( 1 ) ;
2018-07-20 10:46:29 -03:00
if ( _SRV_armed ) {
bool sent_servos = false ;
if ( _servo_bm > 0 ) {
// if we have any Servos in bitmask
2020-06-24 09:07:28 -03:00
uint32_t now = AP_HAL : : native_micros ( ) ;
2018-07-20 10:46:29 -03:00
const uint32_t servo_period_us = 1000000UL / unsigned ( _servo_rate_hz . get ( ) ) ;
if ( now - _SRV_last_send_us > = servo_period_us ) {
_SRV_last_send_us = now ;
SRV_send_actuator ( ) ;
sent_servos = true ;
2023-04-08 01:27:51 -03:00
for ( uint8_t i = 0 ; i < DRONECAN_SRV_NUMBER ; i + + ) {
2018-07-20 10:46:29 -03:00
_SRV_conf [ i ] . servo_pending = false ;
}
}
}
// if we have any ESC's in bitmask
if ( _esc_bm > 0 & & ! sent_servos ) {
SRV_send_esc ( ) ;
}
2023-04-08 01:27:51 -03:00
for ( uint8_t i = 0 ; i < DRONECAN_SRV_NUMBER ; i + + ) {
2018-07-20 10:46:29 -03:00
_SRV_conf [ i ] . esc_pending = false ;
}
}
led_out_send ( ) ;
2019-08-30 23:45:02 -03:00
buzzer_send ( ) ;
2019-10-21 08:10:33 -03:00
rtcm_stream_send ( ) ;
2019-08-31 01:30:49 -03:00
safety_state_send ( ) ;
2021-09-15 03:48:19 -03:00
notify_state_send ( ) ;
2021-07-16 13:27:11 -03:00
send_parameter_request ( ) ;
send_parameter_save_request ( ) ;
2023-01-04 21:09:23 -04:00
send_node_status ( ) ;
_dna_server . verify_nodes ( ) ;
2022-08-06 04:27:01 -03:00
# if AP_OPENDRONEID_ENABLED
AP : : opendroneid ( ) . dronecan_send ( this ) ;
# endif
2023-02-28 18:50:23 -04:00
# if AP_DRONECAN_SEND_GPS
2023-04-08 01:09:10 -03:00
if ( option_is_set ( AP_DroneCAN : : Options : : SEND_GNSS ) & & ! AP_GPS_DroneCAN : : instance_exists ( this ) ) {
2023-02-28 18:50:23 -04:00
// send if enabled and this interface/driver is not used by the AP_GPS driver
gnss_send_fix ( ) ;
gnss_send_yaw ( ) ;
}
# endif
2022-12-06 22:36:20 -04:00
logging ( ) ;
2018-07-20 10:46:29 -03:00
}
2017-04-02 11:55:40 -03:00
}
2018-07-20 10:46:29 -03:00
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : send_node_status ( void )
2023-01-04 21:09:23 -04:00
{
const uint32_t now = AP_HAL : : native_millis ( ) ;
if ( now - _node_status_last_send_ms < 1000 ) {
return ;
}
_node_status_last_send_ms = now ;
node_status_msg . uptime_sec = now / 1000 ;
node_status . broadcast ( node_status_msg ) ;
}
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : handle_node_info_request ( const CanardRxTransfer & transfer , const uavcan_protocol_GetNodeInfoRequest & req )
2023-01-04 21:09:23 -04:00
{
node_info_rsp . status = node_status_msg ;
node_info_rsp . status . uptime_sec = AP_HAL : : native_millis ( ) / 1000 ;
node_info_server . respond ( transfer , node_info_rsp ) ;
}
2018-07-20 10:46:29 -03:00
///// SRV output /////
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : SRV_send_actuator ( void )
2017-04-02 11:55:40 -03:00
{
2018-02-08 19:42:58 -04:00
uint8_t starting_servo = 0 ;
bool repeat_send ;
2017-05-06 06:13:44 -03:00
2018-10-11 20:35:04 -03:00
WITH_SEMAPHORE ( SRV_sem ) ;
2018-07-20 10:46:29 -03:00
2018-02-08 19:42:58 -04:00
do {
repeat_send = false ;
2023-01-04 21:09:23 -04:00
uavcan_equipment_actuator_ArrayCommand msg ;
2017-05-06 06:13:44 -03:00
2018-02-08 19:42:58 -04:00
uint8_t i ;
2023-04-08 01:27:51 -03:00
// DroneCAN can hold maximum of 15 commands in one frame
for ( i = 0 ; starting_servo < DRONECAN_SRV_NUMBER & & i < 15 ; starting_servo + + ) {
2023-01-04 21:09:23 -04:00
uavcan_equipment_actuator_Command cmd ;
2017-04-02 11:55:40 -03:00
2018-02-08 19:42:58 -04:00
/*
* Servo output uses a range of 1000 - 2000 PWM for scaling .
* This converts output PWM from [ 1000 : 2000 ] range to [ - 1 : 1 ] range that
2023-04-08 01:27:51 -03:00
* is passed to servo as unitless type via DroneCAN .
2018-02-08 19:42:58 -04:00
* This approach allows for MIN / TRIM / MAX values to be used fully on
* autopilot side and for servo it should have the setup to provide maximum
* physically possible throws at [ - 1 : 1 ] limits .
*/
2017-04-02 11:55:40 -03:00
2018-05-24 07:23:00 -03:00
if ( _SRV_conf [ starting_servo ] . servo_pending & & ( ( ( ( uint32_t ) 1 ) < < starting_servo ) & _servo_bm ) ) {
2018-02-08 19:42:58 -04:00
cmd . actuator_id = starting_servo + 1 ;
2017-04-02 11:55:40 -03:00
2022-09-12 00:31:04 -03:00
if ( option_is_set ( Options : : USE_ACTUATOR_PWM ) ) {
2023-01-04 21:09:23 -04:00
cmd . command_type = UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_COMMAND_TYPE_PWM ;
2022-09-12 00:31:04 -03:00
cmd . command_value = _SRV_conf [ starting_servo ] . pulse ;
} else {
2023-01-04 21:09:23 -04:00
cmd . command_type = UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_COMMAND_TYPE_UNITLESS ;
2022-09-12 00:31:04 -03:00
cmd . command_value = constrain_float ( ( ( float ) _SRV_conf [ starting_servo ] . pulse - 1000.0 ) / 500.0 - 1.0 , - 1.0 , 1.0 ) ;
}
2017-04-02 11:55:40 -03:00
2023-01-04 21:09:23 -04:00
msg . commands . data [ i ] = cmd ;
2017-04-02 11:55:40 -03:00
2018-02-08 19:42:58 -04:00
i + + ;
}
}
2023-01-04 21:09:23 -04:00
msg . commands . len = i ;
2018-02-08 19:42:58 -04:00
if ( i > 0 ) {
2023-01-04 21:09:23 -04:00
if ( act_out_array . broadcast ( msg ) > 0 ) {
2022-12-06 22:36:20 -04:00
_srv_send_count + + ;
} else {
_fail_send_count + + ;
}
2017-04-17 04:28:38 -03:00
2018-02-08 19:42:58 -04:00
if ( i = = 15 ) {
repeat_send = true ;
}
}
} while ( repeat_send ) ;
}
2017-04-02 11:55:40 -03:00
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : SRV_send_esc ( void )
2018-02-08 19:42:58 -04:00
{
2023-01-04 21:09:23 -04:00
static const int cmd_max = ( ( 1 < < 13 ) - 1 ) ;
uavcan_equipment_esc_RawCommand esc_msg ;
2017-04-17 04:28:38 -03:00
2018-02-08 19:42:58 -04:00
uint8_t active_esc_num = 0 , max_esc_num = 0 ;
uint8_t k = 0 ;
2017-04-17 04:28:38 -03:00
2018-10-11 20:35:04 -03:00
WITH_SEMAPHORE ( SRV_sem ) ;
2018-07-20 10:46:29 -03:00
AP_UAVCAN: added CAN_Dx_UC_ESC_OF parameter
this allows for an offset in ESC numbering for much more efficient CAN
bandwidth usage.
For example, on a coaxial OctoQuad quadplane the ESCs are typically
setup as outputs 5 to 12. An ideal setup is to split these over 2 CAN
buses, with one CAN bus for the top layer and the one bus for the
bottom layer (allowing for VTOL flight with one bus failed).
Without this offset parameter you would be sending RawCommand messages
like this:
bus1: [ 0, 0, 0, 0, ESC1, ESC2, ESC3, ESC4 ]
bus2: [ 0, 0, 0, 0, 0, 0, 0, 0, ESC1, ESC2, ESC3, ESC4 ]
this is very wasteful of bus bandwidth, with bus1 using 3x the
bandwidth it should and bus2 using 4x the bandwidth it should (the
above will take 3 can frames for bus1, and 4 can frames for bus 2)
With this patch you can set:
CAN_D1_UC_ESC_OF = 4
CAN_D2_UC_ESC_OF = 8
and you will get this on the bus:
bus1: [ ESC1, ESC2, ESC3, ESC4 ]
bus2: [ ESC1, ESC2, ESC3, ESC4 ]
that takes just 1 can frame per send on each bus
2022-05-18 03:35:28 -03:00
// esc offset allows for efficient packing of higher ESC numbers in RawCommand
2023-04-08 01:27:51 -03:00
const uint8_t esc_offset = constrain_int16 ( _esc_offset . get ( ) , 0 , DRONECAN_SRV_NUMBER ) ;
AP_UAVCAN: added CAN_Dx_UC_ESC_OF parameter
this allows for an offset in ESC numbering for much more efficient CAN
bandwidth usage.
For example, on a coaxial OctoQuad quadplane the ESCs are typically
setup as outputs 5 to 12. An ideal setup is to split these over 2 CAN
buses, with one CAN bus for the top layer and the one bus for the
bottom layer (allowing for VTOL flight with one bus failed).
Without this offset parameter you would be sending RawCommand messages
like this:
bus1: [ 0, 0, 0, 0, ESC1, ESC2, ESC3, ESC4 ]
bus2: [ 0, 0, 0, 0, 0, 0, 0, 0, ESC1, ESC2, ESC3, ESC4 ]
this is very wasteful of bus bandwidth, with bus1 using 3x the
bandwidth it should and bus2 using 4x the bandwidth it should (the
above will take 3 can frames for bus1, and 4 can frames for bus 2)
With this patch you can set:
CAN_D1_UC_ESC_OF = 4
CAN_D2_UC_ESC_OF = 8
and you will get this on the bus:
bus1: [ ESC1, ESC2, ESC3, ESC4 ]
bus2: [ ESC1, ESC2, ESC3, ESC4 ]
that takes just 1 can frame per send on each bus
2022-05-18 03:35:28 -03:00
2018-02-08 19:42:58 -04:00
// find out how many esc we have enabled and if they are active at all
2023-04-08 01:27:51 -03:00
for ( uint8_t i = esc_offset ; i < DRONECAN_SRV_NUMBER ; i + + ) {
2018-02-08 19:42:58 -04:00
if ( ( ( ( uint32_t ) 1 ) < < i ) & _esc_bm ) {
max_esc_num = i + 1 ;
2018-05-24 07:23:00 -03:00
if ( _SRV_conf [ i ] . esc_pending ) {
2018-02-08 19:42:58 -04:00
active_esc_num + + ;
}
}
}
2017-04-02 11:55:40 -03:00
2018-02-08 19:42:58 -04:00
// if at least one is active (update) we need to send to all
if ( active_esc_num > 0 ) {
k = 0 ;
2017-04-02 11:55:40 -03:00
AP_UAVCAN: added CAN_Dx_UC_ESC_OF parameter
this allows for an offset in ESC numbering for much more efficient CAN
bandwidth usage.
For example, on a coaxial OctoQuad quadplane the ESCs are typically
setup as outputs 5 to 12. An ideal setup is to split these over 2 CAN
buses, with one CAN bus for the top layer and the one bus for the
bottom layer (allowing for VTOL flight with one bus failed).
Without this offset parameter you would be sending RawCommand messages
like this:
bus1: [ 0, 0, 0, 0, ESC1, ESC2, ESC3, ESC4 ]
bus2: [ 0, 0, 0, 0, 0, 0, 0, 0, ESC1, ESC2, ESC3, ESC4 ]
this is very wasteful of bus bandwidth, with bus1 using 3x the
bandwidth it should and bus2 using 4x the bandwidth it should (the
above will take 3 can frames for bus1, and 4 can frames for bus 2)
With this patch you can set:
CAN_D1_UC_ESC_OF = 4
CAN_D2_UC_ESC_OF = 8
and you will get this on the bus:
bus1: [ ESC1, ESC2, ESC3, ESC4 ]
bus2: [ ESC1, ESC2, ESC3, ESC4 ]
that takes just 1 can frame per send on each bus
2022-05-18 03:35:28 -03:00
for ( uint8_t i = esc_offset ; i < max_esc_num & & k < 20 ; i + + ) {
2018-02-08 19:42:58 -04:00
if ( ( ( ( uint32_t ) 1 ) < < i ) & _esc_bm ) {
// TODO: ESC negative scaling for reverse thrust and reverse rotation
2018-03-09 11:36:21 -04:00
float scaled = cmd_max * ( hal . rcout - > scale_esc_to_unity ( _SRV_conf [ i ] . pulse ) + 1.0 ) / 2.0 ;
2017-04-02 11:55:40 -03:00
2018-02-08 19:42:58 -04:00
scaled = constrain_float ( scaled , 0 , cmd_max ) ;
2017-04-02 11:55:40 -03:00
2023-01-04 21:09:23 -04:00
esc_msg . cmd . data [ k ] = static_cast < int > ( scaled ) ;
2018-02-08 19:42:58 -04:00
} else {
2023-01-04 21:09:23 -04:00
esc_msg . cmd . data [ k ] = static_cast < unsigned > ( 0 ) ;
2018-02-08 19:42:58 -04:00
}
2017-04-02 11:55:40 -03:00
2018-02-08 19:42:58 -04:00
k + + ;
}
2023-01-04 21:09:23 -04:00
esc_msg . cmd . len = k ;
2017-04-02 11:55:40 -03:00
2023-01-04 21:09:23 -04:00
if ( esc_raw . broadcast ( esc_msg ) ) {
2022-12-06 22:36:20 -04:00
_esc_send_count + + ;
} else {
_fail_send_count + + ;
}
2018-02-08 19:42:58 -04:00
}
}
2017-04-02 11:55:40 -03:00
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : SRV_push_servos ( )
2018-02-08 19:42:58 -04:00
{
2018-10-11 20:35:04 -03:00
WITH_SEMAPHORE ( SRV_sem ) ;
2018-02-08 19:42:58 -04:00
2023-04-08 01:27:51 -03:00
for ( uint8_t i = 0 ; i < DRONECAN_SRV_NUMBER ; i + + ) {
2018-07-20 10:46:29 -03:00
// Check if this channels has any function assigned
2022-05-20 08:33:43 -03:00
if ( SRV_Channels : : channel_function ( i ) > = SRV_Channel : : k_none ) {
2018-07-20 10:46:29 -03:00
_SRV_conf [ i ] . pulse = SRV_Channels : : srv_channel ( i ) - > get_output_pwm ( ) ;
_SRV_conf [ i ] . esc_pending = true ;
_SRV_conf [ i ] . servo_pending = true ;
2018-02-27 20:02:09 -04:00
}
2018-07-20 10:46:29 -03:00
}
2018-02-08 19:42:58 -04:00
2018-08-08 07:58:10 -03:00
_SRV_armed = hal . util - > safety_switch_state ( ) ! = AP_HAL : : Util : : SAFETY_DISARMED ;
2018-07-20 10:46:29 -03:00
}
2018-02-08 19:46:57 -04:00
2018-01-17 03:18:00 -04:00
2018-07-20 10:46:29 -03:00
///// LED /////
2018-01-17 03:18:00 -04:00
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : led_out_send ( )
2018-07-20 10:46:29 -03:00
{
2020-06-24 09:07:28 -03:00
uint64_t now = AP_HAL : : native_micros64 ( ) ;
2018-07-20 10:46:29 -03:00
if ( ( now - _led_conf . last_update ) < LED_DELAY_US ) {
return ;
2018-01-17 03:18:00 -04:00
}
2023-01-04 21:09:23 -04:00
uavcan_equipment_indication_LightsCommand msg ;
2018-10-11 20:35:04 -03:00
{
WITH_SEMAPHORE ( _led_out_sem ) ;
2018-01-17 03:18:00 -04:00
2018-10-11 20:35:04 -03:00
if ( _led_conf . devices_count = = 0 ) {
return ;
}
2018-01-17 03:18:00 -04:00
2023-01-04 21:09:23 -04:00
msg . commands . len = _led_conf . devices_count ;
2018-10-11 20:35:04 -03:00
for ( uint8_t i = 0 ; i < _led_conf . devices_count ; i + + ) {
2023-01-04 21:09:23 -04:00
msg . commands . data [ i ] . light_id = _led_conf . devices [ i ] . led_index ;
msg . commands . data [ i ] . color . red = _led_conf . devices [ i ] . red > > 3 ;
msg . commands . data [ i ] . color . green = _led_conf . devices [ i ] . green > > 2 ;
msg . commands . data [ i ] . color . blue = _led_conf . devices [ i ] . blue > > 3 ;
2018-10-11 20:35:04 -03:00
}
2018-01-17 03:18:00 -04:00
}
2017-04-02 11:55:40 -03:00
2023-01-04 21:09:23 -04:00
rgb_led . broadcast ( msg ) ;
2018-07-20 10:46:29 -03:00
_led_conf . last_update = now ;
2017-04-02 11:55:40 -03:00
}
2023-04-06 21:18:01 -03:00
bool AP_DroneCAN : : led_write ( uint8_t led_index , uint8_t red , uint8_t green , uint8_t blue )
2017-04-02 11:55:40 -03:00
{
2023-04-06 21:18:01 -03:00
if ( _led_conf . devices_count > = AP_DRONECAN_MAX_LED_DEVICES ) {
2018-07-20 10:46:29 -03:00
return false ;
}
2017-04-02 11:55:40 -03:00
2018-10-11 20:35:04 -03:00
WITH_SEMAPHORE ( _led_out_sem ) ;
2018-03-16 00:19:17 -03:00
2018-07-20 10:46:29 -03:00
// check if a device instance exists. if so, break so the instance index is remembered
uint8_t instance = 0 ;
for ( ; instance < _led_conf . devices_count ; instance + + ) {
if ( _led_conf . devices [ instance ] . led_index = = led_index ) {
break ;
2018-03-16 00:19:17 -03:00
}
}
2018-07-20 10:46:29 -03:00
// load into the correct instance.
// if an existing instance was found in above for loop search,
// then instance value is < _led_conf.devices_count.
// otherwise a new one was just found so we increment the count.
// Either way, the correct instance is the current value of instance
_led_conf . devices [ instance ] . led_index = led_index ;
_led_conf . devices [ instance ] . red = red ;
_led_conf . devices [ instance ] . green = green ;
_led_conf . devices [ instance ] . blue = blue ;
2018-07-18 00:08:08 -03:00
2018-07-20 10:46:29 -03:00
if ( instance = = _led_conf . devices_count ) {
_led_conf . devices_count + + ;
2018-03-16 00:19:17 -03:00
}
2018-07-20 10:46:29 -03:00
return true ;
2018-03-16 00:19:17 -03:00
}
2019-08-30 23:45:02 -03:00
// buzzer send
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : buzzer_send ( )
2019-08-30 23:45:02 -03:00
{
2023-01-04 21:09:23 -04:00
uavcan_equipment_indication_BeepCommand msg ;
2019-08-30 23:45:02 -03:00
WITH_SEMAPHORE ( _buzzer . sem ) ;
uint8_t mask = ( 1U < < _driver_index ) ;
if ( ( _buzzer . pending_mask & mask ) = = 0 ) {
return ;
}
_buzzer . pending_mask & = ~ mask ;
msg . frequency = _buzzer . frequency ;
msg . duration = _buzzer . duration ;
2023-01-04 21:09:23 -04:00
buzzer . broadcast ( msg ) ;
2019-08-30 23:45:02 -03:00
}
// buzzer support
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : set_buzzer_tone ( float frequency , float duration_s )
2019-08-30 23:45:02 -03:00
{
WITH_SEMAPHORE ( _buzzer . sem ) ;
_buzzer . frequency = frequency ;
_buzzer . duration = duration_s ;
_buzzer . pending_mask = 0xFF ;
}
2021-09-15 03:48:19 -03:00
// notify state send
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : notify_state_send ( )
2021-09-15 03:48:19 -03:00
{
uint32_t now = AP_HAL : : native_millis ( ) ;
if ( _notify_state_hz = = 0 | | ( now - _last_notify_state_ms ) < uint32_t ( 1000 / _notify_state_hz ) ) {
return ;
}
2023-01-04 21:09:23 -04:00
ardupilot_indication_NotifyState msg ;
2021-09-15 03:48:19 -03:00
msg . vehicle_state = 0 ;
if ( AP_Notify : : flags . initialising ) {
2023-01-04 21:09:23 -04:00
msg . vehicle_state | = 1 < < ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_INITIALISING ;
2021-09-15 03:48:19 -03:00
}
if ( AP_Notify : : flags . armed ) {
2023-01-04 21:09:23 -04:00
msg . vehicle_state | = 1 < < ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_ARMED ;
2021-09-15 03:48:19 -03:00
}
if ( AP_Notify : : flags . flying ) {
2023-01-04 21:09:23 -04:00
msg . vehicle_state | = 1 < < ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_FLYING ;
2021-09-15 03:48:19 -03:00
}
if ( AP_Notify : : flags . compass_cal_running ) {
2023-01-04 21:09:23 -04:00
msg . vehicle_state | = 1 < < ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_MAGCAL_RUN ;
2021-09-15 03:48:19 -03:00
}
if ( AP_Notify : : flags . ekf_bad ) {
2023-01-04 21:09:23 -04:00
msg . vehicle_state | = 1 < < ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_EKF_BAD ;
2021-09-15 03:48:19 -03:00
}
if ( AP_Notify : : flags . esc_calibration ) {
2023-01-04 21:09:23 -04:00
msg . vehicle_state | = 1 < < ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_ESC_CALIBRATION ;
2021-09-15 03:48:19 -03:00
}
if ( AP_Notify : : flags . failsafe_battery ) {
2023-01-04 21:09:23 -04:00
msg . vehicle_state | = 1 < < ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_FAILSAFE_BATT ;
2021-09-15 03:48:19 -03:00
}
if ( AP_Notify : : flags . failsafe_gcs ) {
2023-01-04 21:09:23 -04:00
msg . vehicle_state | = 1 < < ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_FAILSAFE_GCS ;
2021-09-15 03:48:19 -03:00
}
if ( AP_Notify : : flags . failsafe_radio ) {
2023-01-04 21:09:23 -04:00
msg . vehicle_state | = 1 < < ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_FAILSAFE_RADIO ;
2021-09-15 03:48:19 -03:00
}
if ( AP_Notify : : flags . firmware_update ) {
2023-01-04 21:09:23 -04:00
msg . vehicle_state | = 1 < < ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_FW_UPDATE ;
2021-09-15 03:48:19 -03:00
}
if ( AP_Notify : : flags . gps_fusion ) {
2023-01-04 21:09:23 -04:00
msg . vehicle_state | = 1 < < ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_GPS_FUSION ;
2021-09-15 03:48:19 -03:00
}
if ( AP_Notify : : flags . gps_glitching ) {
2023-01-04 21:09:23 -04:00
msg . vehicle_state | = 1 < < ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_GPS_GLITCH ;
2021-09-15 03:48:19 -03:00
}
if ( AP_Notify : : flags . have_pos_abs ) {
2023-01-04 21:09:23 -04:00
msg . vehicle_state | = 1 < < ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_POS_ABS_AVAIL ;
2021-09-15 03:48:19 -03:00
}
if ( AP_Notify : : flags . leak_detected ) {
2023-01-04 21:09:23 -04:00
msg . vehicle_state | = 1 < < ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_LEAK_DET ;
2021-09-15 03:48:19 -03:00
}
if ( AP_Notify : : flags . parachute_release ) {
2023-01-04 21:09:23 -04:00
msg . vehicle_state | = 1 < < ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_CHUTE_RELEASED ;
2021-09-15 03:48:19 -03:00
}
if ( AP_Notify : : flags . powering_off ) {
2023-01-04 21:09:23 -04:00
msg . vehicle_state | = 1 < < ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_POWERING_OFF ;
2021-09-15 03:48:19 -03:00
}
if ( AP_Notify : : flags . pre_arm_check ) {
2023-01-04 21:09:23 -04:00
msg . vehicle_state | = 1 < < ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_PREARM ;
2021-09-15 03:48:19 -03:00
}
if ( AP_Notify : : flags . pre_arm_gps_check ) {
2023-01-04 21:09:23 -04:00
msg . vehicle_state | = 1 < < ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_PREARM_GPS ;
2021-09-15 03:48:19 -03:00
}
if ( AP_Notify : : flags . save_trim ) {
2023-01-04 21:09:23 -04:00
msg . vehicle_state | = 1 < < ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_SAVE_TRIM ;
2021-09-15 03:48:19 -03:00
}
if ( AP_Notify : : flags . vehicle_lost ) {
2023-01-04 21:09:23 -04:00
msg . vehicle_state | = 1 < < ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_LOST ;
2021-09-15 03:48:19 -03:00
}
if ( AP_Notify : : flags . video_recording ) {
2023-01-04 21:09:23 -04:00
msg . vehicle_state | = 1 < < ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_VIDEO_RECORDING ;
2021-09-15 03:48:19 -03:00
}
if ( AP_Notify : : flags . waiting_for_throw ) {
2023-01-04 21:09:23 -04:00
msg . vehicle_state | = 1 < < ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_THROW_READY ;
2021-09-15 03:48:19 -03:00
}
2023-01-04 21:09:23 -04:00
msg . aux_data_type = ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_YAW_EARTH_CENTIDEGREES ;
2021-09-15 03:48:19 -03:00
uint16_t yaw_cd = ( uint16_t ) ( 360.0f - degrees ( AP : : ahrs ( ) . get_yaw ( ) ) ) * 100.0f ;
const uint8_t * data = ( uint8_t * ) & yaw_cd ;
for ( uint8_t i = 0 ; i < 2 ; i + + ) {
2023-01-04 21:09:23 -04:00
msg . aux_data . data [ i ] = data [ i ] ;
2021-09-15 03:48:19 -03:00
}
2023-01-04 21:09:23 -04:00
msg . aux_data . len = 2 ;
notify_state . broadcast ( msg ) ;
2021-09-15 03:48:19 -03:00
_last_notify_state_ms = AP_HAL : : native_millis ( ) ;
}
2023-02-28 18:50:23 -04:00
# if AP_DRONECAN_SEND_GPS
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : gnss_send_fix ( )
2023-02-28 18:50:23 -04:00
{
const AP_GPS & gps = AP : : gps ( ) ;
const uint32_t gps_lib_time_ms = gps . last_message_time_ms ( ) ;
if ( _gnss . last_gps_lib_fix_ms = = gps_lib_time_ms ) {
return ;
}
_gnss . last_gps_lib_fix_ms = gps_lib_time_ms ;
/*
send Fix2 packet
*/
2023-01-04 21:09:23 -04:00
uavcan_equipment_gnss_Fix2 pkt { } ;
2023-02-28 18:50:23 -04:00
const Location & loc = gps . location ( ) ;
const Vector3f & vel = gps . velocity ( ) ;
pkt . timestamp . usec = AP_HAL : : native_micros64 ( ) ;
pkt . gnss_timestamp . usec = gps . time_epoch_usec ( ) ;
if ( pkt . gnss_timestamp . usec = = 0 ) {
2023-01-04 21:09:23 -04:00
pkt . gnss_time_standard = UAVCAN_EQUIPMENT_GNSS_FIX2_GNSS_TIME_STANDARD_NONE ;
2023-02-28 18:50:23 -04:00
} else {
2023-01-04 21:09:23 -04:00
pkt . gnss_time_standard = UAVCAN_EQUIPMENT_GNSS_FIX2_GNSS_TIME_STANDARD_UTC ;
2023-02-28 18:50:23 -04:00
}
pkt . longitude_deg_1e8 = uint64_t ( loc . lng ) * 10ULL ;
pkt . latitude_deg_1e8 = uint64_t ( loc . lat ) * 10ULL ;
pkt . height_ellipsoid_mm = loc . alt * 10 ;
pkt . height_msl_mm = loc . alt * 10 ;
for ( uint8_t i = 0 ; i < 3 ; i + + ) {
pkt . ned_velocity [ i ] = vel [ i ] ;
}
pkt . sats_used = gps . num_sats ( ) ;
switch ( gps . status ( ) ) {
case AP_GPS : : GPS_Status : : NO_GPS :
case AP_GPS : : GPS_Status : : NO_FIX :
2023-01-04 21:09:23 -04:00
pkt . status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_NO_FIX ;
pkt . mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_SINGLE ;
pkt . sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_DGPS_OTHER ;
2023-02-28 18:50:23 -04:00
break ;
case AP_GPS : : GPS_Status : : GPS_OK_FIX_2D :
2023-01-04 21:09:23 -04:00
pkt . status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_2D_FIX ;
pkt . mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_SINGLE ;
pkt . sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_DGPS_OTHER ;
2023-02-28 18:50:23 -04:00
break ;
case AP_GPS : : GPS_Status : : GPS_OK_FIX_3D :
2023-01-04 21:09:23 -04:00
pkt . status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_3D_FIX ;
pkt . mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_SINGLE ;
pkt . sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_DGPS_OTHER ;
2023-02-28 18:50:23 -04:00
break ;
case AP_GPS : : GPS_Status : : GPS_OK_FIX_3D_DGPS :
2023-01-04 21:09:23 -04:00
pkt . status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_3D_FIX ;
pkt . mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_DGPS ;
pkt . sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_DGPS_SBAS ;
2023-02-28 18:50:23 -04:00
break ;
case AP_GPS : : GPS_Status : : GPS_OK_FIX_3D_RTK_FLOAT :
2023-01-04 21:09:23 -04:00
pkt . status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_3D_FIX ;
pkt . mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_RTK ;
pkt . sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_RTK_FLOAT ;
2023-02-28 18:50:23 -04:00
break ;
case AP_GPS : : GPS_Status : : GPS_OK_FIX_3D_RTK_FIXED :
2023-01-04 21:09:23 -04:00
pkt . status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_3D_FIX ;
pkt . mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_RTK ;
pkt . sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_RTK_FIXED ;
2023-02-28 18:50:23 -04:00
break ;
}
2023-01-04 21:09:23 -04:00
pkt . covariance . len = 6 ;
2023-02-28 18:50:23 -04:00
float hacc ;
if ( gps . horizontal_accuracy ( hacc ) ) {
2023-01-04 21:09:23 -04:00
pkt . covariance . data [ 0 ] = pkt . covariance . data [ 1 ] = sq ( hacc ) ;
2023-02-28 18:50:23 -04:00
}
float vacc ;
if ( gps . vertical_accuracy ( vacc ) ) {
2023-01-04 21:09:23 -04:00
pkt . covariance . data [ 2 ] = sq ( vacc ) ;
2023-02-28 18:50:23 -04:00
}
float sacc ;
if ( gps . speed_accuracy ( sacc ) ) {
const float vc3 = sq ( sacc ) ;
2023-01-04 21:09:23 -04:00
pkt . covariance . data [ 3 ] = pkt . covariance . data [ 4 ] = pkt . covariance . data [ 5 ] = vc3 ;
2023-02-28 18:50:23 -04:00
}
2023-01-04 21:09:23 -04:00
gnss_fix2 . broadcast ( pkt ) ;
2023-02-28 18:50:23 -04:00
const uint32_t now_ms = AP_HAL : : native_millis ( ) ;
if ( now_ms - _gnss . last_send_status_ms > = 1000 ) {
_gnss . last_send_status_ms = now_ms ;
/*
send aux packet
*/
2023-01-04 21:09:23 -04:00
uavcan_equipment_gnss_Auxiliary pkt_auxiliary { } ;
2023-02-28 18:50:23 -04:00
pkt_auxiliary . hdop = gps . get_hdop ( ) * 0.01 ;
pkt_auxiliary . vdop = gps . get_vdop ( ) * 0.01 ;
2023-01-04 21:09:23 -04:00
gnss_auxiliary . broadcast ( pkt_auxiliary ) ;
2023-02-28 18:50:23 -04:00
/*
send Status packet
*/
2023-01-04 21:09:23 -04:00
ardupilot_gnss_Status pkt_status { } ;
2023-02-28 18:50:23 -04:00
pkt_status . healthy = gps . is_healthy ( ) ;
if ( gps . logging_present ( ) & & gps . logging_enabled ( ) & & ! gps . logging_failed ( ) ) {
2023-01-04 21:09:23 -04:00
pkt_status . status | = ARDUPILOT_GNSS_STATUS_STATUS_LOGGING ;
2023-02-28 18:50:23 -04:00
}
uint8_t idx ; // unused
if ( pkt_status . healthy & & ! gps . first_unconfigured_gps ( idx ) ) {
2023-01-04 21:09:23 -04:00
pkt_status . status | = ARDUPILOT_GNSS_STATUS_STATUS_ARMABLE ;
2023-02-28 18:50:23 -04:00
}
uint32_t error_codes ;
if ( gps . get_error_codes ( error_codes ) ) {
pkt_status . error_codes = error_codes ;
}
2023-01-04 21:09:23 -04:00
gnss_status . broadcast ( pkt_status ) ;
2023-02-28 18:50:23 -04:00
}
}
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : gnss_send_yaw ( )
2023-02-28 18:50:23 -04:00
{
const AP_GPS & gps = AP : : gps ( ) ;
if ( ! gps . have_gps_yaw ( ) ) {
return ;
}
float yaw_deg , yaw_acc_deg ;
uint32_t yaw_time_ms ;
if ( ! gps . gps_yaw_deg ( yaw_deg , yaw_acc_deg , yaw_time_ms ) & & yaw_time_ms ! = _gnss . last_lib_yaw_time_ms ) {
return ;
}
_gnss . last_lib_yaw_time_ms = yaw_time_ms ;
2023-01-04 21:09:23 -04:00
ardupilot_gnss_Heading pkt_heading { } ;
2023-02-28 18:50:23 -04:00
pkt_heading . heading_valid = true ;
pkt_heading . heading_accuracy_valid = is_positive ( yaw_acc_deg ) ;
pkt_heading . heading_rad = radians ( yaw_deg ) ;
pkt_heading . heading_accuracy_rad = radians ( yaw_acc_deg ) ;
2023-01-04 21:09:23 -04:00
gnss_heading . broadcast ( pkt_heading ) ;
2023-02-28 18:50:23 -04:00
}
# endif // AP_DRONECAN_SEND_GPS
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : rtcm_stream_send ( )
2019-10-21 08:10:33 -03:00
{
WITH_SEMAPHORE ( _rtcm_stream . sem ) ;
if ( _rtcm_stream . buf = = nullptr | |
_rtcm_stream . buf - > available ( ) = = 0 ) {
// nothing to send
return ;
}
2020-06-24 09:07:28 -03:00
uint32_t now = AP_HAL : : native_millis ( ) ;
2019-10-21 08:10:33 -03:00
if ( now - _rtcm_stream . last_send_ms < 20 ) {
// don't send more than 50 per second
return ;
}
_rtcm_stream . last_send_ms = now ;
2023-01-04 21:09:23 -04:00
uavcan_equipment_gnss_RTCMStream msg ;
2019-10-21 08:10:33 -03:00
uint32_t len = _rtcm_stream . buf - > available ( ) ;
if ( len > 128 ) {
len = 128 ;
}
2023-01-04 21:09:23 -04:00
msg . protocol_id = UAVCAN_EQUIPMENT_GNSS_RTCMSTREAM_PROTOCOL_ID_RTCM3 ;
2019-10-21 08:10:33 -03:00
for ( uint8_t i = 0 ; i < len ; i + + ) {
uint8_t b ;
if ( ! _rtcm_stream . buf - > read_byte ( & b ) ) {
return ;
}
2023-01-04 21:09:23 -04:00
msg . data . data [ i ] = b ;
2019-10-21 08:10:33 -03:00
}
2023-01-04 21:09:23 -04:00
msg . data . len = len ;
rtcm_stream . broadcast ( msg ) ;
2019-10-21 08:10:33 -03:00
}
2019-08-31 01:30:49 -03:00
// SafetyState send
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : safety_state_send ( )
2019-08-31 01:30:49 -03:00
{
2020-06-24 09:07:28 -03:00
uint32_t now = AP_HAL : : native_millis ( ) ;
2019-08-31 01:30:49 -03:00
if ( now - _last_safety_state_ms < 500 ) {
// update at 2Hz
return ;
}
_last_safety_state_ms = now ;
2021-01-22 18:27:23 -04:00
{ // handle SafetyState
2023-01-04 21:09:23 -04:00
ardupilot_indication_SafetyState safety_msg ;
2021-01-22 18:27:23 -04:00
switch ( hal . util - > safety_switch_state ( ) ) {
case AP_HAL : : Util : : SAFETY_ARMED :
2023-01-04 21:09:23 -04:00
safety_msg . status = ARDUPILOT_INDICATION_SAFETYSTATE_STATUS_SAFETY_OFF ;
2023-04-07 04:43:08 -03:00
safety_state . broadcast ( safety_msg ) ;
2021-01-22 18:27:23 -04:00
break ;
case AP_HAL : : Util : : SAFETY_DISARMED :
2023-01-04 21:09:23 -04:00
safety_msg . status = ARDUPILOT_INDICATION_SAFETYSTATE_STATUS_SAFETY_ON ;
2023-04-07 04:43:08 -03:00
safety_state . broadcast ( safety_msg ) ;
2021-01-22 18:27:23 -04:00
break ;
default :
// nothing to send
break ;
}
}
{ // handle ArmingStatus
2023-01-04 21:09:23 -04:00
uavcan_equipment_safety_ArmingStatus arming_msg ;
arming_msg . status = hal . util - > get_soft_armed ( ) ? UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_STATUS_FULLY_ARMED :
UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_STATUS_DISARMED ;
arming_status . broadcast ( arming_msg ) ;
2019-08-31 01:30:49 -03:00
}
}
2019-10-21 08:10:33 -03:00
/*
2023-04-08 01:27:51 -03:00
send RTCMStream packet on all active DroneCAN drivers
2019-10-21 08:10:33 -03:00
*/
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : send_RTCMStream ( const uint8_t * data , uint32_t len )
2019-10-21 08:10:33 -03:00
{
WITH_SEMAPHORE ( _rtcm_stream . sem ) ;
if ( _rtcm_stream . buf = = nullptr ) {
// give enough space for a full round from a NTRIP server with all
// constellations
_rtcm_stream . buf = new ByteBuffer ( 2400 ) ;
}
if ( _rtcm_stream . buf = = nullptr ) {
return ;
}
_rtcm_stream . buf - > write ( data , len ) ;
}
2019-09-02 23:25:39 -03:00
/*
handle Button message
*/
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : handle_button ( const CanardRxTransfer & transfer , const ardupilot_indication_Button & msg )
2019-09-02 23:25:39 -03:00
{
2023-01-04 21:09:23 -04:00
switch ( msg . button ) {
case ARDUPILOT_INDICATION_BUTTON_BUTTON_SAFETY : {
2019-09-02 23:25:39 -03:00
AP_BoardConfig * brdconfig = AP_BoardConfig : : get_singleton ( ) ;
2023-01-04 21:09:23 -04:00
if ( brdconfig & & brdconfig - > safety_button_handle_pressed ( msg . press_time ) ) {
2019-09-02 23:25:39 -03:00
AP_HAL : : Util : : safety_state state = hal . util - > safety_switch_state ( ) ;
if ( state = = AP_HAL : : Util : : SAFETY_ARMED ) {
hal . rcout - > force_safety_on ( ) ;
} else {
hal . rcout - > force_safety_off ( ) ;
}
}
break ;
}
}
}
2019-10-02 06:44:16 -03:00
/*
handle traffic report
*/
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : handle_traffic_report ( const CanardRxTransfer & transfer , const ardupilot_equipment_trafficmonitor_TrafficReport & msg )
2019-10-02 06:44:16 -03:00
{
2020-09-19 07:20:54 -03:00
# if HAL_ADSB_ENABLED
2019-10-02 06:44:16 -03:00
AP_ADSB * adsb = AP : : ADSB ( ) ;
if ( ! adsb | | ! adsb - > enabled ( ) ) {
// ADSB not enabled
return ;
}
AP_ADSB : : adsb_vehicle_t vehicle ;
mavlink_adsb_vehicle_t & pkt = vehicle . info ;
pkt . ICAO_address = msg . icao_address ;
pkt . tslc = msg . tslc ;
pkt . lat = msg . latitude_deg_1e7 ;
pkt . lon = msg . longitude_deg_1e7 ;
pkt . altitude = msg . alt_m * 1000 ;
pkt . heading = degrees ( msg . heading ) * 100 ;
pkt . hor_velocity = norm ( msg . velocity [ 0 ] , msg . velocity [ 1 ] ) * 100 ;
pkt . ver_velocity = - msg . velocity [ 2 ] * 100 ;
pkt . squawk = msg . squawk ;
for ( uint8_t i = 0 ; i < 9 ; i + + ) {
pkt . callsign [ i ] = msg . callsign [ i ] ;
}
pkt . emitter_type = msg . traffic_type ;
2023-01-04 21:09:23 -04:00
if ( msg . alt_type = = ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_ALT_TYPE_PRESSURE_AMSL ) {
2019-10-02 06:44:16 -03:00
pkt . flags | = ADSB_FLAGS_VALID_ALTITUDE ;
pkt . altitude_type = ADSB_ALTITUDE_TYPE_PRESSURE_QNH ;
2023-01-04 21:09:23 -04:00
} else if ( msg . alt_type = = ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_ALT_TYPE_WGS84 ) {
2019-10-02 06:44:16 -03:00
pkt . flags | = ADSB_FLAGS_VALID_ALTITUDE ;
pkt . altitude_type = ADSB_ALTITUDE_TYPE_GEOMETRIC ;
}
if ( msg . lat_lon_valid ) {
pkt . flags | = ADSB_FLAGS_VALID_COORDS ;
}
if ( msg . heading_valid ) {
pkt . flags | = ADSB_FLAGS_VALID_HEADING ;
}
if ( msg . velocity_valid ) {
pkt . flags | = ADSB_FLAGS_VALID_VELOCITY ;
}
if ( msg . callsign_valid ) {
pkt . flags | = ADSB_FLAGS_VALID_CALLSIGN ;
}
if ( msg . ident_valid ) {
pkt . flags | = ADSB_FLAGS_VALID_SQUAWK ;
}
if ( msg . simulated_report ) {
pkt . flags | = ADSB_FLAGS_SIMULATED ;
}
if ( msg . vertical_velocity_valid ) {
2020-08-21 13:11:19 -03:00
pkt . flags | = ADSB_FLAGS_VERTICAL_VELOCITY_VALID ;
2019-10-02 06:44:16 -03:00
}
if ( msg . baro_valid ) {
2020-08-21 13:11:19 -03:00
pkt . flags | = ADSB_FLAGS_BARO_VALID ;
2019-10-02 06:44:16 -03:00
}
2020-06-24 09:07:28 -03:00
vehicle . last_update_ms = AP_HAL : : native_millis ( ) - ( vehicle . info . tslc * 1000 ) ;
2019-10-02 06:44:16 -03:00
adsb - > handle_adsb_vehicle ( vehicle ) ;
2020-09-19 07:20:54 -03:00
# endif
2019-10-02 06:44:16 -03:00
}
2020-01-03 23:52:59 -04:00
/*
handle actuator status message
*/
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : handle_actuator_status ( const CanardRxTransfer & transfer , const uavcan_equipment_actuator_Status & msg )
2020-01-03 23:52:59 -04:00
{
// log as CSRV message
2020-06-24 09:07:28 -03:00
AP : : logger ( ) . Write_ServoStatus ( AP_HAL : : native_micros64 ( ) ,
2023-01-04 21:09:23 -04:00
msg . actuator_id ,
msg . position ,
msg . force ,
msg . speed ,
msg . power_rating_pct ) ;
2020-01-03 23:52:59 -04:00
}
2023-02-13 09:49:17 -04:00
# if AP_DRONECAN_VOLZ_FEEDBACK_ENABLED
2023-04-12 20:46:32 -03:00
void AP_DroneCAN : : handle_actuator_status_Volz ( const CanardRxTransfer & transfer , const com_volz_servo_ActuatorStatus & msg )
2023-02-13 09:49:17 -04:00
{
AP : : logger ( ) . WriteStreaming (
" CVOL " ,
" TimeUS,Id,Pos,Cur,V,Pow,T " ,
" s#dAv%O " ,
" F-00000 " ,
" QBfffBh " ,
AP_HAL : : native_micros64 ( ) ,
2023-04-12 20:46:32 -03:00
msg . actuator_id ,
ToDeg ( msg . actual_position ) ,
msg . current * 0.025f ,
msg . voltage * 0.2f ,
msg . motor_pwm * ( 100.0 / 255.0 ) ,
int16_t ( msg . motor_temperature ) - 50 ) ;
2023-02-13 09:49:17 -04:00
}
# endif
2020-01-04 00:57:01 -04:00
/*
handle ESC status message
*/
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : handle_ESC_status ( const CanardRxTransfer & transfer , const uavcan_equipment_esc_Status & msg )
2020-01-04 00:57:01 -04:00
{
2021-04-16 15:11:23 -03:00
# if HAL_WITH_ESC_TELEM
2023-04-08 01:27:51 -03:00
const uint8_t esc_offset = constrain_int16 ( _esc_offset . get ( ) , 0 , DRONECAN_SRV_NUMBER ) ;
2023-01-04 21:09:23 -04:00
const uint8_t esc_index = msg . esc_index + esc_offset ;
2020-08-05 12:04:55 -03:00
if ( ! is_esc_data_index_valid ( esc_index ) ) {
return ;
}
2021-02-27 12:44:01 -04:00
TelemetryData t {
2023-01-04 21:09:23 -04:00
. temperature_cdeg = int16_t ( ( KELVIN_TO_C ( msg . temperature ) ) * 100 ) ,
. voltage = msg . voltage ,
. current = msg . current ,
2021-02-27 12:44:01 -04:00
} ;
2020-08-05 12:04:55 -03:00
2023-01-04 21:09:23 -04:00
update_rpm ( esc_index , msg . rpm , msg . error_count ) ;
update_telem_data ( esc_index , t ,
( isnan ( msg . current ) ? 0 : AP_ESC_Telem_Backend : : TelemetryType : : CURRENT )
| ( isnan ( msg . voltage ) ? 0 : AP_ESC_Telem_Backend : : TelemetryType : : VOLTAGE )
| ( isnan ( msg . temperature ) ? 0 : AP_ESC_Telem_Backend : : TelemetryType : : TEMPERATURE ) ) ;
2021-04-16 15:11:23 -03:00
# endif
2020-08-05 12:04:55 -03:00
}
2023-04-06 21:18:01 -03:00
bool AP_DroneCAN : : is_esc_data_index_valid ( const uint8_t index ) {
2023-04-08 01:27:51 -03:00
if ( index > DRONECAN_SRV_NUMBER ) {
// printf("DroneCAN: invalid esc index: %d. max index allowed: %d\n\r", index, DRONECAN_SRV_NUMBER);
2020-08-05 12:04:55 -03:00
return false ;
}
return true ;
2020-01-04 00:57:01 -04:00
}
2020-11-29 19:47:32 -04:00
/*
handle LogMessage debug
*/
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : handle_debug ( const CanardRxTransfer & transfer , const uavcan_protocol_debug_LogMessage & msg )
2020-11-29 19:47:32 -04:00
{
2021-05-17 03:51:37 -03:00
# if HAL_LOGGING_ENABLED
2020-11-29 19:47:32 -04:00
if ( AP : : can ( ) . get_log_level ( ) ! = AP_CANManager : : LOG_NONE ) {
// log to onboard log and mavlink
2023-01-04 21:09:23 -04:00
GCS_SEND_TEXT ( MAV_SEVERITY_INFO , " CAN[%u] %s " , transfer . source_node_id , msg . text . data ) ;
2020-11-29 19:47:32 -04:00
} else {
// only log to onboard log
2023-01-04 21:09:23 -04:00
AP : : logger ( ) . Write_MessageF ( " CAN[%u] %s " , transfer . source_node_id , msg . text . data ) ;
2020-11-29 19:47:32 -04:00
}
# endif
}
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : send_parameter_request ( )
2021-07-16 13:27:11 -03:00
{
WITH_SEMAPHORE ( _param_sem ) ;
if ( param_request_sent ) {
return ;
}
2023-01-04 21:09:23 -04:00
param_get_set_client . request ( param_request_node_id , param_getset_req ) ;
2021-07-16 13:27:11 -03:00
param_request_sent = true ;
}
2023-04-06 21:18:01 -03:00
bool AP_DroneCAN : : set_parameter_on_node ( uint8_t node_id , const char * name , float value , ParamGetSetFloatCb * cb )
2021-07-16 13:27:11 -03:00
{
WITH_SEMAPHORE ( _param_sem ) ;
if ( param_int_cb ! = nullptr | |
param_float_cb ! = nullptr ) {
//busy
return false ;
}
2023-01-04 21:09:23 -04:00
param_getset_req . index = 0 ;
param_getset_req . name . len = strncpy_noterm ( ( char * ) param_getset_req . name . data , name , sizeof ( param_getset_req . name . data ) - 1 ) ;
param_getset_req . value . real_value = value ;
param_getset_req . value . union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE ;
2021-07-16 13:27:11 -03:00
param_float_cb = cb ;
param_request_sent = false ;
param_request_node_id = node_id ;
return true ;
}
2023-04-06 21:18:01 -03:00
bool AP_DroneCAN : : set_parameter_on_node ( uint8_t node_id , const char * name , int32_t value , ParamGetSetIntCb * cb )
2021-07-16 13:27:11 -03:00
{
WITH_SEMAPHORE ( _param_sem ) ;
if ( param_int_cb ! = nullptr | |
param_float_cb ! = nullptr ) {
//busy
return false ;
}
2023-01-04 21:09:23 -04:00
param_getset_req . index = 0 ;
param_getset_req . name . len = strncpy_noterm ( ( char * ) param_getset_req . name . data , name , sizeof ( param_getset_req . name . data ) - 1 ) ;
param_getset_req . value . integer_value = value ;
param_getset_req . value . union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE ;
2021-07-16 13:27:11 -03:00
param_int_cb = cb ;
param_request_sent = false ;
param_request_node_id = node_id ;
return true ;
}
2023-04-06 21:18:01 -03:00
bool AP_DroneCAN : : get_parameter_on_node ( uint8_t node_id , const char * name , ParamGetSetFloatCb * cb )
2021-07-16 13:27:11 -03:00
{
WITH_SEMAPHORE ( _param_sem ) ;
if ( param_int_cb ! = nullptr | |
param_float_cb ! = nullptr ) {
//busy
return false ;
}
2023-01-04 21:09:23 -04:00
param_getset_req . index = 0 ;
param_getset_req . name . len = strncpy_noterm ( ( char * ) param_getset_req . name . data , name , sizeof ( param_getset_req . name . data ) ) ;
param_getset_req . value . union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_EMPTY ;
2021-07-16 13:27:11 -03:00
param_float_cb = cb ;
param_request_sent = false ;
param_request_node_id = node_id ;
return true ;
}
2023-04-06 21:18:01 -03:00
bool AP_DroneCAN : : get_parameter_on_node ( uint8_t node_id , const char * name , ParamGetSetIntCb * cb )
2021-07-16 13:27:11 -03:00
{
WITH_SEMAPHORE ( _param_sem ) ;
if ( param_int_cb ! = nullptr | |
param_float_cb ! = nullptr ) {
//busy
return false ;
}
2023-01-04 21:09:23 -04:00
param_getset_req . index = 0 ;
param_getset_req . name . len = strncpy_noterm ( ( char * ) param_getset_req . name . data , name , sizeof ( param_getset_req . name . data ) ) ;
param_getset_req . value . union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_EMPTY ;
2021-07-16 13:27:11 -03:00
param_int_cb = cb ;
param_request_sent = false ;
param_request_node_id = node_id ;
return true ;
}
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : handle_param_get_set_response ( const CanardRxTransfer & transfer , const uavcan_protocol_param_GetSetResponse & rsp )
2021-07-16 13:27:11 -03:00
{
2023-01-04 21:09:23 -04:00
WITH_SEMAPHORE ( _param_sem ) ;
if ( ! param_int_cb & &
! param_float_cb ) {
2021-07-16 13:27:11 -03:00
return ;
}
2023-01-04 21:09:23 -04:00
if ( ( rsp . value . union_tag = = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE ) & & param_int_cb ) {
int32_t val = rsp . value . integer_value ;
if ( ( * param_int_cb ) ( this , transfer . source_node_id , ( const char * ) rsp . name . data , val ) ) {
2021-07-16 13:27:11 -03:00
// we want the parameter to be set with val
2023-01-04 21:09:23 -04:00
param_getset_req . index = 0 ;
memcpy ( param_getset_req . name . data , rsp . name . data , rsp . name . len ) ;
param_getset_req . value . integer_value = val ;
param_getset_req . value . union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE ;
param_request_sent = false ;
param_request_node_id = transfer . source_node_id ;
2021-07-16 13:27:11 -03:00
return ;
}
2023-01-04 21:09:23 -04:00
} else if ( ( rsp . value . union_tag = = UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE ) & & param_float_cb ) {
float val = rsp . value . real_value ;
if ( ( * param_float_cb ) ( this , transfer . source_node_id , ( const char * ) rsp . name . data , val ) ) {
2021-07-16 13:27:11 -03:00
// we want the parameter to be set with val
2023-01-04 21:09:23 -04:00
param_getset_req . index = 0 ;
memcpy ( param_getset_req . name . data , rsp . name . data , rsp . name . len ) ;
param_getset_req . value . real_value = val ;
param_getset_req . value . union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE ;
param_request_sent = false ;
param_request_node_id = transfer . source_node_id ;
2021-07-16 13:27:11 -03:00
return ;
}
}
2023-01-04 21:09:23 -04:00
param_int_cb = nullptr ;
param_float_cb = nullptr ;
2021-07-16 13:27:11 -03:00
}
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : send_parameter_save_request ( )
2021-07-16 13:27:11 -03:00
{
WITH_SEMAPHORE ( _param_save_sem ) ;
if ( param_save_request_sent ) {
return ;
}
2023-01-04 21:09:23 -04:00
param_save_client . request ( param_save_request_node_id , param_save_req ) ;
2021-07-16 13:27:11 -03:00
param_save_request_sent = true ;
}
2023-04-06 21:18:01 -03:00
bool AP_DroneCAN : : save_parameters_on_node ( uint8_t node_id , ParamSaveCb * cb )
2021-07-16 13:27:11 -03:00
{
WITH_SEMAPHORE ( _param_save_sem ) ;
if ( save_param_cb ! = nullptr ) {
//busy
return false ;
}
2023-01-04 21:09:23 -04:00
param_save_req . opcode = UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_REQUEST_OPCODE_SAVE ;
2021-07-16 13:27:11 -03:00
param_save_request_sent = false ;
param_save_request_node_id = node_id ;
save_param_cb = cb ;
return true ;
}
// handle parameter save request response
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : handle_param_save_response ( const CanardRxTransfer & transfer , const uavcan_protocol_param_ExecuteOpcodeResponse & rsp )
2021-07-16 13:27:11 -03:00
{
2023-01-04 21:09:23 -04:00
WITH_SEMAPHORE ( _param_save_sem ) ;
if ( ! save_param_cb ) {
2021-07-16 13:27:11 -03:00
return ;
}
2023-01-04 21:09:23 -04:00
( * save_param_cb ) ( this , transfer . source_node_id , rsp . ok ) ;
save_param_cb = nullptr ;
2021-07-16 13:27:11 -03:00
}
// Send Reboot command
2023-04-08 01:27:51 -03:00
// Note: Do not call this from outside DroneCAN thread context,
2021-07-16 13:27:11 -03:00
// THIS IS NOT A THREAD SAFE API!
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : send_reboot_request ( uint8_t node_id )
2021-07-16 13:27:11 -03:00
{
2023-01-04 21:09:23 -04:00
uavcan_protocol_RestartNodeRequest request ;
request . magic_number = UAVCAN_PROTOCOL_RESTARTNODE_REQUEST_MAGIC_NUMBER ;
restart_node_client . request ( node_id , request ) ;
2021-07-16 13:27:11 -03:00
}
2021-09-10 23:47:02 -03:00
// check if a option is set and if it is then reset it to 0.
// return true if it was set
2023-04-06 21:18:01 -03:00
bool AP_DroneCAN : : check_and_reset_option ( Options option )
2021-09-10 23:47:02 -03:00
{
bool ret = option_is_set ( option ) ;
if ( ret ) {
_options . set_and_save ( int16_t ( _options . get ( ) & ~ uint16_t ( option ) ) ) ;
}
return ret ;
}
2022-04-04 07:33:33 -03:00
// handle prearm check
2023-04-06 21:18:01 -03:00
bool AP_DroneCAN : : prearm_check ( char * fail_msg , uint8_t fail_msg_len ) const
2022-04-04 07:33:33 -03:00
{
// forward this to DNA_Server
2023-01-04 21:09:23 -04:00
return _dna_server . prearm_check ( fail_msg , fail_msg_len ) ;
2022-04-04 07:33:33 -03:00
}
2022-12-06 22:36:20 -04:00
/*
periodic logging
*/
2023-04-06 21:18:01 -03:00
void AP_DroneCAN : : logging ( void )
2022-12-06 22:36:20 -04:00
{
# if HAL_LOGGING_ENABLED
const uint32_t now_ms = AP_HAL : : millis ( ) ;
if ( now_ms - last_log_ms < 1000 ) {
return ;
}
last_log_ms = now_ms ;
if ( HAL_NUM_CAN_IFACES < = _driver_index ) {
// no interface?
return ;
}
const auto * iface = hal . can [ _driver_index ] ;
if ( iface = = nullptr ) {
return ;
}
const auto * stats = iface - > get_statistics ( ) ;
if ( stats = = nullptr ) {
// statistics not implemented on this interface
return ;
}
const auto & s = * stats ;
AP : : logger ( ) . WriteStreaming ( " CANS " ,
" TimeUS,I,T,Trq,Trej,Tov,Tto,Tab,R,Rov,Rer,Bo,Etx,Stx,Ftx " ,
" s#------------- " ,
" F-------------- " ,
" QBIIIIIIIIIIIII " ,
AP_HAL : : micros64 ( ) ,
_driver_index ,
s . tx_success ,
s . tx_requests ,
s . tx_rejected ,
s . tx_overflow ,
s . tx_timedout ,
s . tx_abort ,
s . rx_received ,
s . rx_overflow ,
s . rx_errors ,
s . num_busoff_err ,
_esc_send_count ,
_srv_send_count ,
_fail_send_count ) ;
# endif // HAL_LOGGING_ENABLED
}
2020-06-24 09:07:28 -03:00
# endif // HAL_NUM_CAN_IFACES