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

Scripted CRSF Menus #29368

Merged
merged 19 commits into from
Apr 9, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
19 commits
Select commit Hold shift + click to select a range
4b1b26c
AP_Scripting: add CRSF menu bindings
andyp1per Dec 28, 2024
17b2887
AP_RCTelemetry: add initial CRSF scripting menu options
andyp1per Dec 28, 2024
e991a9c
AP_RCProtocol: better CRSF telemetry debug
andyp1per Feb 21, 2025
3459f5d
AP_RCTelemetry: compile when no scripting
andyp1per Feb 24, 2025
1219fea
AP_Scripting: enable compilation when no CRSF scripting
andyp1per Feb 24, 2025
d7faa8a
AP_Scripting: protect CRSF scripting when there is no scripting
andyp1per Feb 24, 2025
6dcb4a8
AP_Scripting: update crsf menu docs
andyp1per Feb 27, 2025
f7eca54
AP_RCTelemetry: use correct new in CRSF
andyp1per Feb 28, 2025
d2d456c
AP_Scripting: update CRSF bindings
andyp1per Feb 28, 2025
c662ad8
AP_RCTelemetry: rename AP_CRSF_SCRIPTING_ENABLED and address review c…
andyp1per Mar 17, 2025
f2a682f
AP_Scripting: rename AP_CRSF_SCRIPTING_ENABLED
andyp1per Mar 17, 2025
0c43efa
scripts: add AP_CRSF_SCRIPTING_ENABLED to build options
andyp1per Mar 17, 2025
debd7a7
AP_CRSF_Telem: shut up gcc
andyp1per Mar 17, 2025
6bfe670
scripts: add AP_CRSF_SCRIPTING_ENABLED to extract features
andyp1per Mar 17, 2025
fc67f5b
AP_Scripting: AP calibration menu
andyp1per Apr 2, 2025
a0366cf
AP_RCProtocol: add parameter specific debug to CRSF
andyp1per Apr 3, 2025
d0ce50a
AP_Scripting: add CRSF docs and lua wrapper fixes
andyp1per Apr 3, 2025
d7f2fe6
AP_RCProtocol: remove CRSF 11-bit variable frame support since undocu…
andyp1per Apr 3, 2025
5595354
AP_RCTelemetry: check for allocation failure in CRSF scripting
andyp1per Apr 3, 2025
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
1 change: 1 addition & 0 deletions Tools/scripts/build_options.py
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,7 @@ def config_option(self):

Feature('Telemetry', 'CRSF', 'HAL_CRSF_TELEM_ENABLED', 'Enable CRSF telemetry', 0, 'FrSky SPort PassThrough,FrSky,FrSky SPort,RC_CRSF'), # noqa
Feature('Telemetry', 'CRSFText', 'HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED', 'Enable CRSF text param selection', 0, 'CRSF,OSD_PARAM,FrSky SPort PassThrough,FrSky,FrSky SPort'), # NOQA: E501
Feature('Telemetry', 'CRSF Scripting', 'AP_CRSF_SCRIPTING_ENABLED', 'Enable CRSF Menu Scripting', 0, 'CRSFText,CRSF,OSD_PARAM,FrSky SPort PassThrough,FrSky,FrSky SPort'), # noqa
Feature('Telemetry', 'HOTT', 'HAL_HOTT_TELEM_ENABLED', 'Enable HOTT telemetry', 0, None),
Feature('Telemetry', 'SPEKTRUM', 'HAL_SPEKTRUM_TELEM_ENABLED', 'Enable Spektrum telemetry', 0, None),
Feature('Telemetry', 'LTM', 'AP_LTM_TELEM_ENABLED', 'Enable LTM telemetry', 0, None),
Expand Down
1 change: 1 addition & 0 deletions Tools/scripts/extract_features.py
Original file line number Diff line number Diff line change
Expand Up @@ -121,6 +121,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"):
('HAL_{type}_TELEM_ENABLED', r'AP_(?P<type>.*)_Telem::init',),
('AP_{type}_TELEM_ENABLED', r'AP_(?P<type>.*)_Telem::init',),
('HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED', 'AP_CRSF_Telem::calc_text_selection',),
('AP_CRSF_SCRIPTING_ENABLED', 'AP_CRSF_Telem::get_menu_event',),
('AP_LTM_TELEM_ENABLED', 'AP_LTM_Telem::init',),
('HAL_HIGH_LATENCY2_ENABLED', 'GCS_MAVLINK::handle_control_high_latency',),

Expand Down
63 changes: 50 additions & 13 deletions libraries/AP_RCProtocol/AP_RCProtocol_CRSF.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,9 @@ extern const AP_HAL::HAL& hal;

