2020-12-12 05:08:45 -04:00
|
|
|
/*
|
|
|
|
This program 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.
|
|
|
|
|
|
|
|
This program 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/>.
|
|
|
|
*/
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#ifdef HAL_PERIPH_ENABLE_RC_OUT
|
|
|
|
#include "AP_Periph.h"
|
2024-11-18 17:04:15 -04:00
|
|
|
#if AP_SIM_ENABLED
|
|
|
|
#include <dronecan_msgs.h>
|
|
|
|
#endif
|
2020-12-12 05:08:45 -04:00
|
|
|
|
|
|
|
// magic value from UAVCAN driver packet
|
|
|
|
// dsdl/uavcan/equipment/esc/1030.RawCommand.uavcan
|
|
|
|
// Raw ESC command normalized into [-8192, 8191]
|
|
|
|
#define UAVCAN_ESC_MAX_VALUE 8191
|
|
|
|
|
2022-05-20 08:32:58 -03:00
|
|
|
#define SERVO_OUT_RCIN_MAX 32 // note that we allow for more than is in the enum
|
2020-12-12 05:08:45 -04:00
|
|
|
#define SERVO_OUT_MOTOR_MAX 12 // SRV_Channel::k_motor1 ... SRV_Channel::k_motor8, SRV_Channel::k_motor9 ... SRV_Channel::k_motor12
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL &hal;
|
|
|
|
|
|
|
|
void AP_Periph_FW::rcout_init()
|
|
|
|
{
|
2023-09-13 16:27:37 -03:00
|
|
|
#if AP_PERIPH_SAFETY_SWITCH_ENABLED
|
2020-12-21 20:27:53 -04:00
|
|
|
// start up with safety enabled. This disables the pwm output until we receive an packet from the rempte system
|
|
|
|
hal.rcout->force_safety_on();
|
2023-09-13 16:27:37 -03:00
|
|
|
#else
|
|
|
|
hal.rcout->force_safety_off();
|
|
|
|
#endif
|
2020-12-21 20:27:53 -04:00
|
|
|
|
2021-12-09 16:30:58 -04:00
|
|
|
#if HAL_WITH_ESC_TELEM && !HAL_GCS_ENABLED
|
2021-12-07 04:09:41 -04:00
|
|
|
if (g.esc_telem_port >= 0) {
|
|
|
|
serial_manager.set_protocol_and_baud(g.esc_telem_port, AP_SerialManager::SerialProtocol_ESCTelemetry, 115200);
|
|
|
|
}
|
2021-12-09 16:30:58 -04:00
|
|
|
#endif
|
2021-12-07 04:09:41 -04:00
|
|
|
|
2021-04-15 20:14:23 -03:00
|
|
|
#if HAL_PWM_COUNT > 0
|
2020-12-12 05:08:45 -04:00
|
|
|
for (uint8_t i=0; i<HAL_PWM_COUNT; i++) {
|
|
|
|
servo_channels.set_default_function(i, SRV_Channel::Aux_servo_function_t(SRV_Channel::k_rcin1 + i));
|
|
|
|
}
|
2021-04-15 20:14:23 -03:00
|
|
|
#endif
|
2020-12-12 05:08:45 -04:00
|
|
|
|
|
|
|
for (uint8_t i=0; i<SERVO_OUT_RCIN_MAX; i++) {
|
|
|
|
SRV_Channels::set_angle(SRV_Channel::Aux_servo_function_t(SRV_Channel::k_rcin1 + i), 1000);
|
|
|
|
}
|
2021-03-13 18:56:43 -04:00
|
|
|
|
2022-05-15 18:29:45 -03:00
|
|
|
uint32_t esc_mask = 0;
|
2020-12-12 05:08:45 -04:00
|
|
|
for (uint8_t i=0; i<SERVO_OUT_MOTOR_MAX; i++) {
|
2021-03-13 20:03:12 -04:00
|
|
|
SRV_Channels::set_range(SRV_Channels::get_motor_function(i), UAVCAN_ESC_MAX_VALUE);
|
2021-03-13 18:56:43 -04:00
|
|
|
uint8_t chan;
|
|
|
|
if (SRV_Channels::find_channel(SRV_Channels::get_motor_function(i), chan)) {
|
|
|
|
esc_mask |= 1U << chan;
|
|
|
|
}
|
2020-12-12 05:08:45 -04:00
|
|
|
}
|
2020-12-21 20:27:53 -04:00
|
|
|
|
|
|
|
// run this once and at 1Hz to configure aux and esc ranges
|
|
|
|
rcout_init_1Hz();
|
2021-04-15 08:02:47 -03:00
|
|
|
|
2024-07-03 16:38:16 -03:00
|
|
|
#if HAL_DSHOT_ENABLED
|
|
|
|
hal.rcout->set_dshot_esc_type(SRV_Channels::get_dshot_esc_type());
|
|
|
|
#endif
|
|
|
|
|
2024-06-27 20:20:37 -03:00
|
|
|
// run PWM ESCs at configured rate
|
|
|
|
hal.rcout->set_freq(esc_mask, g.esc_rate.get());
|
|
|
|
|
2022-09-05 14:07:19 -03:00
|
|
|
// setup ESCs with the desired PWM type, allowing for DShot
|
2024-11-09 03:40:03 -04:00
|
|
|
AP::srv().init(esc_mask, (AP_HAL::RCOutput::output_mode)g.esc_pwm_type.get());
|
2022-09-05 14:07:19 -03:00
|
|
|
|
2021-04-15 08:02:47 -03:00
|
|
|
// run DShot at 1kHz
|
2022-09-05 14:07:19 -03:00
|
|
|
hal.rcout->set_dshot_rate(SRV_Channels::get_dshot_rate(), 400);
|
|
|
|
#if HAL_WITH_ESC_TELEM
|
|
|
|
esc_telem_update_period_ms = 1000 / constrain_int32(g.esc_telem_rate.get(), 1, 1000);
|
|
|
|
#endif
|
2020-12-21 20:27:53 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
void AP_Periph_FW::rcout_init_1Hz()
|
|
|
|
{
|
|
|
|
// this runs at 1Hz to allow for run-time param changes
|
2024-11-09 03:40:03 -04:00
|
|
|
AP::srv().enable_aux_servos();
|
2020-12-21 20:27:53 -04:00
|
|
|
|
|
|
|
for (uint8_t i=0; i<SERVO_OUT_MOTOR_MAX; i++) {
|
|
|
|
servo_channels.set_esc_scaling_for(SRV_Channels::get_motor_function(i));
|
|
|
|
}
|
2020-12-12 05:08:45 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
void AP_Periph_FW::rcout_esc(int16_t *rc, uint8_t num_channels)
|
|
|
|
{
|
|
|
|
if (rc == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
const uint8_t channel_count = MIN(num_channels, SERVO_OUT_MOTOR_MAX);
|
|
|
|
for (uint8_t i=0; i<channel_count; i++) {
|
2021-03-13 20:03:12 -04:00
|
|
|
// we don't support motor reversal yet on ESCs in AP_Periph
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channels::get_motor_function(i), MAX(0,rc[i]));
|
2020-12-12 05:08:45 -04:00
|
|
|
}
|
|
|
|
|
2020-12-29 01:06:44 -04:00
|
|
|
rcout_has_new_data_to_update = true;
|
2020-12-12 05:08:45 -04:00
|
|
|
}
|
|
|
|
|
2022-09-12 00:27:22 -03:00
|
|
|
void AP_Periph_FW::rcout_srv_unitless(uint8_t actuator_id, const float command_value)
|
2020-12-12 05:08:45 -04:00
|
|
|
{
|
2021-04-15 20:14:23 -03:00
|
|
|
#if HAL_PWM_COUNT > 0
|
2020-12-12 05:08:45 -04:00
|
|
|
const SRV_Channel::Aux_servo_function_t function = SRV_Channel::Aux_servo_function_t(SRV_Channel::k_rcin1 + actuator_id - 1);
|
|
|
|
SRV_Channels::set_output_norm(function, command_value);
|
|
|
|
|
2020-12-29 01:06:44 -04:00
|
|
|
rcout_has_new_data_to_update = true;
|
2024-11-18 17:04:15 -04:00
|
|
|
#if AP_SIM_ENABLED
|
|
|
|
sim_update_actuator(actuator_id);
|
|
|
|
#endif
|
2021-04-15 20:14:23 -03:00
|
|
|
#endif
|
2020-12-12 05:08:45 -04:00
|
|
|
}
|
|
|
|
|
2022-09-12 00:27:22 -03:00
|
|
|
void AP_Periph_FW::rcout_srv_PWM(uint8_t actuator_id, const float command_value)
|
|
|
|
{
|
|
|
|
#if HAL_PWM_COUNT > 0
|
|
|
|
const SRV_Channel::Aux_servo_function_t function = SRV_Channel::Aux_servo_function_t(SRV_Channel::k_rcin1 + actuator_id - 1);
|
|
|
|
SRV_Channels::set_output_pwm(function, uint16_t(command_value+0.5));
|
|
|
|
|
|
|
|
rcout_has_new_data_to_update = true;
|
2024-11-18 17:04:15 -04:00
|
|
|
#if AP_SIM_ENABLED
|
|
|
|
sim_update_actuator(actuator_id);
|
|
|
|
#endif
|
2022-09-12 00:27:22 -03:00
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
2020-12-12 05:08:45 -04:00
|
|
|
void AP_Periph_FW::rcout_handle_safety_state(uint8_t safety_state)
|
|
|
|
{
|
|
|
|
if (safety_state == 255) {
|
|
|
|
hal.rcout->force_safety_off();
|
|
|
|
} else {
|
|
|
|
hal.rcout->force_safety_on();
|
|
|
|
}
|
2020-12-29 01:06:44 -04:00
|
|
|
rcout_has_new_data_to_update = true;
|
2020-12-12 05:08:45 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
void AP_Periph_FW::rcout_update()
|
|
|
|
{
|
2022-11-28 00:45:59 -04:00
|
|
|
uint32_t now_ms = AP_HAL::millis();
|
2022-12-01 06:31:22 -04:00
|
|
|
|
|
|
|
const uint16_t esc_timeout_ms = g.esc_command_timeout_ms >= 0 ? g.esc_command_timeout_ms : 0; // Don't allow negative timeouts!
|
|
|
|
const bool has_esc_rawcommand_timed_out = esc_timeout_ms != 0 && ((now_ms - last_esc_raw_command_ms) >= esc_timeout_ms);
|
2022-11-28 00:45:59 -04:00
|
|
|
if (last_esc_num_channels > 0 && has_esc_rawcommand_timed_out) {
|
|
|
|
// If we've seen ESCs previously, and a timeout has occurred, then zero the outputs
|
2023-08-26 01:45:18 -03:00
|
|
|
int16_t esc_output[last_esc_num_channels];
|
|
|
|
memset(esc_output, 0, sizeof(esc_output));
|
2022-11-28 00:45:59 -04:00
|
|
|
rcout_esc(esc_output, last_esc_num_channels);
|
|
|
|
|
|
|
|
// register that the output has been changed
|
|
|
|
rcout_has_new_data_to_update = true;
|
|
|
|
}
|
|
|
|
|
2020-12-29 01:06:44 -04:00
|
|
|
if (!rcout_has_new_data_to_update) {
|
2020-12-12 05:08:45 -04:00
|
|
|
return;
|
|
|
|
}
|
2020-12-29 01:06:44 -04:00
|
|
|
rcout_has_new_data_to_update = false;
|
2020-12-12 05:08:45 -04:00
|
|
|
|
2024-11-12 17:10:00 -04:00
|
|
|
auto &srv = AP::srv();
|
2020-12-12 05:08:45 -04:00
|
|
|
SRV_Channels::calc_pwm();
|
2024-11-12 17:10:00 -04:00
|
|
|
srv.cork();
|
2020-12-12 05:08:45 -04:00
|
|
|
SRV_Channels::output_ch_all();
|
2024-11-12 17:10:00 -04:00
|
|
|
srv.push();
|
2021-12-06 22:47:50 -04:00
|
|
|
#if HAL_WITH_ESC_TELEM
|
2022-09-05 14:07:19 -03:00
|
|
|
if (now_ms - last_esc_telem_update_ms >= esc_telem_update_period_ms) {
|
2021-12-06 22:47:50 -04:00
|
|
|
last_esc_telem_update_ms = now_ms;
|
2021-12-08 19:52:38 -04:00
|
|
|
esc_telem_update();
|
2021-12-06 22:47:50 -04:00
|
|
|
}
|
2024-08-06 21:16:10 -03:00
|
|
|
#if AP_EXTENDED_ESC_TELEM_ENABLED
|
|
|
|
esc_telem_extended_update(now_ms);
|
|
|
|
#endif
|
2021-12-06 22:47:50 -04:00
|
|
|
#endif
|
2020-12-12 05:08:45 -04:00
|
|
|
}
|
|
|
|
|
2024-11-18 17:04:15 -04:00
|
|
|
#if AP_SIM_ENABLED
|
|
|
|
/*
|
|
|
|
update simulation of servos, sending actuator status
|
|
|
|
*/
|
|
|
|
void AP_Periph_FW::sim_update_actuator(uint8_t actuator_id)
|
|
|
|
{
|
|
|
|
sim_actuator.mask |= 1U << actuator_id;
|
|
|
|
|
|
|
|
// send status at 10Hz
|
|
|
|
const uint32_t period_ms = 100;
|
|
|
|
const uint32_t now_ms = AP_HAL::millis();
|
|
|
|
|
|
|
|
if (now_ms - sim_actuator.last_send_ms < period_ms) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
sim_actuator.last_send_ms = now_ms;
|
|
|
|
|
|
|
|
for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
|
|
|
|
if ((sim_actuator.mask & (1U<<i)) == 0) {
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
const SRV_Channel::Aux_servo_function_t function = SRV_Channel::Aux_servo_function_t(SRV_Channel::k_rcin1 + actuator_id - 1);
|
|
|
|
uavcan_equipment_actuator_Status pkt {};
|
|
|
|
pkt.actuator_id = i;
|
|
|
|
// assume 45 degree angle for simulation
|
|
|
|
pkt.position = radians(SRV_Channels::get_output_norm(function) * 45);
|
|
|
|
pkt.force = 0;
|
|
|
|
pkt.speed = 0;
|
|
|
|
pkt.power_rating_pct = UAVCAN_EQUIPMENT_ACTUATOR_STATUS_POWER_RATING_PCT_UNKNOWN;
|
|
|
|
|
|
|
|
uint8_t buffer[UAVCAN_EQUIPMENT_ACTUATOR_STATUS_MAX_SIZE];
|
|
|
|
uint16_t total_size = uavcan_equipment_actuator_Status_encode(&pkt, buffer, !canfdout());
|
|
|
|
|
|
|
|
canard_broadcast(UAVCAN_EQUIPMENT_ACTUATOR_STATUS_SIGNATURE,
|
|
|
|
UAVCAN_EQUIPMENT_ACTUATOR_STATUS_ID,
|
|
|
|
CANARD_TRANSFER_PRIORITY_LOW,
|
|
|
|
&buffer[0],
|
|
|
|
total_size);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif // AP_SIM_ENABLED
|
|
|
|
|
2020-12-12 05:08:45 -04:00
|
|
|
#endif // HAL_PERIPH_ENABLE_RC_OUT
|