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

Merged
merged 10 commits into from
Jan 13, 2025
Merged
32 changes: 16 additions & 16 deletions libraries/AP_DroneCAN/AP_DroneCAN.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1393,10 +1393,10 @@ void AP_DroneCAN::handle_actuator_status(const CanardRxTransfer& transfer, const
.force = msg.force,
.speed = msg.speed,
.duty_cycle = msg.power_rating_pct,
.valid_types = AP_Servo_Telem::TelemetryData::Types::MEASURED_POSITION |
AP_Servo_Telem::TelemetryData::Types::FORCE |
AP_Servo_Telem::TelemetryData::Types::SPEED |
AP_Servo_Telem::TelemetryData::Types::DUTY_CYCLE
.present_types = AP_Servo_Telem::TelemetryData::Types::MEASURED_POSITION |
AP_Servo_Telem::TelemetryData::Types::FORCE |
AP_Servo_Telem::TelemetryData::Types::SPEED |
AP_Servo_Telem::TelemetryData::Types::DUTY_CYCLE
};

servo_telem->update_telem_data(msg.actuator_id, telem_data);
Expand All @@ -1422,13 +1422,13 @@ void AP_DroneCAN::handle_himark_servoinfo(const CanardRxTransfer& transfer, cons
.motor_temperature_cdeg = int16_t(((msg.motor_temp * 0.2) - 40) * 100),
.pcb_temperature_cdeg = int16_t(((msg.pcb_temp * 0.2) - 40) * 100),
.status_flags = msg.error_status,
.valid_types = AP_Servo_Telem::TelemetryData::Types::COMMANDED_POSITION |
AP_Servo_Telem::TelemetryData::Types::MEASURED_POSITION |
AP_Servo_Telem::TelemetryData::Types::VOLTAGE |
AP_Servo_Telem::TelemetryData::Types::CURRENT |
AP_Servo_Telem::TelemetryData::Types::MOTOR_TEMP |
AP_Servo_Telem::TelemetryData::Types::PCB_TEMP |
AP_Servo_Telem::TelemetryData::Types::STATUS
.present_types = AP_Servo_Telem::TelemetryData::Types::COMMANDED_POSITION |
AP_Servo_Telem::TelemetryData::Types::MEASURED_POSITION |
AP_Servo_Telem::TelemetryData::Types::VOLTAGE |
AP_Servo_Telem::TelemetryData::Types::CURRENT |
AP_Servo_Telem::TelemetryData::Types::MOTOR_TEMP |
AP_Servo_Telem::TelemetryData::Types::PCB_TEMP |
AP_Servo_Telem::TelemetryData::Types::STATUS
};

servo_telem->update_telem_data(msg.servo_id, telem_data);
Expand All @@ -1449,11 +1449,11 @@ void AP_DroneCAN::handle_actuator_status_Volz(const CanardRxTransfer& transfer,
.current = msg.current * 0.025,
.duty_cycle = uint8_t(msg.motor_pwm * (100.0/255.0)),
.motor_temperature_cdeg = int16_t((msg.motor_temperature - 50) * 100),
.valid_types = AP_Servo_Telem::TelemetryData::Types::MEASURED_POSITION |
AP_Servo_Telem::TelemetryData::Types::VOLTAGE |
AP_Servo_Telem::TelemetryData::Types::CURRENT |
AP_Servo_Telem::TelemetryData::Types::DUTY_CYCLE |
AP_Servo_Telem::TelemetryData::Types::MOTOR_TEMP
.present_types = AP_Servo_Telem::TelemetryData::Types::MEASURED_POSITION |
AP_Servo_Telem::TelemetryData::Types::VOLTAGE |
AP_Servo_Telem::TelemetryData::Types::CURRENT |
AP_Servo_Telem::TelemetryData::Types::DUTY_CYCLE |
AP_Servo_Telem::TelemetryData::Types::MOTOR_TEMP
};

