123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290 |
- #include <AP_HAL/AP_HAL.h>
- #include <AP_Math/AP_Math.h>
- #include <AP_Vehicle/AP_Vehicle.h>
- #include "SRV_Channel.h"
- #if HAL_WITH_UAVCAN
- #include <AP_BoardConfig/AP_BoardConfig_CAN.h>
- #include <AP_UAVCAN/AP_UAVCAN.h>
-
- #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
- #include <AP_KDECAN/AP_KDECAN.h>
- #endif
- #include <AP_ToshibaCAN/AP_ToshibaCAN.h>
- #endif
- extern const AP_HAL::HAL& hal;
- SRV_Channel *SRV_Channels::channels;
- SRV_Channels *SRV_Channels::_singleton;
- AP_Volz_Protocol *SRV_Channels::volz_ptr;
- AP_SBusOut *SRV_Channels::sbus_ptr;
- AP_RobotisServo *SRV_Channels::robotis_ptr;
- #if HAL_SUPPORT_RCOUT_SERIAL
- AP_BLHeli *SRV_Channels::blheli_ptr;
- #endif
- uint16_t SRV_Channels::disabled_mask;
- uint16_t SRV_Channels::digital_mask;
- uint16_t SRV_Channels::reversible_mask;
- bool SRV_Channels::disabled_passthrough;
- bool SRV_Channels::initialised;
- bool SRV_Channels::emergency_stop;
- Bitmask<SRV_Channel::k_nr_aux_servo_functions> SRV_Channels::function_mask;
- SRV_Channels::srv_function SRV_Channels::functions[SRV_Channel::k_nr_aux_servo_functions];
- const AP_Param::GroupInfo SRV_Channels::var_info[] = {
-
-
- AP_SUBGROUPINFO(obj_channels[0], "1_", 1, SRV_Channels, SRV_Channel),
-
-
- AP_SUBGROUPINFO(obj_channels[1], "2_", 2, SRV_Channels, SRV_Channel),
-
-
- AP_SUBGROUPINFO(obj_channels[2], "3_", 3, SRV_Channels, SRV_Channel),
-
-
- AP_SUBGROUPINFO(obj_channels[3], "4_", 4, SRV_Channels, SRV_Channel),
-
-
- AP_SUBGROUPINFO(obj_channels[4], "5_", 5, SRV_Channels, SRV_Channel),
-
-
- AP_SUBGROUPINFO(obj_channels[5], "6_", 6, SRV_Channels, SRV_Channel),
-
-
- AP_SUBGROUPINFO(obj_channels[6], "7_", 7, SRV_Channels, SRV_Channel),
-
-
- AP_SUBGROUPINFO(obj_channels[7], "8_", 8, SRV_Channels, SRV_Channel),
-
-
- AP_SUBGROUPINFO(obj_channels[8], "9_", 9, SRV_Channels, SRV_Channel),
-
-
- AP_SUBGROUPINFO(obj_channels[9], "10_", 10, SRV_Channels, SRV_Channel),
-
-
- AP_SUBGROUPINFO(obj_channels[10], "11_", 11, SRV_Channels, SRV_Channel),
-
-
- AP_SUBGROUPINFO(obj_channels[11], "12_", 12, SRV_Channels, SRV_Channel),
-
-
- AP_SUBGROUPINFO(obj_channels[12], "13_", 13, SRV_Channels, SRV_Channel),
-
-
- AP_SUBGROUPINFO(obj_channels[13], "14_", 14, SRV_Channels, SRV_Channel),
-
-
- AP_SUBGROUPINFO(obj_channels[14], "15_", 15, SRV_Channels, SRV_Channel),
-
-
- AP_SUBGROUPINFO(obj_channels[15], "16_", 16, SRV_Channels, SRV_Channel),
-
-
-
-
-
- AP_GROUPINFO_FRAME("_AUTO_TRIM", 17, SRV_Channels, auto_trim, 0, AP_PARAM_FRAME_PLANE),
-
-
-
-
-
-
- AP_GROUPINFO("_RATE", 18, SRV_Channels, default_rate, 50),
-
-
- AP_SUBGROUPINFO(volz, "_VOLZ_", 19, SRV_Channels, AP_Volz_Protocol),
-
-
- AP_SUBGROUPINFO(sbus, "_SBUS_", 20, SRV_Channels, AP_SBusOut),
- #if HAL_SUPPORT_RCOUT_SERIAL
-
-
- AP_SUBGROUPINFO(blheli, "_BLH_", 21, SRV_Channels, AP_BLHeli),
- #endif
-
-
- AP_SUBGROUPINFO(robotis, "_ROB_", 22, SRV_Channels, AP_RobotisServo),
-
- AP_GROUPEND
- };
- SRV_Channels::SRV_Channels(void)
- {
- _singleton = this;
- channels = obj_channels;
-
- AP_Param::setup_object_defaults(this, var_info);
-
- for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
- channels[i].ch_num = i;
- }
- volz_ptr = &volz;
- sbus_ptr = &sbus;
- robotis_ptr = &robotis;
- #if HAL_SUPPORT_RCOUT_SERIAL
- blheli_ptr = &blheli;
- #endif
- }
- void SRV_Channels::save_trim(void)
- {
- for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
- if (trimmed_mask & (1U<<i)) {
- channels[i].servo_trim.set_and_save(channels[i].servo_trim.get());
- }
- }
- trimmed_mask = 0;
- }
- void SRV_Channels::setup_failsafe_trim_all_non_motors(void)
- {
- for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
- if (!SRV_Channel::is_motor(channels[i].get_function())) {
- hal.rcout->set_failsafe_pwm(1U<<channels[i].ch_num, channels[i].servo_trim);
- }
- }
- }
- void SRV_Channels::calc_pwm(void)
- {
- for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
- channels[i].calc_pwm(functions[channels[i].function].output_scaled);
- }
- }
- void SRV_Channels::set_output_pwm_chan(uint8_t chan, uint16_t value)
- {
- if (chan < NUM_SERVO_CHANNELS) {
- channels[chan].set_output_pwm(value);
- }
- }
- void SRV_Channels::cork()
- {
- hal.rcout->cork();
- }
- void SRV_Channels::push()
- {
- hal.rcout->push();
-
- volz_ptr->update();
-
- sbus_ptr->update();
-
- robotis_ptr->update();
-
- #if HAL_SUPPORT_RCOUT_SERIAL
-
- blheli_ptr->update_telemetry();
- #endif
- #if HAL_WITH_UAVCAN
-
- uint8_t can_num_drivers = AP::can().get_num_drivers();
- for (uint8_t i = 0; i < can_num_drivers; i++) {
- switch (AP::can().get_protocol_type(i)) {
- case AP_BoardConfig_CAN::Protocol_Type_UAVCAN: {
- AP_UAVCAN *ap_uavcan = AP_UAVCAN::get_uavcan(i);
- if (ap_uavcan == nullptr) {
- continue;
- }
- ap_uavcan->SRV_push_servos();
- break;
- }
- case AP_BoardConfig_CAN::Protocol_Type_KDECAN: {
- #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
- AP_KDECAN *ap_kdecan = AP_KDECAN::get_kdecan(i);
- if (ap_kdecan == nullptr) {
- continue;
- }
- ap_kdecan->update();
- break;
- #endif
- }
- case AP_BoardConfig_CAN::Protocol_Type_ToshibaCAN: {
- AP_ToshibaCAN *ap_tcan = AP_ToshibaCAN::get_tcan(i);
- if (ap_tcan == nullptr) {
- continue;
- }
- ap_tcan->update();
- break;
- }
- case AP_BoardConfig_CAN::Protocol_Type_None:
- default:
- break;
- }
- }
- #endif
- }
|