diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index 4e15c6d33d0330..eb0de777e9c22d 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -2892,6 +2892,11 @@ gcs = {} ---@param value number -- value to send function gcs:send_named_float(name, value) end +-- send named integer value using NAMED_VALUE_INT message +---@param name string -- up to 10 chars long +---@param value integer -- value to send +function gcs:send_named_int(name, value) end + -- set message interval for a given serial port and message id ---@param port_num integer -- serial port number ---@param msg_id uint32_t_ud|integer|number -- MAVLink message id diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index 3772ca51c07541..2794f2366e9e48 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -289,6 +289,7 @@ singleton GCS rename gcs singleton GCS method send_text void MAV_SEVERITY'enum MAV_SEVERITY_EMERGENCY MAV_SEVERITY_DEBUG "%s"'literal string singleton GCS method set_message_interval MAV_RESULT'enum uint8_t 0 MAVLINK_COMM_NUM_BUFFERS uint32_t'skip_check int32_t -1 INT32_MAX singleton GCS method send_named_float void string float'skip_check +singleton GCS method send_named_int void string int32_t'skip_check singleton GCS method frame_type MAV_TYPE'enum singleton GCS method get_hud_throttle int16_t singleton GCS method sysid_myggcs_last_seen_time_ms uint32_t diff --git a/libraries/GCS_MAVLink/GCS.cpp b/libraries/GCS_MAVLink/GCS.cpp index c4a11f666d55da..19015a8f194d01 100644 --- a/libraries/GCS_MAVLink/GCS.cpp +++ b/libraries/GCS_MAVLink/GCS.cpp @@ -121,6 +121,17 @@ void GCS::send_named_float(const char *name, float value) const (const char *)&packet); } +void GCS::send_named_int(const char *name, int32_t value) const +{ + mavlink_named_value_int_t packet {}; + packet.time_boot_ms = AP_HAL::millis(); + packet.value = value; + memcpy(packet.name, name, MIN(strlen(name), (uint8_t)MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN)); + + gcs().send_to_active_channels(MAVLINK_MSG_ID_NAMED_VALUE_INT, + (const char *)&packet); +} + #if HAL_HIGH_LATENCY2_ENABLED void GCS::enable_high_latency_connections(bool enabled) { diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index aa67f61e8ceddc..82406da66526ed 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -388,6 +388,7 @@ class GCS_MAVLINK void send_gimbal_manager_information() const; void send_gimbal_manager_status() const; void send_named_float(const char *name, float value) const; + void send_named_int(const char *name, int32_t value) const; void send_home_position() const; void send_gps_global_origin() const; virtual void send_attitude_target() {}; @@ -1215,6 +1216,7 @@ class GCS void send_message(enum ap_message id); void send_mission_item_reached_message(uint16_t mission_index); void send_named_float(const char *name, float value) const; + void send_named_int(const char *name, int32_t value) const; void send_parameter_value(const char *param_name, ap_var_type param_type, diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 83eb282ac0274f..bceab90f558351 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -3024,6 +3024,13 @@ void GCS_MAVLINK::send_named_float(const char *name, float value) const mavlink_msg_named_value_float_send(chan, AP_HAL::millis(), float_name, value); } +void GCS_MAVLINK::send_named_int(const char *name, int32_t value) const +{ + char int_name[MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN+1] {}; + strncpy(int_name, name, MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN); + mavlink_msg_named_value_int_send(chan, AP_HAL::millis(), int_name, value); +} + #if AP_AHRS_ENABLED void GCS_MAVLINK::send_home_position() const {