servo_telem->update_telem_data(msg.actuator_id, telem_data);
Expand Down
16 changes: 8 additions & 8 deletions libraries/AP_PiccoloCAN/AP_PiccoloCAN.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -380,14 +380,14 @@ void AP_PiccoloCAN::update()
.duty_cycle = servo.dutyCycle(),
.motor_temperature_cdeg = int16_t(servo.temperature() * 100),
.status_flags = err.errors,
.valid_types = AP_Servo_Telem::TelemetryData::Types::COMMANDED_POSITION |
AP_Servo_Telem::TelemetryData::Types::MEASURED_POSITION |
AP_Servo_Telem::TelemetryData::Types::SPEED |
AP_Servo_Telem::TelemetryData::Types::VOLTAGE |
AP_Servo_Telem::TelemetryData::Types::CURRENT |
AP_Servo_Telem::TelemetryData::Types::DUTY_CYCLE |
AP_Servo_Telem::TelemetryData::Types::MOTOR_TEMP |
AP_Servo_Telem::TelemetryData::Types::STATUS
.present_types = AP_Servo_Telem::TelemetryData::Types::COMMANDED_POSITION |
AP_Servo_Telem::TelemetryData::Types::MEASURED_POSITION |
AP_Servo_Telem::TelemetryData::Types::SPEED |
AP_Servo_Telem::TelemetryData::Types::VOLTAGE |
AP_Servo_Telem::TelemetryData::Types::CURRENT |
AP_Servo_Telem::TelemetryData::Types::DUTY_CYCLE |
AP_Servo_Telem::TelemetryData::Types::MOTOR_TEMP |
AP_Servo_Telem::TelemetryData::Types::STATUS
};

servo_telem->update_telem_data(ii, telem_data);
Expand Down
60 changes: 56 additions & 4 deletions libraries/AP_Scripting/docs/docs.lua
Original file line number Diff line number Diff line change
Expand Up @@ -1395,9 +1395,6 @@ function camera:take_picture(instance) end
---@class (exact) AP_Camera__camera_state_t_ud
local AP_Camera__camera_state_t_ud = {}

---@return AP_Camera__camera_state_t_ud
function AP_Camera__camera_state_t() end

IamPete1 marked this conversation as resolved.
Show resolved Hide resolved
-- get field
---@return Vector2f_ud
function AP_Camera__camera_state_t_ud:tracking_p1() end
Expand Down Expand Up @@ -4015,7 +4012,6 @@ function networking:get_netmask_active() end
function networking:get_ip_active() end

-- visual odometry object
--@class visual_odom
IamPete1 marked this conversation as resolved.
Show resolved Hide resolved
visual_odom = {}

-- visual odometry health
Expand All @@ -4025,3 +4021,59 @@ 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
servo_telem = {}

-- get servo telem for the given servo number
---@param servo_index integer -- 0 indexed servo number
---@return AP_Servo_Telem_Data_ud|nil
function servo_telem:get_telem(servo_index) end

-- Servo telemtry userdata object
---@class AP_Servo_Telem_Data_ud
local AP_Servo_Telem_Data_ud = {}

-- Get timestamp of last telem update
---@return uint32_t_ud -- milliseconds since boot
function AP_Servo_Telem_Data_ud:last_update_ms() end

-- Get type spesfic status flags
---@return integer|nil -- flags or nil if not available
function AP_Servo_Telem_Data_ud:status_flags() end

-- Get pcb temprature in centidegrees
---@return integer|nil -- temperature in centidegrees or nil if not available
function AP_Servo_Telem_Data_ud:pcb_temperature_cdeg() end

-- Get motor temprature in centidegrees
---@return integer|nil -- temperature in centidegrees or nil if not available
function AP_Servo_Telem_Data_ud:motor_temperature_cdeg() end

-- Get duty cycle
---@return integer|nil -- duty cycle 0% to 100% or nil if not available
function AP_Servo_Telem_Data_ud:duty_cycle() end

-- get current
---@return number|nil -- current in amps or nil if not available
function AP_Servo_Telem_Data_ud:current() end

-- get voltage
---@return number|nil -- voltage in volts or nil if not available
function AP_Servo_Telem_Data_ud:voltage() end

-- get speed
---@return number|nil -- speed in degrees per second or nil if not available
function AP_Servo_Telem_Data_ud:speed() end

-- get force
---@return number|nil -- force in newton meters or nil if not available
function AP_Servo_Telem_Data_ud:force() end

-- get measured position
---@return number|nil -- measured position in degrees or nil if not available
function AP_Servo_Telem_Data_ud:measured_position() end

-- get commanded position
---@return number|nil -- comanded position in degrees or nil if not available
function AP_Servo_Telem_Data_ud:command_position() end
20 changes: 20 additions & 0 deletions libraries/AP_Scripting/generator/description/bindings.desc
Original file line number Diff line number Diff line change
Expand Up @@ -1042,3 +1042,23 @@ 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_telem boolean uint8_t'skip_check AP_Servo_Telem::TelemetryData'Null