//#define CRSF_DEBUG
//#define CRSF_DEBUG_CHARS
#ifdef CRSF_DEBUG
//#define CRSF_DEBUG_TELEM
//#define CRSF_DEBUG_PARAMS
#if defined(CRSF_DEBUG) || defined(CRSF_DEBUG_TELEM) || defined(CRSF_DEBUG_PARAMS)
# define debug(fmt, args...) hal.console->printf("CRSF: " fmt "\n", ##args)
static const char* get_frame_type(uint8_t byte, uint8_t subtype = 0)
{
Expand Down Expand Up @@ -127,7 +129,7 @@ static const char* get_frame_type(uint8_t byte, uint8_t subtype = 0)
case AP_RCProtocol_CRSF::CRSF_FRAMETYPE_LINK_STATISTICS_TX:
return "LINK_STATSv3_TX";
case AP_RCProtocol_CRSF::CRSF_FRAMETYPE_PARAMETER_WRITE:
return "UNKNOWN";
return "PARAM_WRITE";
case AP_RCProtocol_CRSF::CRSF_FRAMETYPE_AP_CUSTOM_TELEM_LEGACY:
case AP_RCProtocol_CRSF::CRSF_FRAMETYPE_AP_CUSTOM_TELEM:
switch (subtype) {
Expand Down Expand Up @@ -397,22 +399,33 @@ void AP_RCProtocol_CRSF::write_frame(Frame* frame)
uart->write((uint8_t*)frame, frame->length + 2);
uart->flush();

#ifdef CRSF_DEBUG
hal.console->printf("CRSF: writing %s:", get_frame_type(frame->type, frame->payload[0]));
for (uint8_t i = 0; i < frame->length + 2; i++) {
uint8_t val = ((uint8_t*)frame)[i];
#if defined(CRSF_DEBUG) || defined(CRSF_DEBUG_PARAMS)
#ifdef CRSF_DEBUG_PARAMS
switch (frame->type) {
case CRSF_FRAMETYPE_PARAMETER_SETTINGS_ENTRY:
case CRSF_FRAMETYPE_PARAMETER_READ:
case CRSF_FRAMETYPE_PARAMETER_WRITE:
case CRSF_FRAMETYPE_COMMAND:
#endif

hal.console->printf("CRSF: writing %s:", get_frame_type(frame->type, frame->payload[0]));
for (uint8_t i = 0; i < frame->length + 2; i++) {
uint8_t val = ((uint8_t*)frame)[i];
#ifdef CRSF_DEBUG_CHARS
if (val >= 32 && val <= 126) {
hal.console->printf(" 0x%x '%c'", val, (char)val);
} else {
if (val >= 32 && val <= 126) {
hal.console->printf(" 0x%x '%c'", val, (char)val);
} else {
#endif
hal.console->printf(" 0x%x", val);
hal.console->printf(" 0x%x", val);
#ifdef CRSF_DEBUG_CHARS
}
}
#endif
}
hal.console->printf("\n");
#ifdef CRSF_DEBUG_PARAMS
}
hal.console->printf("\n");
#endif
#endif // defined(CRSF_DEBUG) || defined(CRSF_DEBUG_PARAMS)
}

bool AP_RCProtocol_CRSF::decode_crsf_packet()
Expand Down Expand Up @@ -461,7 +474,31 @@ bool AP_RCProtocol_CRSF::decode_crsf_packet()
break;
}
#if HAL_CRSF_TELEM_ENABLED
if (AP_CRSF_Telem::process_frame(FrameType(_frame.type), (uint8_t*)&_frame.payload)) {
if (AP_CRSF_Telem::process_frame(FrameType(_frame.type), (uint8_t*)&_frame.payload, _frame.length - 2U)) {
#if defined(CRSF_DEBUG_TELEM) || defined(CRSF_DEBUG_PARAMS)
switch (_frame.type) {
case CRSF_FRAMETYPE_RC_CHANNELS_PACKED:
case CRSF_FRAMETYPE_LINK_STATISTICS:
case CRSF_FRAMETYPE_SUBSET_RC_CHANNELS_PACKED:
case CRSF_FRAMETYPE_LINK_STATISTICS_RX:
case CRSF_FRAMETYPE_LINK_STATISTICS_TX:
break;
#ifdef CRSF_DEBUG_PARAMS
case CRSF_FRAMETYPE_PARAMETER_SETTINGS_ENTRY:
case CRSF_FRAMETYPE_PARAMETER_READ:
case CRSF_FRAMETYPE_PARAMETER_WRITE:
case CRSF_FRAMETYPE_COMMAND:
#else
default:
#endif
hal.console->printf("CRSF: received %s:", get_frame_type(_frame.type));
uint8_t* fptr = (uint8_t*)&_frame;
for (uint8_t i = 0; i < _frame.length + 2; i++) {
hal.console->printf(" 0x%x", fptr[i]);
}
hal.console->printf("\n");
}
#endif // defined(CRSF_DEBUG_TELEM) || defined(CRSF_DEBUG_PARAMS)
process_telemetry();
}
// process any pending baudrate changes before reading another frame
Expand Down
Loading
Loading