Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Scripting: add bindings for servo telemetry #28857

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
56 changes: 55 additions & 1 deletion libraries/AP_Scripting/docs/docs.lua
Original file line number Diff line number Diff line change
Expand Up @@ -4003,7 +4003,6 @@ function networking:get_netmask_active() end
function networking:get_ip_active() end

-- visual odometry object
--@class visual_odom
visual_odom = {}

-- visual odometry health
Expand All @@ -4013,3 +4012,58 @@ function visual_odom:healthy() end
-- visual odometry quality as a percentage from 1 to 100 or 0 if unknown
---@return integer
function visual_odom:quality() end


-- servo telemetry class
---@class servo_telem
servo_telem = {}

-- Get the type spesfic status flags for the given servo number
---@param servo_index integer -- 0 indexed servo number
---@return integer|nil -- status flags or nil if not available
function servo_telem:get_status_flags(servo_index) end

-- Get the pcb temprature for the given servo number
---@param servo_index integer -- 0 indexed servo number
---@return number|nil -- pcb temprature in degrees C or nil if not available
function servo_telem:get_pcb_temperature(servo_index) end

-- Get motor temprature for the given servo number
---@param servo_index integer
---@return number|nil -- motor temprature in degrees C or nil if not available
function servo_telem:get_motor_temperature(servo_index) end

-- Get the duty cycle for the given servo number
---@param servo_index integer -- 0 indexed servo number
---@return integer|nil -- duty cycle 0% to 100% or nil if not available
function servo_telem:get_duty_cycle(servo_index) end

-- Get the current for the given servo number
---@param servo_index integer -- 0 indexed servo number
---@return number|nil -- current in amps or nil if not available
function servo_telem:get_current(servo_index) end

-- Get the voltage for the given servo number
---@param servo_index integer -- 0 indexed servo number
---@return number|nil -- voltage in volts or nil if not available
function servo_telem:get_voltage(servo_index) end

-- Get the speed for the given servo number
---@param servo_index integer -- 0 indexed servo number
---@return number|nil -- speed in degrees per second or nil if not available
function servo_telem:get_speed(servo_index) end

-- Get the force for the given servo number
---@param servo_index integer -- 0 indexed servo number
---@return number|nil -- force in newton meters or nil if not available
function servo_telem:get_force(servo_index) end

-- Get the measured position for the given servo number
---@param servo_index integer -- 0 indexed servo number
---@return number|nil -- measured position in degrees or nil if not available
function servo_telem:get_measured_position(servo_index) end

-- Get the commanded position for the given servo number
---@param servo_index integer -- 0 indexed servo number
---@return number|nil -- comanded position in degrees or nil if not available
function servo_telem:get_commanded_position(servo_index) end
16 changes: 16 additions & 0 deletions libraries/AP_Scripting/generator/description/bindings.desc
Original file line number Diff line number Diff line change
Expand Up @@ -1039,3 +1039,19 @@ include AP_TemperatureSensor/AP_TemperatureSensor.h
singleton AP_TemperatureSensor depends AP_TEMPERATURE_SENSOR_ENABLED
singleton AP_TemperatureSensor rename temperature_sensor
singleton AP_TemperatureSensor method get_temperature boolean float'Null uint8_t'skip_check


include AP_Servo_Telem/AP_Servo_Telem.h depends AP_SERVO_TELEM_ENABLED
include AP_Servo_Telem/AP_Servo_Telem_config.h
singleton AP_Servo_Telem depends AP_SERVO_TELEM_ENABLED
singleton AP_Servo_Telem rename servo_telem
singleton AP_Servo_Telem method get_commanded_position boolean uint8_t'skip_check float'Null
singleton AP_Servo_Telem method get_measured_position boolean uint8_t'skip_check float'Null
singleton AP_Servo_Telem method get_force boolean uint8_t'skip_check float'Null
singleton AP_Servo_Telem method get_speed boolean uint8_t'skip_check float'Null
singleton AP_Servo_Telem method get_voltage boolean uint8_t'skip_check float'Null
singleton AP_Servo_Telem method get_current boolean uint8_t'skip_check float'Null
singleton AP_Servo_Telem method get_duty_cycle boolean uint8_t'skip_check uint8_t'Null
singleton AP_Servo_Telem method get_motor_temperature boolean uint8_t'skip_check float'Null
singleton AP_Servo_Telem method get_pcb_temperature boolean uint8_t'skip_check float'Null
singleton AP_Servo_Telem method get_status_flags boolean uint8_t'skip_check uint8_t'Null
125 changes: 125 additions & 0 deletions libraries/AP_Servo_Telem/AP_Servo_Telem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,6 +100,131 @@ void AP_Servo_Telem::update_telem_data(const uint8_t servo_index, const Telemetr
telemdata.last_update_ms = AP_HAL::millis();
}

// Return the commanded position servo position in degrees if available
bool AP_Servo_Telem::get_commanded_position(const uint8_t servo_index, float &command_position) const
{
if (!data_available(servo_index, TelemetryData::Types::COMMANDED_POSITION)) {
return false;
}

command_position = _telem_data[servo_index].command_position;
return true;
}