userdata AP_Servo_Telem::TelemetryData depends AP_SERVO_TELEM_ENABLED
userdata AP_Servo_Telem::TelemetryData rename AP_Servo_Telem_Data
userdata AP_Servo_Telem::TelemetryData field command_position float'skip_check read valid_mask present_types AP_Servo_Telem::TelemetryData::Types::COMMANDED_POSITION
userdata AP_Servo_Telem::TelemetryData field measured_position float'skip_check read valid_mask present_types AP_Servo_Telem::TelemetryData::Types::MEASURED_POSITION
userdata AP_Servo_Telem::TelemetryData field force float'skip_check read valid_mask present_types AP_Servo_Telem::TelemetryData::Types::FORCE
userdata AP_Servo_Telem::TelemetryData field speed float'skip_check read valid_mask present_types AP_Servo_Telem::TelemetryData::Types::SPEED
userdata AP_Servo_Telem::TelemetryData field voltage float'skip_check read valid_mask present_types AP_Servo_Telem::TelemetryData::Types::VOLTAGE
userdata AP_Servo_Telem::TelemetryData field current float'skip_check read valid_mask present_types AP_Servo_Telem::TelemetryData::Types::CURRENT
userdata AP_Servo_Telem::TelemetryData field duty_cycle uint8_t'skip_check read valid_mask present_types AP_Servo_Telem::TelemetryData::Types::DUTY_CYCLE
userdata AP_Servo_Telem::TelemetryData field motor_temperature_cdeg int16_t'skip_check read valid_mask present_types AP_Servo_Telem::TelemetryData::Types::MOTOR_TEMP
userdata AP_Servo_Telem::TelemetryData field pcb_temperature_cdeg int16_t'skip_check read valid_mask present_types AP_Servo_Telem::TelemetryData::Types::PCB_TEMP
userdata AP_Servo_Telem::TelemetryData field status_flags uint8_t'skip_check read valid_mask present_types AP_Servo_Telem::TelemetryData::Types::STATUS
userdata AP_Servo_Telem::TelemetryData field last_update_ms uint32_t'skip_check read
79 changes: 54 additions & 25 deletions libraries/AP_Scripting/generator/src/main.c
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,8 @@ char keyword_global[] = "global";
char keyword_creation[] = "creation";
char keyword_manual_operator[] = "manual_operator";
char keyword_operator_getter[] = "operator_getter";
char keyword_field_valid_mask[] = "valid_mask";


// attributes (should include the leading ' )
char keyword_attr_enum[] = "'enum";
Expand Down Expand Up @@ -184,6 +186,10 @@ struct type {
char *enum_name;
char *literal;
} data;
struct {
char *name;
char *value;
} valid_mask;
};

int TRACE_LEVEL = 0;
Expand Down Expand Up @@ -510,6 +516,11 @@ unsigned int parse_access_flags(struct type * type) {
error(ERROR_INTERNAL, "Can't access a NONE type");
}
}
} else if (strcmp(state.token, keyword_field_valid_mask) == 0) {
char * name = next_token();
string_copy(&(type->valid_mask.name), name);
char * value = next_token();
string_copy(&(type->valid_mask.value), value);
} else {
error(ERROR_UNKNOWN_KEYWORD, "Unknown access provided: %s", state.token);
break;
Expand Down Expand Up @@ -1290,6 +1301,24 @@ void end_dependency(FILE *f, const char *dependency) {
}
}

int should_emit_creation(struct userdata * data) {
if (data->creation || data->methods) {
// Custom creation or methods, if not specifically disabled
return !(data->creation && data->creation_args == -1);
} else {
// Don't expose creation function for items with only read-only fields
struct userdata_field * field = data->fields;
while(field) {
if (field->access_flags & ACCESS_FLAG_WRITE) {
return TRUE;
break;
}
field = field->next;
}
return FALSE;
}
}

