Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/AP_Periph/rc_out.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14#include <AP_HAL/AP_HAL.h>15#ifdef HAL_PERIPH_ENABLE_RC_OUT16#include "AP_Periph.h"17#if AP_SIM_ENABLED18#include <dronecan_msgs.h>19#endif2021// magic value from UAVCAN driver packet22// dsdl/uavcan/equipment/esc/1030.RawCommand.uavcan23// Raw ESC command normalized into [-8192, 8191]24#define UAVCAN_ESC_MAX_VALUE 81912526#define SERVO_OUT_RCIN_MAX 32 // note that we allow for more than is in the enum27#define SERVO_OUT_MOTOR_MAX 12 // SRV_Channel::k_motor1 ... SRV_Channel::k_motor8, SRV_Channel::k_motor9 ... SRV_Channel::k_motor122829extern const AP_HAL::HAL &hal;3031void AP_Periph_FW::rcout_init()32{33#if AP_PERIPH_SAFETY_SWITCH_ENABLED34// start up with safety enabled. This disables the pwm output until we receive an packet from the rempte system35hal.rcout->force_safety_on();36#else37hal.rcout->force_safety_off();38#endif3940#if HAL_WITH_ESC_TELEM && !HAL_GCS_ENABLED41if (g.esc_telem_port >= 0) {42serial_manager.set_protocol_and_baud(g.esc_telem_port, AP_SerialManager::SerialProtocol_ESCTelemetry, 115200);43}44#endif4546#if HAL_PWM_COUNT > 047for (uint8_t i=0; i<HAL_PWM_COUNT; i++) {48servo_channels.set_default_function(i, SRV_Channel::Aux_servo_function_t(SRV_Channel::k_rcin1 + i));49}50#endif5152for (uint8_t i=0; i<SERVO_OUT_RCIN_MAX; i++) {53SRV_Channels::set_angle(SRV_Channel::Aux_servo_function_t(SRV_Channel::k_rcin1 + i), 1000);54}5556uint32_t esc_mask = 0;57for (uint8_t i=0; i<SERVO_OUT_MOTOR_MAX; i++) {58SRV_Channels::set_range(SRV_Channels::get_motor_function(i), UAVCAN_ESC_MAX_VALUE);59uint8_t chan;60if (SRV_Channels::find_channel(SRV_Channels::get_motor_function(i), chan)) {61esc_mask |= 1U << chan;62}63}6465// run this once and at 1Hz to configure aux and esc ranges66rcout_init_1Hz();6768#if HAL_DSHOT_ENABLED69hal.rcout->set_dshot_esc_type(SRV_Channels::get_dshot_esc_type());70#endif7172// run PWM ESCs at configured rate73hal.rcout->set_freq(esc_mask, g.esc_rate.get());7475// setup ESCs with the desired PWM type, allowing for DShot76AP::srv().init(esc_mask, (AP_HAL::RCOutput::output_mode)g.esc_pwm_type.get());7778// run DShot at 1kHz79hal.rcout->set_dshot_rate(SRV_Channels::get_dshot_rate(), 400);80#if HAL_WITH_ESC_TELEM81esc_telem_update_period_ms = 1000 / constrain_int32(g.esc_telem_rate.get(), 1, 1000);82#endif83}8485void AP_Periph_FW::rcout_init_1Hz()86{87// this runs at 1Hz to allow for run-time param changes88AP::srv().enable_aux_servos();8990for (uint8_t i=0; i<SERVO_OUT_MOTOR_MAX; i++) {91servo_channels.set_esc_scaling_for(SRV_Channels::get_motor_function(i));92}93}9495void AP_Periph_FW::rcout_esc(int16_t *rc, uint8_t num_channels)96{97if (rc == nullptr) {98return;99}100101const uint8_t channel_count = MIN(num_channels, SERVO_OUT_MOTOR_MAX);102for (uint8_t i=0; i<channel_count; i++) {103// we don't support motor reversal yet on ESCs in AP_Periph104SRV_Channels::set_output_scaled(SRV_Channels::get_motor_function(i), MAX(0,rc[i]));105}106107rcout_has_new_data_to_update = true;108}109110void AP_Periph_FW::rcout_srv_unitless(uint8_t actuator_id, const float command_value)111{112#if HAL_PWM_COUNT > 0113const SRV_Channel::Aux_servo_function_t function = SRV_Channel::Aux_servo_function_t(SRV_Channel::k_rcin1 + actuator_id - 1);114SRV_Channels::set_output_norm(function, command_value);115116rcout_has_new_data_to_update = true;117#if AP_SIM_ENABLED118sim_update_actuator(actuator_id);119#endif120#endif121}122123void AP_Periph_FW::rcout_srv_PWM(uint8_t actuator_id, const float command_value)124{125#if HAL_PWM_COUNT > 0126const SRV_Channel::Aux_servo_function_t function = SRV_Channel::Aux_servo_function_t(SRV_Channel::k_rcin1 + actuator_id - 1);127SRV_Channels::set_output_pwm(function, uint16_t(command_value+0.5));128129rcout_has_new_data_to_update = true;130#if AP_SIM_ENABLED131sim_update_actuator(actuator_id);132#endif133#endif134}135136void AP_Periph_FW::rcout_handle_safety_state(uint8_t safety_state)137{138if (safety_state == 255) {139hal.rcout->force_safety_off();140} else {141hal.rcout->force_safety_on();142}143rcout_has_new_data_to_update = true;144}145146void AP_Periph_FW::rcout_update()147{148uint32_t now_ms = AP_HAL::millis();149150const uint16_t esc_timeout_ms = g.esc_command_timeout_ms >= 0 ? g.esc_command_timeout_ms : 0; // Don't allow negative timeouts!151const bool has_esc_rawcommand_timed_out = esc_timeout_ms != 0 && ((now_ms - last_esc_raw_command_ms) >= esc_timeout_ms);152if (last_esc_num_channels > 0 && has_esc_rawcommand_timed_out) {153// If we've seen ESCs previously, and a timeout has occurred, then zero the outputs154int16_t esc_output[last_esc_num_channels];155memset(esc_output, 0, sizeof(esc_output));156rcout_esc(esc_output, last_esc_num_channels);157158// register that the output has been changed159rcout_has_new_data_to_update = true;160}161162if (!rcout_has_new_data_to_update) {163return;164}165rcout_has_new_data_to_update = false;166167auto &srv = AP::srv();168SRV_Channels::calc_pwm();169srv.cork();170SRV_Channels::output_ch_all();171srv.push();172#if HAL_WITH_ESC_TELEM173if (now_ms - last_esc_telem_update_ms >= esc_telem_update_period_ms) {174last_esc_telem_update_ms = now_ms;175esc_telem_update();176}177#if AP_EXTENDED_ESC_TELEM_ENABLED178esc_telem_extended_update(now_ms);179#endif180#endif181}182183#if AP_SIM_ENABLED184/*185update simulation of servos, sending actuator status186*/187void AP_Periph_FW::sim_update_actuator(uint8_t actuator_id)188{189sim_actuator.mask |= 1U << actuator_id;190191// send status at 10Hz192const uint32_t period_ms = 100;193const uint32_t now_ms = AP_HAL::millis();194195if (now_ms - sim_actuator.last_send_ms < period_ms) {196return;197}198sim_actuator.last_send_ms = now_ms;199200for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {201if ((sim_actuator.mask & (1U<<i)) == 0) {202continue;203}204const SRV_Channel::Aux_servo_function_t function = SRV_Channel::Aux_servo_function_t(SRV_Channel::k_rcin1 + actuator_id - 1);205uavcan_equipment_actuator_Status pkt {};206pkt.actuator_id = i;207// assume 45 degree angle for simulation208pkt.position = radians(SRV_Channels::get_output_norm(function) * 45);209pkt.force = 0;210pkt.speed = 0;211pkt.power_rating_pct = UAVCAN_EQUIPMENT_ACTUATOR_STATUS_POWER_RATING_PCT_UNKNOWN;212213uint8_t buffer[UAVCAN_EQUIPMENT_ACTUATOR_STATUS_MAX_SIZE];214uint16_t total_size = uavcan_equipment_actuator_Status_encode(&pkt, buffer, !canfdout());215216canard_broadcast(UAVCAN_EQUIPMENT_ACTUATOR_STATUS_SIGNATURE,217UAVCAN_EQUIPMENT_ACTUATOR_STATUS_ID,218CANARD_TRANSFER_PRIORITY_LOW,219&buffer[0],220total_size);221}222}223#endif // AP_SIM_ENABLED224225#endif // HAL_PERIPH_ENABLE_RC_OUT226227228