// Return the measured Servo position in degrees if available
bool AP_Servo_Telem::get_measured_position(const uint8_t servo_index, float &measured_position) const
{
if (!data_available(servo_index, TelemetryData::Types::MEASURED_POSITION)) {
return false;
}

measured_position = _telem_data[servo_index].measured_position;
return true;
}

// Return the force in newton meters if available
bool AP_Servo_Telem::get_force(const uint8_t servo_index, float &force) const
{
if (!data_available(servo_index, TelemetryData::Types::FORCE)) {
return false;
}

force = _telem_data[servo_index].force;
return true;
}

// Return the speed in degrees per second if available
bool AP_Servo_Telem::get_speed(const uint8_t servo_index, float &speed) const
{
if (!data_available(servo_index, TelemetryData::Types::SPEED)) {
return false;
}

speed = _telem_data[servo_index].speed;
return true;
}

// Return the voltage in volts per second if available
bool AP_Servo_Telem::get_voltage(const uint8_t servo_index, float &voltage) const
{
if (!data_available(servo_index, TelemetryData::Types::VOLTAGE)) {
return false;
}

voltage = _telem_data[servo_index].voltage;
return true;
}

// Return the current in amps per second if available
bool AP_Servo_Telem::get_current(const uint8_t servo_index, float &current) const
{
if (!data_available(servo_index, TelemetryData::Types::CURRENT)) {
return false;
}

current = _telem_data[servo_index].current;
return true;
}


// Return the duty cycle 0% to 100% if available
bool AP_Servo_Telem::get_duty_cycle(const uint8_t servo_index, uint8_t &duty_cycle) const
{
if (!data_available(servo_index, TelemetryData::Types::DUTY_CYCLE)) {
return false;
}

duty_cycle = _telem_data[servo_index].duty_cycle;
return true;
}

// Return the motor temperature in degrees C if available
bool AP_Servo_Telem::get_motor_temperature(const uint8_t servo_index, float &motor_temperature) const
{
if (!data_available(servo_index, TelemetryData::Types::MOTOR_TEMP)) {
return false;
}

motor_temperature = _telem_data[servo_index].motor_temperature_cdeg * 0.01;
return true;
}

// Return the pcb temperature in degrees C if available
bool AP_Servo_Telem::get_pcb_temperature(const uint8_t servo_index, float &pcb_temperature) const
{
if (!data_available(servo_index, TelemetryData::Types::PCB_TEMP)) {
return false;
}

pcb_temperature = _telem_data[servo_index].pcb_temperature_cdeg * 0.01;
return true;
}

// Return type specific status flags if available
bool AP_Servo_Telem::get_status_flags(const uint8_t servo_index, uint8_t &status_flags) const
{
if (!data_available(servo_index, TelemetryData::Types::STATUS)) {
return false;
}

status_flags = _telem_data[servo_index].status_flags;
return true;
}

// Helper to check index and if data is available
bool AP_Servo_Telem::data_available(const uint8_t servo_index, const TelemetryData::Types type) const
{
if (servo_index >= SERVO_TELEM_MAX_SERVOS) {
return false;
}

if (!_telem_data[servo_index].valid(type)) {
return false;
}

return true;
}

void AP_Servo_Telem::update()
{
#if HAL_LOGGING_ENABLED
Expand Down
35 changes: 35 additions & 0 deletions libraries/AP_Servo_Telem/AP_Servo_Telem.h
Original file line number Diff line number Diff line change
Expand Up @@ -70,8 +70,43 @@ class AP_Servo_Telem {
// callback to update the data in the frontend, should be called by the driver when new data is available
void update_telem_data(const uint8_t servo_index, const TelemetryData& new_data);

// Getters for telem values

// Return the commanded position servo position in degrees if available
bool get_commanded_position(const uint8_t servo_index, float &command_position) const;

// Return the measured Servo position in degrees if available
bool get_measured_position(const uint8_t servo_index, float &measured_position) const;

// Return the force in newton meters if available
bool get_force(const uint8_t servo_index, float &force) const;

// Return the speed in degrees per second if available
bool get_speed(const uint8_t servo_index, float &speed) const;

// Return the voltage in volts per second if available
bool get_voltage(const uint8_t servo_index, float &voltage) const;

// Return the current in amps per second if available
bool get_current(const uint8_t servo_index, float &current) const;

// Return the duty cycle 0% to 100% if available
bool get_duty_cycle(const uint8_t servo_index, uint8_t &duty_cycle) const;

// Return the motor temperature in degrees C if available
bool get_motor_temperature(const uint8_t servo_index, float &motor_temperature) const;

// Return the pcb temperature in degrees C if available
bool get_pcb_temperature(const uint8_t servo_index, float &pcb_temperature) const;

// Return type specific status flags if available
bool get_status_flags(const uint8_t servo_index, uint8_t &status_flags) const;

private:

// Helper to check index and if data is available
bool data_available(const uint8_t servo_index, const TelemetryData::Types type) const;

// Log telem of each servo
void write_log();

Expand Down
Loading