void emit_headers(FILE *f) {
struct header *node = headers;
while (node) {
Expand All @@ -1314,7 +1343,7 @@ void emit_userdata_allocators(void) {
fprintf(source, "}\n");

// New method used externally, includes argcheck, overridden by custom creation function if provided
if (node->creation == NULL) {
if (node->creation == NULL && should_emit_creation(node)) {
fprintf(source, "\n");
fprintf(source, "int lua_new_%s(lua_State *L) {\n", node->sanatized_name);

Expand Down Expand Up @@ -1399,7 +1428,7 @@ void emit_userdata_declarations(void) {
while (node) {
start_dependency(header, node->dependency);
fprintf(header, "%s * new_%s(lua_State *L);\n", node->name, node->sanatized_name);
if (node->creation == NULL) {
if (node->creation == NULL && should_emit_creation(node)) {
fprintf(header, "int lua_new_%s(lua_State *L);\n", node->sanatized_name);
}
fprintf(header, "%s * check_%s(lua_State *L, int arg);\n", node->name, node->sanatized_name);
Expand Down Expand Up @@ -1716,10 +1745,20 @@ void emit_field(const struct userdata_field *field, const char* object_name, con
fprintf(source, " binding_argcheck(L, %d);\n",args);
}

int valid_mask = (field->type.valid_mask.name != NULL) && (field->type.valid_mask.value != NULL);

if (field->access_flags & ACCESS_FLAG_READ) {
if (use_switch) {
fprintf(source, " case 1:\n");
}

// Check if field is valid
if (valid_mask) {
fprintf(source, "%sif ((%s%s%s & %s) == 0) {\n", indent, object_name, object_access, field->type.valid_mask.name, field->type.valid_mask.value);
fprintf(source, "%s return 0;\n", indent);
fprintf(source, "%s}\n", indent);
}

switch (field->type.type) {
case TYPE_BOOLEAN:
fprintf(source, "%slua_pushinteger(L, %s%s%s%s);\n", indent, object_name, object_access, field->name, index_string);
Expand Down Expand Up @@ -1764,6 +1803,12 @@ void emit_field(const struct userdata_field *field, const char* object_name, con
fprintf(source, " case 2: {\n");
}
emit_checker(field->type, write_arg_number, 0, indent);

// set field valid
if (valid_mask) {
fprintf(source, "%s%s%s%s |= %s;\n", indent, object_name, object_access, field->type.valid_mask.name, field->type.valid_mask.value);
}

fprintf(source, "%s%s%s%s%s = data_%i;\n", indent, object_name, object_access, field->name, index_string, write_arg_number);
fprintf(source, "%sreturn 0;\n", indent);
if (use_switch) {
Expand Down Expand Up @@ -2585,24 +2630,7 @@ void emit_userdata_new_funcs(void) {
fprintf(source, " const lua_CFunction fun;\n");
fprintf(source, "} new_userdata[] = {\n");
while (data) {
// Dont expose creation function for all read only items
int expose_creation = FALSE;
if (data->creation || data->methods) {
// Custom creation or methods, if not specifically disabled
expose_creation = !(data->creation && data->creation_args == -1);
} else {
// Feilds only
struct userdata_field * field = data->fields;
while(field) {
if (field->access_flags & ACCESS_FLAG_WRITE) {
expose_creation = TRUE;
break;
}
field = field->next;
}
}

if (expose_creation) {
if (should_emit_creation(data)) {
start_dependency(source, data->dependency);
if (data->creation) {
// expose custom creation function to user (not used internally)
Expand Down Expand Up @@ -2888,8 +2916,7 @@ void emit_docs(struct userdata *node, int is_userdata, int emit_creation) {
// local userdata
fprintf(docs, "local %s = {}\n\n", name);

int creation_disabled = (node->creation && node->creation_args == -1);
if (emit_creation && (!node->creation || !creation_disabled)) {
if (emit_creation && should_emit_creation(node)) {
// creation function
if (node->creation != NULL) {
for (int i = 0; i < node->creation_args; ++i) {
Expand All @@ -2910,7 +2937,6 @@ void emit_docs(struct userdata *node, int is_userdata, int emit_creation) {
}
fprintf(docs, ") end\n\n");
}

}
} else {
// global
Expand All @@ -2922,11 +2948,14 @@ void emit_docs(struct userdata *node, int is_userdata, int emit_creation) {
if (node->fields != NULL) {
struct userdata_field *field = node->fields;
while(field) {
int valid_mask = (field->type.valid_mask.name != NULL) && (field->type.valid_mask.value != NULL);
const char * return_postfix = valid_mask ? "|nil\n" : "\n";

if (field->array_len == NULL) {
// single value field
if (field->access_flags & ACCESS_FLAG_READ) {
fprintf(docs, "-- get field\n");
emit_docs_type(field->type, "---@return", "\n");
emit_docs_type(field->type, "---@return", return_postfix);
fprintf(docs, "function %s:%s() end\n\n", name, field->rename ? field->rename : field->name);
}
if (field->access_flags & ACCESS_FLAG_WRITE) {
Expand All @@ -2939,7 +2968,7 @@ void emit_docs(struct userdata *node, int is_userdata, int emit_creation) {
if (field->access_flags & ACCESS_FLAG_READ) {
fprintf(docs, "-- get array field\n");
fprintf(docs, "---@param index integer\n");
emit_docs_type(field->type, "---@return", "\n");
emit_docs_type(field->type, "---@return", return_postfix);
fprintf(docs, "function %s:%s(index) end\n\n", name, field->rename ? field->rename : field->name);
}
if (field->access_flags & ACCESS_FLAG_WRITE) {
Expand Down
Loading
Loading