Path: blob/master/Tools/AP_Periph/actuator_telem.cpp
9424 views
/*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*/1415#include "AP_Periph.h"1617#if AP_PERIPH_ACTUATOR_TELEM_ENABLED1819#include <dronecan_msgs.h>2021extern const AP_HAL::HAL &hal;2223#ifndef AP_PERIPH_ACTUATOR_TELEM_RATE_DEFAULT24#define AP_PERIPH_ACTUATOR_TELEM_RATE_DEFAULT 1025#endif2627#ifndef AP_PERIPH_ACTUATOR_TELEM_NUM_CHANNELS_DEFAULT28#define AP_PERIPH_ACTUATOR_TELEM_NUM_CHANNELS_DEFAULT 029#endif3031#ifndef AP_PERIPH_ACTUATOR_TELEM_CURR_PIN_DEFAULT32#define AP_PERIPH_ACTUATOR_TELEM_CURR_PIN_DEFAULT -133#endif3435#ifndef AP_PERIPH_ACTUATOR_TELEM_CURR_AMP_OFFSET_DEFAULT36#define AP_PERIPH_ACTUATOR_TELEM_CURR_AMP_OFFSET_DEFAULT 0.0f37#endif3839#ifndef AP_PERIPH_ACTUATOR_TELEM_CURR_AMP_PERVLT_DEFAULT40#define AP_PERIPH_ACTUATOR_TELEM_CURR_AMP_PERVLT_DEFAULT 1041#endif4243#ifndef AP_PERIPH_ACTUATOR_TELEM_CURR_MAX_DEFAULT44#define AP_PERIPH_ACTUATOR_TELEM_CURR_MAX_DEFAULT 2.5f45#endif4647const AP_Param::GroupInfo ActuatorTelem::var_info[] = {48// @Param: _TELEM_RATE49// @DisplayName: Actuator Telemetry rate50// @Description: Actuator Telemetry update rate in Hz. Set to 0 to disable.51// @Units: Hz52// @Range: 0 10053// @User: Standard54AP_GROUPINFO("_TELEM_RATE", 1, ActuatorTelem, rate, AP_PERIPH_ACTUATOR_TELEM_RATE_DEFAULT),5556// @Param: _NUM_CHANS57// @DisplayName: Number of actuator channels58// @Description: Number of actuator channels to monitor for telemetry.59// @Range: 0 460// @User: Standard61AP_GROUPINFO("_NUM_CHANS", 2, ActuatorTelem, num_chans, AP_PERIPH_ACTUATOR_TELEM_NUM_CHANNELS_DEFAULT),6263// @Param: _CURR_PIN164// @DisplayName: Current sensing pin 165// @Description: Analog input pin number for current sensing on channel 1. Set to -1 to disable.66// @Values: -1:Disabled67// @Range: -1 12768// @User: Standard69// @RebootRequired: True70AP_GROUPINFO("_CURR_PIN1", 3, ActuatorTelem, curr_pin1, AP_PERIPH_ACTUATOR_TELEM_CURR_PIN_DEFAULT),7172// @Param: _AMP_OFFSET73// @DisplayName: Current sensor offset74// @Description: Voltage offset at zero current on the current sensor.75// @Units: V76// @User: Standard77AP_GROUPINFO("AMP_OFFSET", 4, ActuatorTelem, curr_amp_offset, AP_PERIPH_ACTUATOR_TELEM_CURR_AMP_OFFSET_DEFAULT),7879// @Param: _AMP_PERVLT80// @DisplayName: Amps per volt81// @Description: Current sensor scale factor.82// @Units: A/V83// @User: Standard84AP_GROUPINFO("AMP_PERVLT", 5, ActuatorTelem, curr_amp_per_volt, AP_PERIPH_ACTUATOR_TELEM_CURR_AMP_PERVLT_DEFAULT),8586// @Param: _CURR_MAX87// @DisplayName: Maximum current88// @Description: Maximum expected current for this channel.89// @Units: A90// @User: Standard91AP_GROUPINFO("CURR_MAX", 6, ActuatorTelem, curr_max, AP_PERIPH_ACTUATOR_TELEM_CURR_MAX_DEFAULT),9293AP_GROUPEND94};9596ActuatorTelem::ActuatorTelem(void)97{98AP_Param::setup_object_defaults(this, var_info);99for (uint8_t i = 0; i < HAL_ACTUATOR_TELEM_CURR_MAX_CHANNELS; i++) {100analog_sources[i] = nullptr;101}102}103104void ActuatorTelem::init(void)105{106const int8_t curr_pin1_val = curr_pin1.get();107const int8_t num_chans_val = num_chans.get();108109if (curr_pin1_val >= 0 && num_chans_val > 0) {110for (uint8_t i = 0; i < MIN(HAL_ACTUATOR_TELEM_CURR_MAX_CHANNELS, num_chans_val); i++) {111const int8_t pin = curr_pin1_val + i;112if (pin >= 0) {113analog_sources[i] = hal.analogin->channel(pin);114}115}116}117}118119void ActuatorTelem::send_telemetry(uint8_t channel_index, uint8_t actuator_id)120{121// Check if this channel is enabled122if (channel_index >= HAL_ACTUATOR_TELEM_CURR_MAX_CHANNELS) {123return;124}125126AP_HAL::AnalogSource *source = analog_sources[channel_index];127if (source == nullptr) {128return;129}130// Read current from analog input131float current_amp = 0;132float adc_voltage = source->voltage_average();133current_amp = (adc_voltage - curr_amp_offset) * curr_amp_per_volt;134135uavcan_equipment_actuator_Status pkt {};136137pkt.actuator_id = actuator_id;138pkt.position = nanf(""); // Not available139pkt.force = nanf(""); // Not available140pkt.speed = nanf(""); // Not available141142// Calculate power rating percentage from current143const float max_current = curr_max.get();144if (max_current > 0 && current_amp >= 0) {145pkt.power_rating_pct = constrain_int16(current_amp / max_current * 100.0f, 0, 100);146} else {147pkt.power_rating_pct = UAVCAN_EQUIPMENT_ACTUATOR_STATUS_POWER_RATING_PCT_UNKNOWN;148}149150// encode and broadcast151uint8_t buffer[UAVCAN_EQUIPMENT_ACTUATOR_STATUS_MAX_SIZE];152uint16_t total_size = uavcan_equipment_actuator_Status_encode(&pkt, buffer, !periph.canfdout());153154periph.canard_broadcast(UAVCAN_EQUIPMENT_ACTUATOR_STATUS_SIGNATURE,155UAVCAN_EQUIPMENT_ACTUATOR_STATUS_ID,156CANARD_TRANSFER_PRIORITY_LOW,157&buffer[0],158total_size);159}160161void ActuatorTelem::update()162{163// Check global telemetry rate164const float telem_rate = rate.get();165if (telem_rate <= 0) {166return; // telemetry disabled167}168169const uint32_t now = AP_HAL::millis();170if (now - last_telem_update_ms < 1000.0f / telem_rate) {171return;172}173last_telem_update_ms = now;174175#if HAL_PWM_COUNT > 0176const int8_t num_chans_val = num_chans.get();177if (num_chans_val > 0) {178for (uint8_t i = 0; i < MIN(HAL_PWM_COUNT, num_chans_val); i++) {179const auto *srv_channel = periph.servo_channels.srv_channel(i);180if (srv_channel == nullptr) {181continue;182}183184const SRV_Channel::Function function = srv_channel->get_function();185// Only send for configured actuator functions186if (function < SRV_Channel::k_rcin1 || function > SRV_Channel::k_rcin16) {187continue;188}189190const uint8_t actuator_id = function - SRV_Channel::k_rcin1 + 1;191192send_telemetry(i, actuator_id);193}194}195#endif196}197198#endif // AP_PERIPH_ACTUATOR_TELEM_ENABLED199200201