Compare commits

..

1 Commits

Author SHA1 Message Date
Alexander Lerach 9b55dc81ca bl_update: Allow booting from SD card (without forced BL copy to ROMFS) 2025-08-20 18:22:42 +02:00
334 changed files with 3557 additions and 7231 deletions
-5
View File
@@ -36,11 +36,6 @@ CONFIG:
buildType: RelWithDebInfo
settings:
CONFIG: px4_sitl_test
px4_sitl_zenoh:
short: px4_sitl_zenoh
buildType: RelWithDebInfo
settings:
CONFIG: px4_sitl_test
px4_io-v2_default:
short: px4_io-v2
buildType: MinSizeRel
+1 -1
View File
@@ -43,7 +43,7 @@
"files.watcherExclude": {
"**/build/**": true
},
"git.detectSubmodulesLimit": 25,
"git.detectSubmodulesLimit": 20,
"git.ignoreLimitWarning": true,
"githubPullRequests.defaultMergeMethod": "squash",
"githubPullRequests.telemetry.enabled": false,
-5
View File
@@ -73,11 +73,6 @@ menu "Toolchain"
help
relative path to the ROMFS root directory
config BOARD_ADDITIONAL_INIT
string "Additional init file"
help
additional configurable init file to include in the ROMFS
config BOARD_IO
string "IO board name"
default "px4_io-v2_default"
+1 -1
View File
@@ -19,7 +19,7 @@ See [the documentation on Maintainers](https://docs.px4.io/main/en/contribute/ma
| Matthias Grob | Multirotor | [@MaEtUgR](https://github.com/MaEtUgR) | maetugr |
| Silvan Fuhrer | Fixed-Wing / VTOL | [@sfuhrer](https://github.com/sfuhrer) | sfuhrer |
| Christian Friedrich | Rover | [@chfriedrich98](https://github.com/chfriedrich98) | christian982564 |
| Pedro Roque | Spacecraft | [@Pedro-Roque](https://github.com/Pedro-Roque) | .pedroroque | <roque@caltech.edu>
| Pedro Roque | Spacecraft | [@Pedro-Roque](https://github.com/Pedro-Roque) | .pedroroque | <padr@kth.se>
| Jacob Dahl | Simulation | [@dakejahl](https://github.com/dakejahl) | dakejahl | <dahl.jakejacob@gmail.com>
-1
View File
@@ -511,7 +511,6 @@ validate_module_configs:
@find "$(SRC_DIR)"/src/modules "$(SRC_DIR)"/src/drivers "$(SRC_DIR)"/src/lib -name *.yaml -type f \
-not -path "$(SRC_DIR)/src/lib/mixer_module/*" \
-not -path "$(SRC_DIR)/src/modules/uxrce_dds_client/dds_topics.yaml" \
-not -path "$(SRC_DIR)/src/modules/zenoh/dds_topics.yaml" \
-not -path "$(SRC_DIR)/src/modules/zenoh/zenoh-pico/*" \
-not -path "$(SRC_DIR)/src/lib/events/libevents/*" \
-not -path "$(SRC_DIR)/src/lib/cdrstream/*" \
+2 -27
View File
@@ -202,43 +202,18 @@ foreach(board_rc_file ${OPTIONAL_BOARD_RC})
endforeach()
if(config_additional_init)
if(EXISTS "${PX4_BOARD_DIR}/init/${config_additional_init}")
file(RELATIVE_PATH rc_file_relative ${PX4_SOURCE_DIR} ${PX4_BOARD_DIR}/init/${config_additional_init})
message(STATUS "ROMFS: Adding ${rc_file_relative} -> /etc/init.d/rc.additional_init")
add_custom_command(
OUTPUT
${romfs_gen_root_dir}/init.d/rc.additional_init
${config_additional_init}.stamp
COMMAND ${CMAKE_COMMAND} -E copy_if_different ${PX4_BOARD_DIR}/init/${config_additional_init} ${romfs_gen_root_dir}/init.d/rc.additional_init
COMMAND ${CMAKE_COMMAND} -E touch ${config_additional_init}.stamp
DEPENDS
${PX4_BOARD_DIR}/init/${config_additional_init}
romfs_copy.stamp
COMMENT "ROMFS: copying ${config_additional_init}"
)
list(APPEND extras_dependencies
${config_additional_init}.stamp
)
else()
message(FATAL_ERROR "BOARD_ADDITIONAL_INIT file not found at: ${PX4_BOARD_DIR}/init/${config_additional_init}")
endif()
endif()
# board extras
set(OPTIONAL_BOARD_EXTRAS)
file(GLOB OPTIONAL_BOARD_EXTRAS ${PX4_BOARD_DIR}/extras/*)
# bootloader (optional)
# - if systemcmds/bl_update included and board bootloader available then generate rc.board_bootloader_upgrade and copy bootloader binary
# - if systemcmds/bl_update included (with romfs copy) and board bootloader available then generate rc.board_bootloader_upgrade and copy bootloader binary
# - otherwise remove bootloader binary from extras in final ROMFS
foreach(board_extra_file ${OPTIONAL_BOARD_EXTRAS})
file(RELATIVE_PATH extra_file_base_name ${PX4_BOARD_DIR}/extras/ ${board_extra_file})
if(${extra_file_base_name} MATCHES "${PX4_BOARD_VENDOR}_${PX4_BOARD_MODEL}_bootloader.bin")
if(CONFIG_SYSTEMCMDS_BL_UPDATE)
if(CONFIG_SYSTEMCMDS_BL_UPDATE AND CONFIG_BL_UPDATE_BL_ROMFS)
# generate rc.board_bootloader_upgrade
set(BOARD_FIRMWARE_BIN "${PX4_BOARD_VENDOR}_${PX4_BOARD_MODEL}_bootloader.bin")
message(STATUS "ROMFS: Adding platforms/nuttx/init/rc.board_bootloader_upgrade -> /etc/init.d/rc.board_bootloader_upgrade")
-11
View File
@@ -56,17 +56,6 @@ then
fi
unset BOARD_RC_DEFAULTS
#
# Optional additional init file: rc.additional_init
#
set BOARD_RC_ADDITIONAL_INIT ${R}etc/init.d/rc.additional_init
if [ -f $BOARD_RC_ADDITIONAL_INIT ]
then
echo "Board additional init: ${BOARD_RC_ADDITIONAL_INIT}"
. $BOARD_RC_ADDITIONAL_INIT
fi
unset BOARD_RC_ADDITIONAL_INIT
#
# Start system state indicator.
#
@@ -34,6 +34,7 @@ param set-default COM_LOW_BAT_ACT 0
param set-default NAV_DLL_ACT 0
param set-default GF_ACTION 1
param set-default NAV_RCL_ACT 1
param set-default COM_POSCTL_NAVL 2
# disable attitude failure detection
param set-default FD_FAIL_P 0
@@ -1,21 +1,10 @@
#!/bin/sh
#
# @name KTH-ATMOS
# @name 3DoF Spacecraft Model
#
# @type Free-Flyer
# @class Spacecraft
# @type 2D Freeflyer with 8 thrusters - Planar motion
#
# @output Motor1 back left thruster, +x thrust
# @output Motor2 front left thruster, -x thrust
# @output Motor3 back right thruster, +x thrust
# @output Motor4 front right thruster, -x thrust
# @output Motor5 front left thruster, +y thrust
# @output Motor6 front right thruster, -y thrust
# @output Motor7 back left thruster, +y thrust
# @output Motor8 back right thruster, -y thrust
#
# @maintainer discower-io
# @url https://atmos.discower.io
# @maintainer Pedro Roque <padr@kth.se>
#
. ${R}etc/init.d/rc.sc_defaults
@@ -45,6 +34,7 @@ param set-default COM_LOW_BAT_ACT 0
param set-default NAV_DLL_ACT 0
param set-default GF_ACTION 1
param set-default NAV_RCL_ACT 1
param set-default COM_POSCTL_NAVL 2
# disable attitude failure detection
param set-default FD_FAIL_P 0
-5
View File
@@ -324,11 +324,6 @@ fi
uxrce_dds_client start -t udp -p $uxrce_dds_port $uxrce_dds_ns
if param greater -s ZENOH_ENABLE 0
then
zenoh start
fi
if param greater -s MNT_MODE_IN -1
then
gimbal start
@@ -45,6 +45,7 @@ param set-default COM_LOW_BAT_ACT 0
param set-default NAV_DLL_ACT 0
param set-default GF_ACTION 1
param set-default NAV_RCL_ACT 1
param set-default COM_POSCTL_NAVL 2
# disable attitude failure detection
param set-default FD_FAIL_P 0
@@ -5,17 +5,7 @@
# @type Free-Flyer
# @class Spacecraft
#
# @output Motor1 back left thruster, +x thrust
# @output Motor2 front left thruster, -x thrust
# @output Motor3 back right thruster, +x thrust
# @output Motor4 front right thruster, -x thrust
# @output Motor5 front left thruster, +y thrust
# @output Motor6 front right thruster, -y thrust
# @output Motor7 back left thruster, +y thrust
# @output Motor8 back right thruster, -y thrust
#
# @maintainer DISCOWER
# @url https://atmos.discower.io
#
. ${R}etc/init.d/rc.sc_defaults
@@ -35,6 +25,7 @@ param set-default COM_LOW_BAT_ACT 0
param set-default NAV_DLL_ACT 0
param set-default GF_ACTION 1
param set-default NAV_RCL_ACT 1
param set-default COM_POSCTL_NAVL 2
# Set Mocap Vision frame
param set EKF2_EV_CTRL 15
+1 -24
View File
@@ -8,9 +8,6 @@
# End Setup for board specific configurations. #
###############################################################################
#
# Set SD logging mode
#
if param compare SDLOG_MODE 1
then
set LOGGER_ARGS "${LOGGER_ARGS} -e"
@@ -31,28 +28,8 @@ then
set LOGGER_ARGS "${LOGGER_ARGS} -a"
fi
#
# Set logging backend
#
if param compare SDLOG_BACKEND 1
then
set LOGGER_ARGS "${LOGGER_ARGS} -m file"
fi
if param compare SDLOG_BACKEND 2
then
set LOGGER_ARGS "${LOGGER_ARGS} -m mavlink"
fi
if param compare SDLOG_BACKEND 3
then
set LOGGER_ARGS "${LOGGER_ARGS} -m all"
fi
#
# Start logger if any logging backend is enabled
#
if ! param compare SDLOG_BACKEND 0
if ! param compare SDLOG_MODE -1
then
logger start -b ${LOGGER_BUF} -t ${LOGGER_ARGS}
fi
-1
View File
@@ -237,7 +237,6 @@ then
qmc5883p -X -q start
rm3100 -X -q start
bmm350 -X -q start
iis2mdc -X -q start
# start last (wait for possible icm20948 passthrough mode)
ak09916 -X -q start
+19 -12
View File
@@ -217,17 +217,6 @@ else
fi
unset BOARD_RC_DEFAULTS
#
# Optional additional init file: rc.additional_init
#
set BOARD_RC_ADDITIONAL_INIT ${R}etc/init.d/rc.additional_init
if [ -f $BOARD_RC_ADDITIONAL_INIT ]
then
echo "Board additional init: ${BOARD_RC_ADDITIONAL_INIT}"
. $BOARD_RC_ADDITIONAL_INIT
fi
unset BOARD_RC_ADDITIONAL_INIT
# Load airframe configuration based on SYS_AUTOSTART parameter
if ! param compare SYS_AUTOSTART 0
then
@@ -624,7 +613,9 @@ else
. ${R}etc/init.d/rc.autostart.post
fi
#
# Bootloader upgrade (ROMFS)
#
set BOARD_BOOTLOADER_UPGRADE ${R}etc/init.d/rc.board_bootloader_upgrade
if [ -f $BOARD_BOOTLOADER_UPGRADE ]
then
@@ -632,6 +623,22 @@ else
fi
unset BOARD_BOOTLOADER_UPGRADE
#
# Bootloader upgrade (SD card)
#
if param compare -s SYS_BL_UPDATE 2
then
if [ -f "/fs/microsd/bl/bl.bin" ]
then
param set SYS_BL_UPDATE 0
param save
echo "bootloader update..."
bl_update "/fs/microsd/bl/bl.bin"
echo "bootloader update done, rebooting"
reboot
fi
fi
#
# Check if UAVCAN is enabled, default to it for ESCs.
#
@@ -49,14 +49,14 @@ for field in spec.parsed_fields():
(package, name) = genmsg.names.package_resource_name(field.base_type)
package = package or spec.package # convert '' to package
print('typedef px4_msgs_msg_%s px4_msgs_msg_px4_msgs__msg__%s;' % (name,name))
print('typedef px4_msg_%s px4_msg_px4__msg__%s;' % (name,name))
}@
typedef struct @uorb_struct px4_msgs_msg_@(file_base_name);
typedef struct @uorb_struct px4_msg_@(file_base_name);
extern const struct dds_cdrstream_desc px4_msgs_msg_@(file_base_name)_cdrstream_desc;
extern const struct dds_cdrstream_desc px4_msg_@(file_base_name)_cdrstream_desc;
#ifdef __cplusplus
}
+1 -2
View File
@@ -14,6 +14,7 @@ class AirframeGroup(object):
self.af_class = af_class
self.airframes = []
def AddAirframe(self, airframe):
"""
Add airframe to the airframe group
@@ -106,8 +107,6 @@ class AirframeGroup(object):
return "Balloon"
elif (self.type == "Vectored 6 DOF UUV"):
return "Vectored6DofUUV"
elif self.type == "Free-Flyer":
return "FreeFlyer"
return "AirframeUnknown"
def GetAirframes(self):
+5 -24
View File
@@ -42,7 +42,6 @@ import os
import argparse
import re
import sys
import json
try:
import em
@@ -125,7 +124,7 @@ def generate_by_template(output_file, template_file, em_globals):
return True
def generate_topics_list_file_from_files(files, outputdir, template_filename, templatedir, rihs_path):
def generate_topics_list_file_from_files(files, outputdir, template_filename, templatedir):
# generate cpp file with topics list
filenames = []
for filename in [os.path.basename(p) for p in files if os.path.basename(p).endswith(".msg")]:
@@ -139,27 +138,11 @@ def generate_topics_list_file_from_files(files, outputdir, template_filename, te
for filename in [os.path.basename(p) for p in files if os.path.basename(p).endswith(".msg")]:
full_base_names.append(filename.replace(".msg",""))
rihs01_hashes = dict()
if rihs_path != '':
for topic in full_base_names:
with open(rihs_path + "/msg/" + topic + ".json") as f:
d = json.load(f)
assert d['type_hashes'][0]['hash_string'][:7] == 'RIHS01_'
rihs01_hash = d['type_hashes'][0]['hash_string'][7:]
byte_array = [f"0x{rihs01_hash[i:i+2]}" for i in range(0, len(rihs01_hash), 2)]
c_code = f"{{ {', '.join(byte_array)} }};"
rihs01_hashes[topic] = c_code
topics = []
datatypes_with_topics = dict()
for msg_filename in files:
datatype = re.sub(r'(?<!^)(?=[A-Z])', '_', os.path.basename(msg_filename)).lower().replace(".msg","")
datatypes_with_topics[datatype] = get_topics(msg_filename)
topics.extend(datatypes_with_topics[datatype])
topics.extend(get_topics(msg_filename))
tl_globals = {"msgs": filenames, "topics": topics, "datatypes": datatypes, "full_base_names": full_base_names, "rihs01_hashes": rihs01_hashes, "datatypes_with_topics": datatypes_with_topics}
tl_globals = {"msgs": filenames, "topics": topics, "datatypes": datatypes, "full_base_names": full_base_names}
tl_template_file = os.path.join(templatedir, template_filename)
tl_out_file = os.path.join(outputdir, template_filename.replace(".em", ""))
@@ -179,15 +162,13 @@ if __name__ == "__main__":
parser.add_argument('-p', dest='prefix', default='',
help='string added as prefix to the output file '
' name when converting directories')
parser.add_argument('--rihs', dest='rihs', default='',
help='path where rihs01 json files located')
args = parser.parse_args()
if args.zenoh_config:
generate_topics_list_file_from_files(args.file, args.outputdir, ZENOH_TEMPLATE_FILE[0], args.templatedir, args.rihs)
generate_topics_list_file_from_files(args.file, args.outputdir, ZENOH_TEMPLATE_FILE[0], args.templatedir)
exit(0)
elif args.zenoh_pub_sub:
generate_topics_list_file_from_files(args.file, args.outputdir, ZENOH_TEMPLATE_FILE[1], args.templatedir, args.rihs)
generate_topics_list_file_from_files(args.file, args.outputdir, ZENOH_TEMPLATE_FILE[1], args.templatedir)
exit(0)
else:
print('Error: either --headers or --sources must be specified')
@@ -74,7 +74,7 @@ full_base_names.sort()
@[for idx, topic_name in enumerate(datatypes)]@
@{
type_topic_count = len(datatypes_with_topics[topic_name])
type_topic_count = len([e for e in topic_names_all if e.startswith(topic_name)])
}@
#ifdef CONFIG_ZENOH_PUBSUB_@(topic_name.upper())
# define CONFIG_ZENOH_PUBSUB_@(topic_name.upper())_COUNT @(type_topic_count)
@@ -88,28 +88,9 @@ type_topic_count = len(datatypes_with_topics[topic_name])
CONFIG_ZENOH_PUBSUB_@(topic_name.upper())_COUNT + \
@[end for] 0
@[for topic_name, rihs01_hash in rihs01_hashes.items()]@
const uint8_t @(topic_name)_hash[32] = @(rihs01_hash)
@[end for]
@[for idx, topic_name in enumerate(datatypes)]@
#ifdef CONFIG_ZENOH_PUBSUB_@(topic_name.upper())
@{
topic_names = datatypes_with_topics[topic_name]
}@
const orb_metadata* @(topic_name)_topic_meta[@(len(topic_names))] = {
@[for topic_name_inst in topic_names]@
ORB_ID(@(topic_name_inst)),
@[end for]};
#endif
@[end for]
typedef struct {
const char *data_type_name;
const uint32_t *ops;
const uint8_t *hash;
const orb_metadata** orb_topic;
const uint8_t orb_topics_size;
const orb_metadata* orb_meta;
} UorbPubSubTopicBinder;
const UorbPubSubTopicBinder _topics[ZENOH_PUBSUB_COUNT] {
@@ -119,95 +100,54 @@ uorb_id_idx = 0
@[for idx, topic_name in enumerate(datatypes)]@
#ifdef CONFIG_ZENOH_PUBSUB_@(topic_name.upper())
@{
topic_names = datatypes_with_topics[topic_name]
topic_names = [e for e in topic_names_all if e.startswith(topic_name)]
}@
@[for topic_name_inst in topic_names]@
{
"@(topic_name)",
px4_msgs_msg_@(topic_dict[topic_name])_cdrstream_desc.ops.ops,
@(topic_dict[topic_name])_hash,
@(topic_name)_topic_meta,
@(len(topic_names)),
px4_msg_@(topic_dict[topic_name])_cdrstream_desc.ops.ops,
ORB_ID(@(topic_name_inst))
},
#endif
@{
uorb_id_idx += 1
}@
@[end for]#endif
@[end for]
};
uORB_Zenoh_Publisher* genPublisher(const orb_metadata *meta, int instance) {
uORB_Zenoh_Publisher* genPublisher(const orb_metadata *meta) {
for (auto &pub : _topics) {
for(int i = 0; i < pub.orb_topics_size; i++) {
if(pub.orb_topic[i]->o_id == meta->o_id) {
return new uORB_Zenoh_Publisher(meta, pub.ops, instance);
}
if(pub.orb_meta->o_id == meta->o_id) {
return new uORB_Zenoh_Publisher(meta, pub.ops);
}
}
return NULL;
}
uORB_Zenoh_Publisher* genPublisher(const char *name, int instance) {
uORB_Zenoh_Publisher* genPublisher(const char *name) {
for (auto &pub : _topics) {
for(int i = 0; i < pub.orb_topics_size; i++) {
if(strcmp(pub.orb_topic[i]->o_name, name) == 0) {
return new uORB_Zenoh_Publisher(pub.orb_topic[i], pub.ops, instance);
}
if(strcmp(pub.orb_meta->o_name, name) == 0) {
return new uORB_Zenoh_Publisher(pub.orb_meta, pub.ops);
}
}
return NULL;
}
Zenoh_Subscriber* genSubscriber(const orb_metadata *meta, int instance) {
Zenoh_Subscriber* genSubscriber(const orb_metadata *meta) {
for (auto &sub : _topics) {
for(int i = 0; i < sub.orb_topics_size; i++) {
if(sub.orb_topic[i]->o_id == meta->o_id) {
return new uORB_Zenoh_Subscriber(meta, sub.ops, instance);
}
if(sub.orb_meta->o_id == meta->o_id) {
return new uORB_Zenoh_Subscriber(meta, sub.ops);
}
}
return NULL;
}
Zenoh_Subscriber* genSubscriber(const char *name, int instance) {
Zenoh_Subscriber* genSubscriber(const char *name) {
for (auto &sub : _topics) {
for(int i = 0; i < sub.orb_topics_size; i++) {
if(strcmp(sub.orb_topic[i]->o_name, name) == 0) {
return new uORB_Zenoh_Subscriber(sub.orb_topic[i], sub.ops, instance);
}
}
}
return NULL;
}
const char* getTypeName(const char *name) {
for (auto &sub : _topics) {
for(int i = 0; i < sub.orb_topics_size; i++) {
if(strcmp(sub.orb_topic[i]->o_name, name) == 0) {
return sub.data_type_name;
}
}
}
return NULL;
}
const uint8_t* getRIHS01_Hash(const orb_metadata *meta) {
for (auto &sub : _topics) {
for(int i = 0; i < sub.orb_topics_size; i++) {
if(sub.orb_topic[i]->o_id == meta->o_id) {
return sub.hash;
}
}
}
return NULL;
}
const uint8_t* getRIHS01_Hash(const char *name) {
for (auto &sub : _topics) {
for(int i = 0; i < sub.orb_topics_size; i++) {
if(strcmp(sub.orb_topic[i]->o_name, name) == 0) {
return sub.hash;
}
if(strcmp(sub.orb_meta->o_name, name) == 0) {
return new uORB_Zenoh_Subscriber(sub.orb_meta, sub.ops);
}
}
return NULL;
@@ -75,6 +75,7 @@ CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
+1
View File
@@ -35,6 +35,7 @@ CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
-1
View File
@@ -21,7 +21,6 @@ CONFIG_COMMON_MAGNETOMETER=y
CONFIG_DATAMAN_PERSISTENT_STORAGE=n
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_COMMON_RC=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
@@ -14,7 +14,7 @@ param set-default SYS_DM_BACKEND 1
# Set TELEM1 as default mavlink connection
param set-default MAV_0_CONFIG 0
# Disable logger writing to FRAM, only stream over MAVLINK
param set-default SDLOG_BACKEND 2
set LOGGER_ARGS "-m mavlink"
# 200kOhm/10kOhm voltage divider on V_BAT
param set-default BAT1_V_DIV 21
+11 -17
View File
@@ -12,20 +12,17 @@ board_adc start
bmi088 -A -R 0 -s start
bmi088 -G -R 0 -s start
# MAG on I2C4, ROTATION_ROLL_180=8
if ver hwtypecmp V6S013 V6S015
then
# Revision(s) with BMM150
# MAG on I2C4, ROTATION_ROLL_180=8
bmm150 -I -R 8 start
else
# Revision(s) with BMM350
# MAG on I2C4, ROTATION_ROLL_180=8
bmm350 -I -R 8 start
fi
# BARO on I2C4
bmp388 -I -b 4 -a 0x77 start
# External sensors on I2C1
if param compare SENS_EN_INA226 1
then
# Start Digital power monitors
@@ -62,17 +59,14 @@ fi
if param compare BAT1_V_CHANNEL -2
then
if [ "$INA_CONFIGURED" != "yes" ]
then
param set BAT1_V_CHANNEL -1
fi
if [ "$INA_CONFIGURED" != "yes" ]
then
param set BAT1_V_CHANNEL -1
fi
fi
# External compass IST8310 on I2C1
# External compass on GPS1/I2C1 (the 3rd external bus): standard Holybro Pixhawk 4 or CUAV V5 GPS/compass puck (with lights, safety button, and buzzer)
ist8310 -X -b 1 -R 10 start
# Start an external PWM generator
if param greater PCA9685_EN_BUS 0
then
pca9685_pwm_out start -b 1
fi
# BARO on I2C4
bmp388 -I -b 4 -a 0x77 start
+1
View File
@@ -71,6 +71,7 @@ CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
+1
View File
@@ -8,4 +8,5 @@ CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n
CONFIG_BOARD_TESTING=y
CONFIG_DRIVERS_TEST_PPM=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_MICROBENCH=y
@@ -74,6 +74,7 @@ CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_GPIO=y
@@ -75,6 +75,7 @@ CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_GPIO=y
@@ -75,6 +75,7 @@ CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
+1
View File
@@ -66,6 +66,7 @@ CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
+1
View File
@@ -68,6 +68,7 @@ CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
@@ -38,5 +38,5 @@ param set-default SYS_DM_BACKEND 1
# Ignore that there is no SD card
param set-default COM_ARM_SDCARD 0
# Disable logging
param set-default SDLOG_BACKEND 0
# Don't try to log onto SD card
param set-default SDLOG_MODE -1
@@ -38,5 +38,5 @@ param set-default SYS_DM_BACKEND 1
# Ignore that there is no SD card
param set-default COM_ARM_SDCARD 0
# Disable logging
param set-default SDLOG_BACKEND 0
# Don't try to log onto SD card
param set-default SDLOG_MODE -1
+1
View File
@@ -79,6 +79,7 @@ CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
+1
View File
@@ -84,6 +84,7 @@ CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
+1
View File
@@ -79,6 +79,7 @@ CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
+1
View File
@@ -67,6 +67,7 @@ CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_GPIO=y
@@ -73,6 +73,7 @@ CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
+1
View File
@@ -73,6 +73,7 @@ CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
+1
View File
@@ -73,6 +73,7 @@ CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
+1
View File
@@ -75,6 +75,7 @@ CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
+1
View File
@@ -8,4 +8,5 @@ CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n
CONFIG_BOARD_TESTING=y
CONFIG_DRIVERS_TEST_PPM=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_MICROBENCH=y
-1
View File
@@ -14,7 +14,6 @@ CONFIG_MODULES_EKF2=y
CONFIG_MODULES_MAVLINK=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_ZENOH=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_MFT=y
@@ -182,7 +182,6 @@ CONFIG_NET_SOLINGER=y
CONFIG_NET_TCP=y
CONFIG_NET_TCPBACKLOG=y
CONFIG_NET_TCP_DELAYED_ACK=y
CONFIG_NET_TCP_KEEPALIVE=y
CONFIG_NET_TCP_WRITE_BUFFERS=y
CONFIG_NET_TIMESTAMP=y
CONFIG_NET_UDP=y
@@ -208,7 +207,6 @@ CONFIG_PIPES=y
CONFIG_PREALLOC_TIMERS=50
CONFIG_PRIORITY_INHERITANCE=y
CONFIG_PTHREAD_MUTEX_ROBUST=y
CONFIG_PTHREAD_MUTEX_TYPES=y
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAM_SIZE=272000
CONFIG_RAM_START=0x20400000
+57
View File
@@ -0,0 +1,57 @@
# CONFIG_BOARD_ROMFSROOT is not set
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS1"
CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS4"
CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS2"
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS3"
CONFIG_BOARD_UAVCAN_INTERFACES=1
CONFIG_COMMON_LIGHT=y
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y
CONFIG_DRIVERS_MAGNETOMETER_LIS3MDL=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_DRIVERS_SAFETY_BUTTON=y
CONFIG_DRIVERS_UAVCAN=y
CONFIG_EXAMPLES_FAKE_GPS=y
CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FW_ATT_CONTROL=y
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_FW_MODE_MANAGER=y
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
CONFIG_MODULES_FW_RATE_CONTROL=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LOAD_MON=y
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y
CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_MODULES_ZENOH=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_REFLECT=y
CONFIG_SYSTEMCMDS_SERIAL_TEST=y
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
@@ -75,7 +75,6 @@ CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_MODULES_ZENOH=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
@@ -49,7 +49,6 @@ CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEBUG_TCBINFO=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_SIZE=70
CONFIG_DEV_URANDOM=y
CONFIG_ETH0_PHY_DP83825I=y
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
@@ -156,8 +155,8 @@ CONFIG_NETDEV_LATEINIT=y
CONFIG_NETDEV_PHY_IOCTL=y
CONFIG_NETINIT_DHCPC=y
CONFIG_NETINIT_DNS=y
CONFIG_NETINIT_DNSIPADDR=0xA290AFE
CONFIG_NETINIT_DRIPADDR=0xA290AFE
CONFIG_NETINIT_DNSIPADDR=0XC0A800FE
CONFIG_NETINIT_DRIPADDR=0XC0A800FE
CONFIG_NETINIT_RETRY_MOUNTPATH=10
CONFIG_NETINIT_THREAD=y
CONFIG_NETINIT_THREAD_PRIORITY=49
@@ -168,18 +167,15 @@ CONFIG_NET_BROADCAST=y
CONFIG_NET_CAN=y
CONFIG_NET_CAN_EXTID=y
CONFIG_NET_CAN_NOTIFIER=y
CONFIG_NET_CAN_RAW_FILTER_MAX=1
CONFIG_NET_CAN_RAW_TX_DEADLINE=y
CONFIG_NET_CAN_SOCK_OPTS=y
CONFIG_NET_ETH_PKTSIZE=1518
CONFIG_NET_ICMP=y
CONFIG_NET_ICMP_SOCKET=y
CONFIG_NET_IGMP=y
CONFIG_NET_SOLINGER=y
CONFIG_NET_TCP=y
CONFIG_NET_TCPBACKLOG=y
CONFIG_NET_TCP_DELAYED_ACK=y
CONFIG_NET_TCP_KEEPALIVE=y
CONFIG_NET_TCP_WRITE_BUFFERS=y
CONFIG_NET_TIMESTAMP=y
CONFIG_NET_UDP=y
@@ -200,7 +196,6 @@ CONFIG_NSH_VARS=y
CONFIG_PIPES=y
CONFIG_PREALLOC_TIMERS=50
CONFIG_PRIORITY_INHERITANCE=y
CONFIG_PTHREAD_MUTEX_TYPES=y
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAM_SIZE=1048576
CONFIG_RAM_START=0x20200000
+1
View File
@@ -47,6 +47,7 @@ CONFIG_MODULES_SENSORS=y
# CONFIG_SENSORS_VEHICLE_AIRSPEED is not set
# CONFIG_SENSORS_VEHICLE_OPTICAL_FLOW is not set
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_MFT=y
CONFIG_SYSTEMCMDS_MTD=y
+1
View File
@@ -79,6 +79,7 @@ CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
+1
View File
@@ -80,6 +80,7 @@ CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
+1
View File
@@ -77,6 +77,7 @@ CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
+1
View File
@@ -83,6 +83,7 @@ CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
+1
View File
@@ -91,6 +91,7 @@ CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_GPIO=y
-1
View File
@@ -89,7 +89,6 @@ CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_MODULES_ZENOH=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
@@ -55,7 +55,6 @@ CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEBUG_TCBINFO=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_SIZE=70
CONFIG_DEV_URANDOM=y
CONFIG_ETH0_PHY_MULTI=y
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
@@ -215,18 +214,15 @@ CONFIG_NET_BROADCAST=y
CONFIG_NET_CAN=y
CONFIG_NET_CAN_EXTID=y
CONFIG_NET_CAN_NOTIFIER=y
CONFIG_NET_CAN_RAW_FILTER_MAX=1
CONFIG_NET_CAN_RAW_TX_DEADLINE=y
CONFIG_NET_CAN_SOCK_OPTS=y
CONFIG_NET_ETH_PKTSIZE=1518
CONFIG_NET_ICMP=y
CONFIG_NET_ICMP_SOCKET=y
CONFIG_NET_IGMP=y
CONFIG_NET_SOLINGER=y
CONFIG_NET_TCP=y
CONFIG_NET_TCPBACKLOG=y
CONFIG_NET_TCP_DELAYED_ACK=y
CONFIG_NET_TCP_KEEPALIVE=y
CONFIG_NET_TCP_WRITE_BUFFERS=y
CONFIG_NET_TIMESTAMP=y
CONFIG_NET_UDP=y
@@ -247,7 +243,6 @@ CONFIG_NSH_VARS=y
CONFIG_PIPES=y
CONFIG_PREALLOC_TIMERS=50
CONFIG_PRIORITY_INHERITANCE=y
CONFIG_PTHREAD_MUTEX_TYPES=y
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAMTRON_SETSPEED=y
CONFIG_RAM_SIZE=1835008
@@ -72,6 +72,7 @@ CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
+1
View File
@@ -74,6 +74,7 @@ CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
+1
View File
@@ -74,6 +74,7 @@ CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
+1
View File
@@ -61,6 +61,7 @@ CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
+1
View File
@@ -66,6 +66,7 @@ CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
+1
View File
@@ -65,6 +65,7 @@ CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
+1
View File
@@ -65,6 +65,7 @@ CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_BL_UPDATE_BL_ROMFS=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
-5
View File
@@ -339,11 +339,6 @@ if(EXISTS ${BOARD_DEFCONFIG})
endif()
endif()
# ADDITIONAL INIT
if(ADDITIONAL_INIT)
set(config_additional_init ${ADDITIONAL_INIT} CACHE INTERNAL "additional init" FORCE)
endif()
if(UAVCAN_INTERFACES)
set(config_uavcan_num_ifaces ${UAVCAN_INTERFACES} CACHE INTERNAL "UAVCAN interfaces" FORCE)
endif()
@@ -1,8 +1,8 @@
# Onboard parameters for Vehicle 1
#
# Stack: PX4 Pro
# Vehicle: Multi-Rotor
# Version: 1.15.4
# Vehicle: śŕĐýŇí
# Version: 1.15.4
# Git Revision: 99c40407ff000000
#
# Vehicle-Id Component-Id Name Value Type
@@ -318,6 +318,7 @@
1 1 COM_OBS_AVOID 0 6
1 1 COM_OF_LOSS_T 1.000000000000000000 9
1 1 COM_PARACHUTE 0 6
1 1 COM_POSCTL_NAVL 0 6
1 1 COM_POS_FS_DELAY 1 6
1 1 COM_POS_FS_EPH 5.000000000000000000 9
1 1 COM_POS_LOW_EPH -1.000000000000000000 9
-197
View File
@@ -1,197 +0,0 @@
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<!-- Generator: Adobe Illustrator 19.2.0, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg
version="1.1"
id="draw"
x="0px"
y="0px"
viewBox="0 0 291.424 291.77"
enable-background="new 0 0 291.424 291.77"
xml:space="preserve"
sodipodi:docname="FreeFlyer.svg"
inkscape:version="1.2.2 (b0a8486541, 2022-12-01)"
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
xmlns="http://www.w3.org/2000/svg"
xmlns:svg="http://www.w3.org/2000/svg"
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
xmlns:cc="http://creativecommons.org/ns#"
xmlns:dc="http://purl.org/dc/elements/1.1/"><metadata
id="metadata13908"><rdf:RDF><cc:Work
rdf:about=""><dc:format>image/svg+xml</dc:format><dc:type
rdf:resource="http://purl.org/dc/dcmitype/StillImage" /><dc:title>QuadRotorX</dc:title></cc:Work></rdf:RDF></metadata><defs
id="defs13906"><rect
x="64.295094"
y="257.16159"
width="20.004284"
height="19.434001"
id="rect1674" /><rect
x="57.181928"
y="12.768183"
width="21.455602"
height="14.069247"
id="rect1668" /><rect
x="64.295097"
y="257.16159"
width="20.004284"
height="19.434002"
id="rect1674-3" /><rect
x="64.295097"
y="257.16159"
width="20.004284"
height="19.434002"
id="rect1674-6" /><rect
x="64.295097"
y="257.16159"
width="20.004284"
height="19.434002"
id="rect1674-8" /><rect
x="64.295097"
y="257.16159"
width="20.004284"
height="19.434002"
id="rect1674-9" /><rect
x="64.295097"
y="257.16159"
width="20.004284"
height="19.434002"
id="rect1674-9-0" /><rect
x="64.295097"
y="257.16159"
width="20.004284"
height="19.434002"
id="rect1674-9-0-3" /><rect
x="64.295097"
y="257.16159"
width="20.004284"
height="19.434002"
id="rect1674-9-0-5" /></defs><sodipodi:namedview
pagecolor="#ffffff"
bordercolor="#666666"
borderopacity="1"
objecttolerance="10"
gridtolerance="10"
guidetolerance="10"
inkscape:pageopacity="0"
inkscape:pageshadow="2"
inkscape:window-width="1920"
inkscape:window-height="1131"
id="namedview13904"
showgrid="true"
showguides="false"
inkscape:zoom="2"
inkscape:cx="37"
inkscape:cy="143.75"
inkscape:window-x="0"
inkscape:window-y="0"
inkscape:window-maximized="1"
inkscape:current-layer="draw"
inkscape:showpageshadow="2"
inkscape:pagecheckerboard="0"
inkscape:deskcolor="#d1d1d1"><inkscape:grid
type="xygrid"
id="grid14610" /></sodipodi:namedview><title
id="title13869">QuadRotorX</title>
<rect
style="fill:#4ec3e8;fill-opacity:0.8;stroke-width:0.703099"
id="rect866"
width="182.87863"
height="182.87863"
x="54.336742"
y="54.008221" /><path
style="fill:#159e1f;fill-opacity:0.8;stroke-width:1.32638"
d="m 41.75804,283.31181 64.75142,-0.1091 -34.35904,-46.53234"
id="path978" /><path
style="fill:#159e1f;fill-opacity:0.8;stroke-width:1.32638"
d="m 8.0625538,189.05596 0.1091,64.75142 46.5323452,-34.35904"
id="path978-3" /><path
style="fill:#159e1f;fill-opacity:0.8;stroke-width:1.32638"
d="m 7.6111718,42.233006 0.1091,64.751414 46.5323442,-34.359034"
id="path978-3-5" /><path
style="fill:#159e1f;fill-opacity:0.8;stroke-width:1.32638"
d="M 283.3143,102.92315 283.2052,38.171731 236.67284,72.530766"
id="path978-3-0" /><path
style="fill:#159e1f;fill-opacity:0.8;stroke-width:1.32638"
d="m 283.76568,249.7461 -0.1091,-64.75142 -46.53235,34.35904"
id="path978-3-5-9" /><path
style="fill:#159e1f;fill-opacity:0.8;stroke-width:1.32638"
d="m 186.0159,282.76127 64.75142,-0.1091 -34.35904,-46.53235"
id="path978-5" /><path
style="fill:#159e1f;fill-opacity:0.8;stroke-width:1.32638"
d="m 249.48837,7.3723165 -64.75142,0.1091 34.35904,46.5323455"
id="path978-6" /><path
style="fill:#159e1f;fill-opacity:0.8;stroke-width:1.32638"
d="M 105.23051,7.9228645 40.479095,8.0319644 74.838131,54.56431"
id="path978-5-2" /><path
fill="#ffffff"
stroke="#000000"
stroke-miterlimit="10"
d="m 177.46535,152.08429 -25.44869,25.44869 c -2.72029,2.72029 -7.13013,2.72029 -9.84972,0 l -25.44868,-25.44869 c -2.7203,-2.72029 -2.7203,-7.13013 0,-9.84972 l 25.44868,-25.44868 c 2.72029,-2.72029 7.13013,-2.72029 9.84972,0 l 25.44869,25.44868 c 2.72029,2.72029 2.72029,7.13013 0,9.84972 z"
id="path13875-2"
style="stroke-width:0.703099" /><polygon
fill="#ff442b"
stroke="#000000"
stroke-miterlimit="10"
points="145.645,117.211 163.823,168.211 127.468,168.211 "
id="polygon13877-7"
transform="matrix(0.70309945,0,0,0.70309945,44.68853,44.358917)" /><text
xml:space="preserve"
id="text1666"
style="fill:#ffffff;fill-opacity:0.80000001;white-space:pre;shape-inside:url(#rect1668)" /><text
xml:space="preserve"
id="text1672"
style="font-size:16px;white-space:pre;shape-inside:url(#rect1674);fill:#ffffff;fill-opacity:0.8"
transform="matrix(1.8712033,0,0,1.8712033,-56.149908,-232.98716)"><tspan
x="64.294922"
y="271.72011"
id="tspan2022">1</tspan></text><text
xml:space="preserve"
id="text1672-6"
style="font-size:16px;white-space:pre;shape-inside:url(#rect1674-3);display:inline;fill:#ffffff;fill-opacity:0.8"
transform="matrix(1.8712033,0,0,1.8712033,-54.90599,-471.96664)"><tspan
x="64.294922"
y="271.72011"
id="tspan2024">2</tspan></text><text
xml:space="preserve"
id="text1672-1"
style="font-size:16px;white-space:pre;shape-inside:url(#rect1674-6);display:inline;fill:#ffffff;fill-opacity:0.8"
transform="matrix(1.8712033,0,0,1.8712033,88.181331,-233.48182)"><tspan
x="64.294922"
y="271.72011"
id="tspan2026">3</tspan></text><text
xml:space="preserve"
id="text1672-7"
style="font-size:16px;white-space:pre;shape-inside:url(#rect1674-8);display:inline;fill:#ffffff;fill-opacity:0.8"
transform="matrix(1.8712033,0,0,1.8712033,89.923516,-472.9994)"><tspan
x="64.294922"
y="271.72011"
id="tspan2028">4</tspan></text><text
xml:space="preserve"
id="text1672-2"
style="font-size:16px;white-space:pre;shape-inside:url(#rect1674-9);display:inline;fill:#ffffff;fill-opacity:0.8"
transform="matrix(1.8712033,0,0,1.8712033,-107.88311,-425.85878)"><tspan
x="64.294922"
y="271.72011"
id="tspan2030">5</tspan></text><text
xml:space="preserve"
id="text1672-2-2"
style="font-size:16px;white-space:pre;shape-inside:url(#rect1674-9-0);display:inline;fill:#ffffff;fill-opacity:0.8"
transform="matrix(1.8712033,0,0,1.8712033,140.31603,-426.60417)"><tspan
x="64.294922"
y="271.72011"
id="tspan2032">6</tspan></text><text
xml:space="preserve"
id="text1672-2-2-7"
style="font-size:16px;white-space:pre;shape-inside:url(#rect1674-9-0-3);display:inline;fill:#ffffff;fill-opacity:0.8"
transform="matrix(1.8712033,0,0,1.8712033,-106.57328,-277.85487)"><tspan
x="64.294922"
y="271.72011"
id="tspan2034">7</tspan></text><text
xml:space="preserve"
id="text1672-2-2-9"
style="font-size:16px;white-space:pre;shape-inside:url(#rect1674-9-0-5);display:inline;fill:#ffffff;fill-opacity:0.8"
transform="matrix(1.8712033,0,0,1.8712033,140.59859,-279.63807)"><tspan
x="64.294922"
y="271.72011"
id="tspan2036">8</tspan></text></svg>

Before

Width:  |  Height:  |  Size: 7.4 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 21 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 30 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 18 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 26 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 37 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 19 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 25 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 18 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 50 KiB

-1
View File
@@ -157,7 +157,6 @@
- [mRo (3DR) Pixhawk Wiring Quickstart](assembly/quick_start_pixhawk.md)
- [Holybro Pixhawk Mini (FMUv3) - Discontinued](flight_controller/pixhawk_mini.md)
- [Manufacturer-Supported Autopilots](flight_controller/autopilot_manufacturer_supported.md)
- [Accton Godwit GA1](flight_controller/accton-godwit_ga1.md)
- [AirMind MindPX](flight_controller/mindpx.md)
- [AirMind MindRacer](flight_controller/mindracer.md)
- [ARK Electronics ARKV6X](flight_controller/ark_v6x.md)
+1 -1
View File
@@ -290,7 +290,7 @@ If you're using [DroneCAN ESC](../peripherals/esc_motors.md#dronecan) the contro
### Flight Controller Power
Pixhawk FCs require a regulated power supply that can supply at around 5V/3A continuous (check your specific FC)!
This is sufficient to power the controller itself and a few low-power peripherals, such as a GNSS module, RC receiver, and low power telemetry radio, but not for motors, actuators, and other peripherals.
This is sufficient to power the controller itself and a few low-power peripherals, such as a GNSS module, RC transmitter, and low power telemetry radio, but not for motors, actuators, and other peripherals.
[Power modules](../power_module/index.md) are commonly used to "split off" this regulated power supply for the FC and also to provide measurements of the battery voltage and total current to the whole system — which PX4 can use to estimate power levels.
The power module is connected to the FC power port, which is normally labeled `POWER` (or `POWER 1` or `POWER 2` for FCs that have redundant power supply).
+2 -29
View File
@@ -90,8 +90,6 @@ This is documented below.
The best way to customize the system startup is to introduce a [new frame configuration](../dev_airframes/adding_a_new_frame.md).
The frame configuration file can be included in the firmware or on an SD Card.
#### Dynamic customization
If you only need to "tweak" the existing configuration, such as starting one more application or setting the value of a few parameters, you can specify these by creating two files in the `/etc/` directory of the SD Card:
- [/etc/config.txt](#customizing-the-configuration-config-txt): modify parameter values
@@ -108,7 +106,7 @@ If editing on Windows use a suitable editor.
These files are referenced in PX4 code as `/fs/microsd/etc/config.txt` and `/fs/microsd/etc/extras.txt`, where the root folder of the microsd card is identified by the path `/fs/microsd`.
:::
##### Customizing the Configuration (config.txt)
#### Customizing the Configuration (config.txt)
The `config.txt` file can be used to modify parameters.
It is loaded after the main system has been configured and _before_ it is booted.
@@ -120,7 +118,7 @@ param set-default PWM_MAIN_DIS3 1000
param set-default PWM_MAIN_MIN3 1120
```
##### Starting Additional Applications (extras.txt)
#### Starting Additional Applications (extras.txt)
The `extras.txt` can be used to start additional applications after the main system boot.
Typically these would be payload controllers or similar optional custom components.
@@ -147,28 +145,3 @@ The following example shows how to start custom applications:
mandatory_app start # Will abort boot if mandatory_app is unknown or fails
```
#### Additional customization
In rare cases where the desired setup cannot be achieved through frame configuration or dynamic customization,
you can add a script that will be contained in the binary.
**Note**: In almost all cases, you should use a frame configuration. This method should only be used for
edge-cases such as customizing `cannode` based boards.
- Add a new init script in `boards/<vendor>/<board>/init` that will run during board startup. For example:
```sh
# File: boards/<vendor>/<board>/init/rc.additional
param set-default <param> <value>
```
- Add a new board variant in `boards/<vendor>/<board>/<variant>.px4board` that includes the additional script. For example:
```sh
# File: boards/<vendor>/<board>/var.px4board
CONFIG_BOARD_ADDITIONAL_INIT="rc.additional"
```
- Compile the firmware with your new variant by appending the variant name to the compile target. For example:
```sh
make <target>_var
```
+12 -2
View File
@@ -206,13 +206,23 @@ The relevant parameters shown below.
### Position Loss Failsafe Action
Multicopters will switch to [Altitude mode](../flight_modes_mc/altitude.md) if a height estimate is available, otherwise [Stabilized mode](../flight_modes_mc/manual_stabilized.md).
The failure action is controlled by [COM_POSCTL_NAVL](../advanced_config/parameter_reference.md#COM_POSCTL_NAVL), based on whether RC control is assumed to be available (and altitude information):
- `0`: Remote control available.
Switch to _Altitude mode_ if a height estimate is available, otherwise _Stabilized mode_.
- `1`: Remote control _not_ available.
Switch to _Descend mode_ if a height estimate is available, otherwise enter flight termination.
_Descend mode_ is a landing mode that does not require a position estimate.
Fixed-wing planes, and VTOLs not configured to land in hover ([NAV_FORCE_VT](../advanced_config/parameter_reference.md#NAV_FORCE_VT)), have a parameter ([FW_GPSF_LT](../advanced_config/parameter_reference.md#FW_GPSF_LT)) that defines how long they will loiter (circle with a constant roll angle ([FW_GPSF_R](../advanced_config/parameter_reference.md#FW_GPSF_R)) at the current altitude) after losing position before attempting to land.
If VTOLs have are configured to switch to hover for landing ([NAV_FORCE_VT](../advanced_config/parameter_reference.md#NAV_FORCE_VT)) then they will first transition and then descend.
The relevant parameters for all vehicles shown below.
| Parameter | Description |
| -------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------- |
| <a id="COM_POSCTL_NAVL"></a>[COM_POSCTL_NAVL](../advanced_config/parameter_reference.md#COM_POSCTL_NAVL) | Position control navigation loss response during mission. Values: `0` - assume use of RC, `1` - Assume no RC. |
Parameters that only affect Fixed-wing vehicles:
| Parameter | Description |
+2 -3
View File
@@ -35,15 +35,14 @@ The parameters you are most likely to change are listed below.
| Parameter | Description |
| ------------------------------------------------------------------------ | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| [SDLOG_MODE](../advanced_config/parameter_reference.md#SDLOG_MODE) | Logging Mode. Defines when logging starts and stops.<br />- `0`: Log when armed until disarm (default).<br />- `1`: Log from boot until disarm.<br />- `2`: Log from boot until shutdown.<br />- `3`: Log based on the [AUX1 RC channel](../advanced_config/parameter_reference.md#RC_MAP_AUX1).<br />- `4`: Log from first armed until shutdown. |
| [SDLOG_BACKEND](../advanced_config/parameter_reference.md#SDLOG_BACKEND) | Logging Backend (bitmask). Setting a bit enables the corresponding backend. If no backend is selected, the logger is disabled.<br />- bit `0`: SD card logging.</br >- bit `1`: Mavlink logging.
| [SDLOG_MODE](../advanced_config/parameter_reference.md#SDLOG_MODE) | Logging Mode. Defines when logging starts and stops.<br />- `-1`: Logging disabled.<br />- `0`: Log when armed until disarm (default).<br />- `1`: Log from boot until disarm.<br />- `2`: Log from boot until shutdown.<br />- `3`: Log based on the [AUX1 RC channel](../advanced_config/parameter_reference.md#RC_MAP_AUX1).<br />- `4`: Log from first armed until shutdown. |
| [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) | Logging profile. Use this to enable less common logging/analysis (e.g. for EKF2 replay, high rate logging for PID & filter tuning, thermal temperature calibration). |
| [SDLOG_MISSION](../advanced_config/parameter_reference.md#SDLOG_MISSION) | Create very small additional "Mission Log".<br>This log can _not_ be used with [Flight Review](../log/flight_log_analysis.md#flight-review-online-tool), but is useful when you need a small log for geotagging or regulatory compliance. |
Useful settings for specific cases:
- Raw sensor data for comparison: [SDLOG_MODE=1](../advanced_config/parameter_reference.md#SDLOG_MODE) and [SDLOG_PROFILE=64](../advanced_config/parameter_reference.md#SDLOG_PROFILE).
- Disabling logging altogether: [SDLOG_BACKEND=`0`](../advanced_config/parameter_reference.md#SDLOG_BACKEND)
- Disabling logging altogether: [SDLOG_MODE=`-1`](../advanced_config/parameter_reference.md#SDLOG_MODE)
### Logger module
@@ -1,153 +0,0 @@
# Accton Godwit G-A1
:::warning
PX4 does not manufacture this (or any) autopilot.
Contact the [manufacturer](https://cubepilot.org/#/home) for hardware support or compliance issues.
:::
The G-A1 is a state-of-the-art flight controller developed derived from the [Pixhawk Autopilot v6X Standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-012%20Pixhawk%20Autopilot%20v6X%20Standard.pdf).
It includes an STM32H753 double-precision floating-point FMU processor and an STM32F103 IO coprocessor, multiple IMUs with 6-axis inertial sensors, two pressure/temperature sensors, and a geomagnetic sensor.
It also has independent buses and power supplies, and is designed for safety and rich expansion capabilities.
With an integrated 10/100M Ethernet Physical Layer (PHY), the G-A1 can also communicate with a mission computer (airborne computer), high-end surveying and mapping cameras, and other UxV-mounted equipment for high-speed communications, meeting the needs of advanced UxV systems.
:::tip
Visit [Accton-IoT Godwit](https://www.accton-iot.com/godwit/) for more information.
:::
![AccGodwitGA1](../../assets/flight_controller/accton-godwit/ga1/outlook.png "Accton Godwit G-A1")
![AccGodwitGA1 Top View](../../assets/flight_controller/accton-godwit/ga1/orientation.png "Accton Godwit G-A1 Top View")
::: info
This flight controller is [manufacturer supported](../flight_controller/autopilot_manufacturer_supported.md).
:::
## Specifications
### Processor
- STM32H753IIK (Arm® Cortex®-M7 480MHz)
- STM32F103 (Arm® Cortex®-M3, 72MHz)
### Sensors
- Bosch BMI088 (vibration isolated)
- TDK InvenSense ICM-42688-P x 2 (one vibration isolated)
- TDK Barometric Pressure and Temperature Sensor CP-20100 x 2 (one vibration isolated)
- PNI RM3100 Geomagnetic Sensor (vibration isolated)
### Power
- 4.6V to 5.7V
### External ports
- 2 CAN Buses (CAN1 and CAN2)
- 3 TELEM Ports (TELEM1, TELEM2 and TELEM3)
- 2 GPS Ports (GPS1 with safety switch, LED, buzzer, and GPS2)
- 1 PPM IN
- 1 SBUS OUT
- 2 USB Ports (1 TYPE-C and 1 JST GH1.25)
- 1 10/100Base-T Ethernet Port
- 1 DSM/SBUS RC
- 1 UART 4
- 1 AD&IO Port
- 2 Debug Ports (1 IO Debug and 1 FMU Debug)
- 1 SPI6 Bus
- 4 Power Inputs (Power 1, Power 2, Power C1 and Power C2)
- 16 PWM Servo Outputs (A1-A8 from FMU and M1-M8 from IO)
- Micro SD Socket (supports SD 4.1 & SDIO 4.0 in two databus modes: 1 bit (default) and 4 bits)
### Size and Dimensions
- 92.2 (L) x 51.2 (W) x 28.3 (H) mm
- 77.6g (carrier board with IMU)
## Where to Buy
- [Accton-IoT Godwit](https://www.accton-iot.com/godwit/)
- [sales@accton-iot.com](sales@accton-iot.com)
## Pinout
![G-A1 Pin definition](../../assets/flight_controller/accton-godwit/ga1/pin_definition.png "G-A1 Pin definition")
## UART Mapping
| Serial# | Protocol | Port | Notes |
| ------- | --------- | ------ | ---------- |
| SERIAL1 | Telem1 | UART7 | /dev/ttyS6 |
| SERIAL2 | Telem2 | UART5 | /dev/ttyS4 |
| SERIAL3 | GPS1 | USART1 | /dev/ttyS0 |
| SERIAL4 | GPS2 | UART8 | /dev/ttyS7 |
| SERIAL5 | Telem3 | USART2 | /dev/ttyS1 |
| SERIAL6 | UART4 | UART4 | /dev/ttyS3 |
| SERIAL7 | FMU Debug | USART3 | |
| SERIAL8 | OTG2 | USB | |
## Wiring Diagram
![G-A1 Wiring](../../assets/flight_controller/accton-godwit/ga1/wiring.png "G-A1 Wiring")
## PWM Output
PWM M1-M8 (IO Main PWM), A1-A8(FMU PWM).
All these 16 support normal PWM output formats.
FMU PWM A1-A6 can support DShot and B-Directional DShot.
A1-A8(FMU PWM) are grouped as:
- Group 1: A1, A2, A3, A4
- Group 2: A5, A6
- Group 3: A7, A8
The motor and servo system should be connected to these ports according to the order outlined in the fuselage reference for your carrier.
![G-A1 PWM Motor Servo](../../assets/flight_controller/accton-godwit/ga1/motor_servo.png "G-A1 PWM Motor Servo")
## RC Input
For DSM/SBUS receivers, connect them to the DSM/SBUS interface which provides dedicated 3.3V and 5V power pins respectively, and check above "Pinout" for detailed pin definition.
PPM receivers should be connected to the PPM interface. And other RC systems can be connected via other spare telemetry ports.
![G-A1 Radio](../../assets/flight_controller/accton-godwit/ga1/radio.png "G-A1 Radio")
## GPS/Compass
The Godwit G-A1 has a built-in compass
Due to potential interference, the autopilot is usually used with an external I2C compass as part of a GPS/Compass combination.
![G-A1 GPS](../../assets/flight_controller/accton-godwit/ga1/gps.png "G-A1 GPS")
## Power Connection and Battery Monitor
This universal controller features a CAN PMU module that supports 3 to 14s lithium batteries.
To ensure proper connection, attach the module's 6-pin connector to the flight control Power C1 and/or Power C2 interface.
This universal controller does not provide power to the servos.
To power them, an external BEC must be connected to the positive and negative terminals of any A1A8 or M1M8 port.
![G-A1 Power](../../assets/flight_controller/accton-godwit/ga1/power.png "G-A1 Power")
## SD Card
The SD card is NOT included in the package, you need to prepare the SD card and insert it into the slot.
![G-A1 SD Card](../../assets/flight_controller/accton-godwit/ga1/sdcard.png "G-A1 SD Card")
## Firmware
The autopilot is compatible with PX4 firmware. And G-A1 can be detected by QGroundControl automatically. Users can also build it with target "accton-godwit_ga1"
To [build PX4](../dev_setup/building_px4.md) for this target, open up the terminal and enter:
```sh
make accton-godwit_ga1
```
## More Information and Support
- [Accton-IoT Godwit](https://www.accton-iot.com/godwit/)
- [sales@accton-iot.com](sales@accton-iot.com)
- [support@accton-iot.com](mailto:support@accton-iot.com)
@@ -12,7 +12,6 @@ This category includes boards that are not fully compliant with the pixhawk stan
The boards in this category are:
- [Accton Godwit GA1](../flight_controller/accton-godwit_ga1.md)
- [AirMind MindPX](../flight_controller/mindpx.md)
- [AirMind MindRacer](../flight_controller/mindracer.md)
- [ARK Electronics ARKV6X](../flight_controller/ark_v6x.md) (and [ARK Electronics Pixhawk Autopilot Bus Carrier](../flight_controller/ark_pab.md))
+1 -1
View File
@@ -5,7 +5,7 @@ PX4 uses accelerometer data for velocity estimation.
You should not need to attach an accelometer as a stand-alone external device:
- Most flight controllers, such as those in the [Pixhawk Series](../flight_controller/pixhawk_series.md), include an accelerometer as part of the flight controller's [Inertial Motion Unit (IMU)](https://en.wikipedia.org/wiki/Inertial_measurement_unit).
- Gyroscopes are present as part of an [external INS, AHRS or INS-enhanced GNSS system](../sensor/inertial_navigation_systems.md).
- Gyroscopes are present as part of an [external INS, ARHS or INS-enhanced GNSS system](../sensor/inertial_navigation_systems.md).
The accelerometer must be calibrated before first use of the vehicle:
-37
View File
@@ -316,43 +316,6 @@ For SIH as SITL (no FC):
For specific examples see the `_sihsim_` airframes in [ROMFS/px4fmu_common/init.d-posix/airframes](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d-posix/airframes/) (SIH as SITL) and [ROMFS/px4fmu_common/init.d/airframes](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d/airframes) (SIH on FC).
## Controlling Actuators in SIH
:::warning
If you want to control throttling actuators in SIH, make sure to remove propellers for safety.
:::
In some scenarios, it may be useful to control an actuator while running SIH. For example, you might want to verify that winches or grippers are functioning correctly by checking the servo responses.
To enable actuator control in SIH:
1. Configure PWM parameters in the airframe file:
Ensure your airframe file includes the necessary parameters to map PWM outputs to the correct channels.
For example, if a servo is connected to MAIN 3 and you want to map it to AUX1 on your RC, use the following command:
`param set-default PWM_MAIN_FUNC3 407`
You can find a full list of available values for `PWM_MAIN_FUNCn` [here](../advanced_config/parameter_reference.md#PWM_MAIN_FUNC1). In this case, `407` maps the MAIN 3 output to AUX1 on the RC.
Alternatively, you can use the [`PWM_AUX_FUNCn`](../advanced_config/parameter_reference.md#PWM_AUX_FUNC1) parameters.
You may also configure the output as desired:
- Disarmed PWM: ([`PWM_MAIN_DISn`](../advanced_config/parameter_reference.md#PWM_MAIN_DIS1) / [`PWM_AUX_DIS1`](../advanced_config/parameter_reference.md#PWM_AUX_DIS1))
- Minimum PWM ([`PWM_MAIN_MINn`](../advanced_config/parameter_reference.md#PWM_MAIN_MIN1) / [`PWM_AUX_MINn`](../advanced_config/parameter_reference.md#PWM_AUX_MIN1))
- Maximum PWM ([`PWM_MAIN_MAXn`](../advanced_config/parameter_reference.md#PWM_MAIN_MAX1) / [`PWM_AUX_MAXn`](../advanced_config/parameter_reference.md#PWM_AUX_MAX1))
2. Manually start the PWM output driver
For safety, the PWM driver is not started automatically in SIH. To enable it, run the following command in the MAVLink shell:
`pwm_out start`
And to disable it again:
`pwm_out stop`
## Dynamic Models
The dynamic models for the various vehicles are:
+6
View File
@@ -3,6 +3,12 @@
[Rotoye Batmon](https://rotoye.com/batmon/) is a kit for adding smart battery functionality to off-the-shelf Lithium-Ion and LiPo batteries.
It can be purchased as a standalone unit or as part of a factory-assembled smart-battery.
::: info
At time of writing you can only use Batmon by [building a custom branch of PX4](#build-px4-firmware).
Support in the codeline is pending [PR approval](https://github.com/PX4/PX4-Autopilot/pull/16723).
:::
![Rotoye Batmon Board](../../assets/hardware/smart_batteries/rotoye_batmon/smart-battery-rotoye.jpg)
![Pre-assembled Rotoye smart battery](../../assets/hardware/smart_batteries/rotoye_batmon/smart-battery-rotoye-pack.jpg)
-2
View File
@@ -843,8 +843,6 @@
- [시험 MC_04 - 안전 장치 시험](test_cards/mc_04_failsafe_testing.md)
- [Test MC_05 - Manual Modes (Inside)](test_cards/mc_05_indoor_flight_manual_modes.md)
- [Test MC_06 - Optical Flow (Inside)](test_cards/mc_06_optical_flow.md)
- [Test MC_07 - VIO (Inside)](test_cards/mc_07_vio.md)
- [Test MC_08 - DSHOT ESC](test_cards/mc_08_dshot.md)
- [단위 테스트](test_and_ci/unit_tests.md)
- [Fuzz Tests](test_and_ci/fuzz_tests.md)
- [지속 통합](test_and_ci/continous_integration.md)
+2 -29
View File
@@ -95,8 +95,6 @@ This is documented below.
The best way to customize the system startup is to introduce a [new frame configuration](../dev_airframes/adding_a_new_frame.md).
The frame configuration file can be included in the firmware or on an SD Card.
#### Dynamic customization
If you only need to "tweak" the existing configuration, such as starting one more application or setting the value of a few parameters, you can specify these by creating two files in the `/etc/` directory of the SD Card:
- [/etc/config.txt](#customizing-the-configuration-config-txt): modify parameter values
@@ -113,7 +111,7 @@ Windows에서 편집하는 경우 적절한 편집기를 사용하여야 합니
These files are referenced in PX4 code as `/fs/microsd/etc/config.txt` and `/fs/microsd/etc/extras.txt`, where the root folder of the microsd card is identified by the path `/fs/microsd`.
:::
##### 구성 사용자 정의(config.txt)
#### 구성 사용자 정의(config.txt)
The `config.txt` file can be used to modify parameters.
It is loaded after the main system has been configured and _before_ it is booted.
@@ -125,7 +123,7 @@ param set-default PWM_MAIN_DIS3 1000
param set-default PWM_MAIN_MIN3 1120
```
##### Starting Additional Applications (extras.txt)
#### Starting Additional Applications (extras.txt)
The `extras.txt` can be used to start additional applications after the main system boot.
일반적으로, 페이로드 콘트롤러나 유사한 선택적 사용자 지정 구성 요소들입니다.
@@ -152,28 +150,3 @@ Calling an unknown command in system boot files may result in boot failure.
mandatory_app start # Will abort boot if mandatory_app is unknown or fails
```
#### Additional customization
In rare cases where the desired setup cannot be achieved through frame configuration or dynamic customization,
you can add a script that will be contained in the binary.
**Note**: In almost all cases, you should use a frame configuration. This method should only be used for
edge-cases such as customizing `cannode` based boards.
- Add a new init script in `boards/<vendor>/<board>/init` that will run during board startup. 예:
```sh
# File: boards/<vendor>/<board>/init/rc.additional
param set-default <param> <value>
```
- Add a new board variant in `boards/<vendor>/<board>/<variant>.px4board` that includes the additional script. 예:
```sh
# File: boards/<vendor>/<board>/var.px4board
CONFIG_BOARD_ADDITIONAL_INIT="rc.additional"
```
- Compile the firmware with your new variant by appending the variant name to the compile target. 예:
```sh
make <target>_var
```
+11 -56
View File
@@ -27,18 +27,10 @@
That is the minimum setup to use the rover in [Manual mode](../flight_modes_rover/manual.md#manual-mode).
:::info
The rest of the tuning on this page is not mandatory for [Manual mode](../flight_modes_rover/manual.md#manual-mode), but it will have an effect on the behaviour of the rover.
:::
:::warning
Do not skip the rest of this setup if you intend to use more sophisticated modes!
All parameters will be mandatory for all subsequent modes, except those tagged as `(Optional)`.
:::
## Geometric Parameters
First, we set up the geometric parameters of the rover:
Manual mode is also affected by (optional) acceleration/deceleration limits set using the geometric described below.
These limits are mandatory for all other modes.
![Geometric parameters](../../assets/config/rover/geometric_parameters.png)
@@ -50,7 +42,7 @@ Navigate to [Parameters](../advanced_config/parameters.md) in QGroundControl and
2. [RA_MAX_STR_ANG](#RA_MAX_STR_ANG) [deg]: Measure the maximum steering angle.
3. (Optional) [RA_STR_RATE_LIM](#RA_STR_RATE_LIM) [deg/s]: Maximum steering rate you want to allow for your rover.
::: tip
:::tip
This value depends on your rover and use case.
For bigger rovers there might be a mechanical limit that is easy to identify by steering the rover at a standstill and increasing
[RA_STR_RATE_LIM](#RA_STR_RATE_LIM) until you observe the steering rate to no longer be limited by the parameter.
@@ -59,7 +51,7 @@ Navigate to [Parameters](../advanced_config/parameters.md) in QGroundControl and
:::
::: warning
:::warning
A low maximum steering rate makes the rover worse at tracking steering setpoints, which can lead to a poor performance in the subsequent modes.
:::
@@ -84,7 +76,7 @@ Navigate to [Parameters](../advanced_config/parameters.md) in QGroundControl and
2. (Optional) [RO_ACCEL_LIM](#RO_ACCEL_LIM) [m/s^2]: Maximum acceleration you want to allow for your rover.
<a id="RO_ACCEL_LIM_CONSIDERATIONS"></a>
<a id="RO_ACCEL_LIM_CONSIDERATIONS"></a>
:::tip
Your rover has a maximum possible acceleration which is determined by the maximum torque the motor can supply.
@@ -117,39 +109,6 @@ Navigate to [Parameters](../advanced_config/parameters.md) in QGroundControl and
:::
## (Optional) Stick Input Mapping
Input shaping can be used to adjust the default linear mapping from stick inputs $\in [-1, 1]$ to normalized setpoints $\in [-1, 1]$. Applying this specifically to the steering input, can provide a smoother driving experience, by enabling the user to make small adjustments when the stick is close to the center, but still send large inputs when moving them to the edges.
We provide this input shaping through the super exponential function:
$$
\delta = \frac{(f \cdot x^3 + x(1-f)) \cdot (1-g)}{1-g \cdot |x|}
$$
with:
- $\delta \in [-1, 1]=$ Normalized steering setpoint.
- $x \in [-1, 1]=$ Normalized stick input.
- $f=$ [RO_YAW_EXPO](#RO_YAW_EXPO): `0` Purely linear input curve, `1` Purely cubic input curve.
- $g=$ [RO_YAW_SUPEXPO](#RO_YAW_SUPEXPO): `0` Pure Expo function, `0.7` reasonable shape enhancement for intuitive stick feel, `0.95` very strong bent input curve only near maxima have effect.
In [Manual mode](../flight_modes_rover/manual.md#manual-mode) we can additionally scale $\delta$ with an additional parameter $r$:
- Differential Rover: $r=$ [RD_YAW_STK_GAIN](#RD_YAW_STK_GAIN), which enables adjusting the slope of the input mapping. This leads to a normalized steering input $\hat{\delta} = \delta \cdot r \in$ [-[RD_YAW_STK_GAIN](#RD_YAW_STK_GAIN), [RD_YAW_STK_GAIN](#RD_YAW_STK_GAIN)].
- Mecanum Rover: $r=$ [RM_YAW_STK_GAIN](#RM_YAW_STK_GAIN), which enables adjusting the slope of the input mapping. This leads to a normalized steering input $\hat{\delta} = \delta \cdot r \in$ [-[RM_YAW_STK_GAIN](#RM_YAW_STK_GAIN), [RM_YAW_STK_GAIN](#RM_YAW_STK_GAIN)].
This scaling is useful to limit the normalized steering setpoint, if it is too aggresive for your rover in manual mode.
You can experiment with the relationships graphically using the [PX4 SuperExpo Rover calculator](https://www.desmos.com/calculator/gwm8lrlanx).
:::info
In [Acro](../flight_modes_rover/manual.md#acro-mode), [Stabilized](../flight_modes_rover/manual.md#stabilized-mode) and [Position](../flight_modes_rover/manual.md#position-mode) Mode, $\delta$ is instead scaled by $r=$ [RO_YAW_RATE_LIM](../advanced_config/parameter_reference.md#RO_MAX_THR_SPEED) for all rovers. This leads to a yaw rate setpoint $\dot{\psi} = \delta \cdot r \in$ [-[RO_YAW_RATE_LIM](../advanced_config/parameter_reference.md#RO_MAX_THR_SPEED), [RO_YAW_RATE_LIM](../advanced_config/parameter_reference.md#RO_MAX_THR_SPEED)]. This parameter is setup during [rate tuning](rate_tuning.md).
:::
:::info
The input shaping through [RO_YAW_EXPO](#RO_YAW_EXPO) and [RO_YAW_SUPEXPO](#RO_YAW_SUPEXPO) applies for all manual modes, while [RD_YAW_STK_GAIN](#RD_YAW_STK_GAIN)/[RM_YAW_STK_GAIN](#RM_YAW_STK_GAIN) only affects full manual mode.
:::
You can now continue the configuration process with [rate tuning](rate_tuning.md).
## Parameter Overview
@@ -159,8 +118,6 @@ You can now continue the configuration process with [rate tuning](rate_tuning.md
| <a id="RO_MAX_THR_SPEED"></a>[RO_MAX_THR_SPEED](../advanced_config/parameter_reference.md#RO_MAX_THR_SPEED) | Speed the rover drives at maximum throttle | $m/s$ |
| <a id="RO_ACCEL_LIM"></a>[RO_ACCEL_LIM](../advanced_config/parameter_reference.md#RO_ACCEL_LIM) | (Optional) Maximum allowed acceleration | $m/s^2$ |
| <a id="RO_DECEL_LIM"></a>[RO_DECEL_LIM](../advanced_config/parameter_reference.md#RO_DECEL_LIM) | (Optional) Maximum allowed deceleration | $m/s^2$ |
| <a id="RO_YAW_EXPO"></a>[RO_YAW_EXPO](../advanced_config/parameter_reference.md#RO_YAW_EXPO) | (Optional) Yaw rate expo factor | $-$ |
| <a id="RO_YAW_SUPEXPO"></a>[RO_YAW_SUPEXPO](../advanced_config/parameter_reference.md#RO_YAW_SUPEXPO) | (Optional) Yaw rate super expo factor | $-$ |
### Ackermann Specific
@@ -172,14 +129,12 @@ You can now continue the configuration process with [rate tuning](rate_tuning.md
### Differential Specific
| 매개변수 | 설명 | Unit |
| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------ | ---- |
| <a id="RD_WHEEL_TRACK"></a>[RD_WHEEL_TRACK](../advanced_config/parameter_reference.md#RD_WHEEL_TRACK) | Wheel track | $m$ |
| <a id="RD_YAW_STK_GAIN"></a>[RD_YAW_STK_GAIN](../advanced_config/parameter_reference.md#RD_YAW_STK_GAIN) | (Optional) Yaw stick gain for Manual mode | $-$ |
| 매개변수 | 설명 | Unit |
| ----------------------------------------------------------------------------------------------------------------------------------------------- | ----------- | ---- |
| <a id="RD_WHEEL_TRACK"></a>[RD_WHEEL_TRACK](../advanced_config/parameter_reference.md#RD_WHEEL_TRACK) | Wheel track | m |
### Mecanum Specific
| 매개변수 | 설명 | Unit |
| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------ | ---- |
| <a id="RM_WHEEL_TRACK"></a>[RM_WHEEL_TRACK](../advanced_config/parameter_reference.md#RM_WHEEL_TRACK) | Wheel track | $m$ |
| <a id="RM_YAW_STK_GAIN"></a>[RM_YAW_STK_GAIN](../advanced_config/parameter_reference.md#RM_YAW_STK_GAIN) | (Optional) Yaw stick gain for Manual mode | $-$ |
| 매개변수 | 설명 | Unit |
| ----------------------------------------------------------------------------------------------------------------------------------------------- | ----------- | ---- |
| <a id="RM_WHEEL_TRACK"></a>[RM_WHEEL_TRACK](../advanced_config/parameter_reference.md#RM_WHEEL_TRACK) | Wheel track | m |
+2 -2
View File
@@ -20,7 +20,7 @@ To tune the velocity controller configure the following [parameters](../advanced
2. [RO_MAX_THR_SPEED](#RO_MAX_THR_SPEED) [m/s]: This parameter is used to calculate the feed-forward term of the closed loop speed control which linearly maps desired speeds to normalized motor commands.
As mentioned in the [Manual mode](../flight_modes_rover/manual.md#manual-mode) configuration , a good starting point is the observed ground speed when the rover drives at maximum throttle in [Manual mode](../flight_modes_rover/manual.md#manual-mode).
<a id="RA_SPEED_TUNING"></a>
<a id="RA_SPEED_TUNING"></a>
::: tip
To further tune this parameter:
@@ -94,7 +94,7 @@ These steps are only necessary if you are tuning/want to unlock the manual [Posi
The rover is now ready to drive in [Position mode](../flight_modes_rover/manual.md#position-mode) and the configuration can be continued with [position tuning](position_tuning.md).
## Velocity Controller Structure (Info Only)
## Attitude Controller Structure (Info Only)
This section provides additional information for developers and people with experience in control system design.
+6 -7
View File
@@ -33,17 +33,16 @@ The logging system is configured by default to collect sensible logs for [flight
Logging may further be configured using the [SD Logging](../advanced_config/parameter_reference.md#sd-logging) parameters.
변경할 가능성이 높은 매개변수가 아래에 설명되어 있습니다.
| 매개변수 | 설명 |
| --------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| [SDLOG_MODE](../advanced_config/parameter_reference.md#SDLOG_MODE) | Logging Mode. Defines when logging starts and stops.<br />- `0`: Log when armed until disarm (default).<br />- `1`: Log from boot until disarm.<br />- `2`: Log from boot until shutdown.<br />- `3`: Log based on the [AUX1 RC channel](../advanced_config/parameter_reference.md#RC_MAP_AUX1).<br />- `4`: Log from first armed until shutdown. |
| [SDLOG_BACKEND](../advanced_config/parameter_reference.md#SDLOG_BACKEND) | Logging Backend (bitmask). Setting a bit enables the corresponding backend. If no backend is selected, the logger is disabled.<br />- bit `0`: SD card logging.</br >- bit `1`: Mavlink logging. |
| [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) | 로깅 프로파일. Use this to enable less common logging/analysis (e.g. for EKF2 replay, high rate logging for PID & filter tuning, thermal temperature calibration). |
| [SDLOG_MISSION](../advanced_config/parameter_reference.md#SDLOG_MISSION) | Create very small additional "Mission Log".<br>This log can _not_ be used with [Flight Review](../log/flight_log_analysis.md#flight-review-online-tool), but is useful when you need a small log for geotagging or regulatory compliance. |
| 매개변수 | 설명 |
| --------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| [SDLOG_MODE](../advanced_config/parameter_reference.md#SDLOG_MODE) | Logging Mode. Defines when logging starts and stops.<br />- `-1`: Logging disabled.<br />- `0`: Log when armed until disarm (default).<br />- `1`: Log from boot until disarm.<br />- `2`: Log from boot until shutdown.<br />- `3`: Log based on the [AUX1 RC channel](../advanced_config/parameter_reference.md#RC_MAP_AUX1).<br />- `4`: Log from first armed until shutdown. |
| [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) | 로깅 프로파일. Use this to enable less common logging/analysis (e.g. for EKF2 replay, high rate logging for PID & filter tuning, thermal temperature calibration). |
| [SDLOG_MISSION](../advanced_config/parameter_reference.md#SDLOG_MISSION) | Create very small additional "Mission Log".<br>This log can _not_ be used with [Flight Review](../log/flight_log_analysis.md#flight-review-online-tool), but is useful when you need a small log for geotagging or regulatory compliance. |
Useful settings for specific cases:
- Raw sensor data for comparison: [SDLOG_MODE=1](../advanced_config/parameter_reference.md#SDLOG_MODE) and [SDLOG_PROFILE=64](../advanced_config/parameter_reference.md#SDLOG_PROFILE).
- Disabling logging altogether: [SDLOG_BACKEND=`0`](../advanced_config/parameter_reference.md#SDLOG_BACKEND)
- Disabling logging altogether: [SDLOG_MODE=`-1`](../advanced_config/parameter_reference.md#SDLOG_MODE)
### Logger module
+2 -21
View File
@@ -2,32 +2,13 @@
PX4 typically runs on flight controllers that include an IMU, such as the Pixhawk series, and fuse the sensor data along with GNSS information in the EKF2 estimator to determine vehicle attitude, heading, position, and velocity.
However PX4 can also use some INS devices as either sources of raw data, or as an external estimator, replacing EKF2.
However PX4 can also use some INS devices as either sources of raw data, or as an external estimator, replacing the EKF.
## Supported INS Systems
INS systems that can be used as a replacement for EKF2 in PX4:
Systems that can be used in this way include:
- [InertialLabs](../sensor/inertiallabs.md)
- [VectorNav](../sensor/vectornav.md): IMU/AHRS, GNSS/INS, Dual GNSS/INS systems that can be used as an external INS or as a source of raw sensor data.
## PX4 Firmware
The driver module for your INS system may not be included in the PX4 firmware for your flight controller by default.
You can check by searching the [default.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/fmu-v6c/default.px4board#L25) configuration file for your target board for either:
- `CONFIG_COMMON_INS`, which includes drivers for [all INS systems](https://github.com/PX4/PX4-Autopilot/blob/main/src/drivers/ins/Kconfig).
- The key for the particular INS system you are using, such as:
- `CONFIG_DRIVERS_INS_ILABS`
- `CONFIG_DRIVERS_INS_MICROSTRAIN`
- `CONFIG_DRIVERS_INS_VECTORNAV`
If the required key is not present you can include the module in firmware by adding the key to the `default.px4board` file, or using the [kconfig board configuration tool](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) and then select the driver you want (`Drivers -> INS`).
Note that if you're working on a flight controller where flash memory is limited, you're better off installing just the modules you need.
You will then need to rebuild the firmware.
## Glossary
### Inertial Measurement Unit (IMU)
+55 -93
View File
@@ -71,24 +71,24 @@ To check that these are present on your flight controller:
3. Enter the following commands in the console:
```sh
pwm_out_sim status
```
```sh
pwm_out_sim status
```
```sh
sensor_baro_sim status
```
```sh
sensor_baro_sim status
```
```sh
sensor_gps_sim status
```
```sh
sensor_gps_sim status
```
```sh
sensor_mag_sim status
```
```sh
sensor_mag_sim status
```
::: tip
Note that when using SIH on real hardware you do not need to additionally enable the modules using their corresponding parameters ([SENS_EN_GPSSIM](../advanced_config/parameter_reference.md#SENS_EN_GPSSIM), [SENS_EN_BAROSIM](../advanced_config/parameter_reference.md#SENS_EN_BAROSIM), [SENS_EN_MAGSIM](../advanced_config/parameter_reference.md#SENS_EN_MAGSIM)).
::: tip
Note that when using SIH on real hardware you do not need to additionally enable the modules using their corresponding parameters ([SENS_EN_GPSSIM](../advanced_config/parameter_reference.md#SENS_EN_GPSSIM), [SENS_EN_BAROSIM](../advanced_config/parameter_reference.md#SENS_EN_BAROSIM), [SENS_EN_MAGSIM](../advanced_config/parameter_reference.md#SENS_EN_MAGSIM)).
:::
@@ -141,12 +141,12 @@ To set up/start SIH:
1. Connect the flight controller to the desktop computer with a USB cable.
2. Open QGroundControl and wait for the flight controller too boot and connect.
3. Open [Vehicle Setup > Airframe](../config/airframe.md) then select the desired frame:
- [SIH Quadcopter X](../airframes/airframe_reference.md#copter_simulation_sih_quadcopter_x)
- **SIH Hexacopter X** (currently only has an airframe for SITL to safe flash so on flight control hardware it has to be manually configured equivalently).
- [SIH plane AERT](../airframes/airframe_reference.md#plane_simulation_sih_plane_aert)
- [SIH Tailsitter Duo](../airframes/airframe_reference.md#vtol_simulation_sih_tailsitter_duo)
- [SIH Standard VTOL QuadPlane](../airframes/airframe_reference.md#vtol_simulation_sih_standard_vtol_quadplane)
- [SIH Ackermann Rover](../airframes/airframe_reference.md#rover_rover_sih_rover_ackermann)
- [SIH Quadcopter X](../airframes/airframe_reference.md#copter_simulation_sih_quadcopter_x)
- **SIH Hexacopter X** (currently only has an airframe for SITL to safe flash so on flight control hardware it has to be manually configured equivalently).
- [SIH plane AERT](../airframes/airframe_reference.md#plane_simulation_sih_plane_aert)
- [SIH Tailsitter Duo](../airframes/airframe_reference.md#vtol_simulation_sih_tailsitter_duo)
- [SIH Standard VTOL QuadPlane](../airframes/airframe_reference.md#vtol_simulation_sih_standard_vtol_quadplane)
- [SIH Ackermann Rover](../airframes/airframe_reference.md#rover_rover_sih_rover_ackermann)
The autopilot will then reboot.
The `sih` module is started on reboot, and the vehicle should be displayed on the ground control station map.
@@ -172,19 +172,19 @@ To display the simulated vehicle:
3. Start jMAVSim by calling the script **jmavsim_run.sh** from a terminal:
```sh
./Tools/simulation/jmavsim/jmavsim_run.sh -q -d /dev/ttyACM0 -b 2000000 -o
```
```sh
./Tools/simulation/jmavsim/jmavsim_run.sh -q -d /dev/ttyACM0 -b 2000000 -o
```
where the flags are:
where the flags are:
- `-q` to allow the communication to _QGroundControl_ (optional).
- `-d` to start the serial device `/dev/ttyACM0` on Linux.
On macOS this would be `/dev/tty.usbmodem1`.
- `-b` to set the serial baud rate to `2000000`.
- `-o` to start jMAVSim in _display Only_ mode (i.e. the physical engine is turned off and jMAVSim only displays the trajectory given by the SIH in real-time).
- add a flag `-a` to display an aircraft or `-t` to display a tailsitter.
If this flag is not present a quadrotor will be displayed by default.
- `-q` to allow the communication to _QGroundControl_ (optional).
- `-d` to start the serial device `/dev/ttyACM0` on Linux.
On macOS this would be `/dev/tty.usbmodem1`.
- `-b` to set the serial baud rate to `2000000`.
- `-o` to start jMAVSim in _display Only_ mode (i.e. the physical engine is turned off and jMAVSim only displays the trajectory given by the SIH in real-time).
- add a flag `-a` to display an aircraft or `-t` to display a tailsitter.
If this flag is not present a quadrotor will be displayed by default.
4. After few seconds, _QGroundControl_ can be opened again.
@@ -201,41 +201,41 @@ To run SIH as SITL:
1. Install the [PX4 Development toolchain](../dev_setup/dev_env.md).
2. Run the appropriate make command for each vehicle type (at the root of the PX4-Autopilot repository):
- Quadcopter
- Quadcopter
```sh
make px4_sitl sihsim_quadx
```
```sh
make px4_sitl sihsim_quadx
```
- Hexacopter
- Hexacopter
```sh
make px4_sitl sihsim_hex
```
```sh
make px4_sitl sihsim_hex
```
- Fixed-wing (plane)
- Fixed-wing (plane)
```sh
make px4_sitl sihsim_airplane
```
```sh
make px4_sitl sihsim_airplane
```
- XVert VTOL tailsitter
- XVert VTOL tailsitter
```sh
make px4_sitl sihsim_xvert
```
```sh
make px4_sitl sihsim_xvert
```
- 표준 VTOL
- 표준 VTOL
```sh
make px4_sitl sihsim_standard_vtol
```
```sh
make px4_sitl sihsim_standard_vtol
```
- Ackermann Rover
- Ackermann Rover
```sh
make px4_sitl sihsim_rover_ackermann
```
```sh
make px4_sitl sihsim_rover_ackermann
```
### Change Simulation Speed
@@ -328,44 +328,6 @@ For SIH as SITL (no FC):
For specific examples see the `_sihsim_` airframes in [ROMFS/px4fmu_common/init.d-posix/airframes](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d-posix/airframes/) (SIH as SITL) and [ROMFS/px4fmu_common/init.d/airframes](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d/airframes) (SIH on FC).
## Controlling Actuators in SIH
:::warning
If you want to control throttling actuators in SIH, make sure to remove propellers for safety.
:::
In some scenarios, it may be useful to control an actuator while running SIH. For example, you might want to verify that winches or grippers are functioning correctly by checking the servo responses.
To enable actuator control in SIH:
1. Configure PWM parameters in the airframe file:
Ensure your airframe file includes the necessary parameters to map PWM outputs to the correct channels.
For example, if a servo is connected to MAIN 3 and you want to map it to AUX1 on your RC, use the following command:
`param set-default PWM_MAIN_FUNC3 407`
You can find a full list of available values for `PWM_MAIN_FUNCn` [here](../advanced_config/parameter_reference.md#PWM_MAIN_FUNC1). In this case, `407` maps the MAIN 3 output to AUX1 on the RC.
Alternatively, you can use the [`PWM_AUX_FUNCn`](../advanced_config/parameter_reference.md#PWM_AUX_FUNC1) parameters.
You may also configure the output as desired:
- Disarmed PWM: ([`PWM_MAIN_DISn`](../advanced_config/parameter_reference.md#PWM_MAIN_DIS1) / [`PWM_AUX_DIS1`](../advanced_config/parameter_reference.md#PWM_AUX_DIS1))
- Minimum PWM ([`PWM_MAIN_MINn`](../advanced_config/parameter_reference.md#PWM_MAIN_MIN1) / [`PWM_AUX_MINn`](../advanced_config/parameter_reference.md#PWM_AUX_MIN1))
- Maximum PWM ([`PWM_MAIN_MAXn`](../advanced_config/parameter_reference.md#PWM_MAIN_MAX1) / [`PWM_AUX_MAXn`](../advanced_config/parameter_reference.md#PWM_AUX_MAX1))
2. Manually start the PWM output driver
For safety, the PWM driver is not started automatically in SIH. To enable it, run the following command in the MAVLink shell:
`pwm_out start`
And to disable it again:
`pwm_out stop`
## Dynamic Models
The dynamic models for the various vehicles are:
+5
View File
@@ -3,6 +3,11 @@
[Rotoye Batmon](https://rotoye.com/batmon/) is a kit for adding smart battery functionality to off-the-shelf Lithium-Ion and LiPo batteries.
독립형 장치로 또는 공장에서 조립된 스마트 배터리의 일부로 구입할 수 있습니다.
:::info
At time of writing you can only use Batmon by [building a custom branch of PX4](#build-px4-firmware).
Support in the codeline is pending [PR approval](https://github.com/PX4/PX4-Autopilot/pull/16723).
:::
![Rotoye Batmon Board](../../assets/hardware/smart_batteries/rotoye_batmon/smart-battery-rotoye.jpg)
![Pre-assembled Rotoye smart battery](../../assets/hardware/smart_batteries/rotoye_batmon/smart-battery-rotoye-pack.jpg)
-2
View File
@@ -28,5 +28,3 @@ These are run by the test team as part of release testing, and for more signific
- [MC_04 - Failsafe Testing](../test_cards/mc_04_failsafe_testing.md)
- [MC_05 - Indoor Flight (Manual Modes)](../test_cards/mc_05_indoor_flight_manual_modes.md)
- [MC_06 - Indoor Flight (Optical Flow)](../test_cards/mc_06_optical_flow.md)
- [MC_07 - VIO (Visual-Inertial Odometry)](../test_cards/mc_07_vio.md)
- [MC_08 - DSHOT ESC](../test_cards/mc_08_dshot.md)
+1 -11
View File
@@ -2,19 +2,11 @@
## Objective
To test that optical flow works as expected
To test that optical flow / external vision work as expected
## Preflight
Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation
([Setup Information here](../sensor/optical_flow.md))
Ensure there are no other sources of positioning besides optical flow
- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1`
- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0`
- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0`
- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `0`
Ensure that the drone can go into Altitude / Position flight mode while still on the ground
@@ -47,7 +39,5 @@ Ensure that the drone can go into Altitude / Position flight mode while still on
## 예상 결과
- 추력을 올릴 때 서서히 이륙한다
- Drone should hold altitude in Altitude Flight mode without wandering
- Drone should hold position within 1 meter in Position Flight mode without pilot moving sticks
- 위에 언급한 어떤 비행 모드에서도 떨림이 나타나서는 안됨
- 지면에 착륙시, 콥터가 지면에서 튀면 안됨
-52
View File
@@ -1,52 +0,0 @@
# Test MC_07 - VIO (Visual-Inertial Odometry)
## Objective
To test that external vision (VIO) works as expected
## Preflight
Disconnect all GPS / compasses and ensure vehicle is using VIO for navigation
Ensure that the drone can go into Altitude / Position flight mode while still on the ground
Ensure there are no other sources of positioning besides VIO:
- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `0`
- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0`
- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `15`
- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `0`
## Flight Tests
❏ Altitude flight mode
&nbsp;&nbsp;&nbsp;&nbsp;❏ Vertical position should hold current value with stick centered
&nbsp;&nbsp;&nbsp;&nbsp;❏ Pitch/Roll/Yaw response 1:1
&nbsp;&nbsp;&nbsp;&nbsp;❏ Throttle response set to climb/descent rate
❏ Position flight mode
&nbsp;&nbsp;&nbsp;&nbsp;❏ Horizontal position should hold current value with stick centered
&nbsp;&nbsp;&nbsp;&nbsp;❏ Vertical position should hold current value with stick centered
&nbsp;&nbsp;&nbsp;&nbsp;❏ Throttle response set to climb/descent rate
&nbsp;&nbsp;&nbsp;&nbsp;❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates
## 착륙
❏ Land in either Position or Altitude mode with the throttle below 40%
❏ Upon touching ground, copter should disarm automatically within 2 seconds (default: see [COM_DISARM_LAND](../advanced_config/parameter_reference.md#COM_DISARM_LAND))
## 예상 결과
- 추력을 올릴 때 서서히 이륙한다
- Drone should hold altitude in Altitude Flight mode without wandering
- Drone should hold position within 1 meter in Position Flight mode without pilot moving sticks
- 위에 언급한 어떤 비행 모드에서도 떨림이 나타나서는 안됨
- 지면에 착륙시, 콥터가 지면에서 튀면 안됨
-46
View File
@@ -1,46 +0,0 @@
# Test MC_08 - DSHOT ESC
## Objective
Regression test for DSHOT working with PX4
## Preflight
- Ensure vehicle is using a DSHOT ESC.
- Parameter [DSHOT_BIDIR_EN](../advanced_config/parameter_reference.md#DSHOT_BIDIR_EN) is enabled
- Parameter [DSHOT_TEL_CFG](../advanced_config/parameter_reference.md#DSHOT_TEL_CFG) is configured (if ESC supports telemetry)
- Parameter [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) has Debug (`5`) checked
## Flight Tests
❏ Stabilized Flight mode
&nbsp;&nbsp;&nbsp;&nbsp;❏ Takeoff in stabilized flight mode to ensure correct motor spin
&nbsp;&nbsp;&nbsp;&nbsp;❏ Pitch/Roll/Yaw response 1:1
&nbsp;&nbsp;&nbsp;&nbsp;❏ Throttle response 1:1
❏ Position flight mode
&nbsp;&nbsp;&nbsp;&nbsp;❏ Horizontal position should hold current value with stick centered
&nbsp;&nbsp;&nbsp;&nbsp;❏ Vertical position should hold current value with stick centered
&nbsp;&nbsp;&nbsp;&nbsp;❏ Throttle response set to climb/descent rate
&nbsp;&nbsp;&nbsp;&nbsp;❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates
## 착륙
❏ Land in either Position or Altitude mode with the throttle below 40%
❏ Upon touching ground, copter should disarm automatically within 2 seconds (default: see [COM_DISARM_LAND](../advanced_config/parameter_reference.md#COM_DISARM_LAND))
## 예상 결과
- Download flight logs
- Load into Data Plot Juggler
- Ensure data is logged for esc_status/esc.0x/esc_rpm
![Reference frames](../../assets/test_cards/dshot_log_output.png)
-2
View File
@@ -843,8 +843,6 @@
- [Тест MC_04 - Тестування відмовостійкості](test_cards/mc_04_failsafe_testing.md)
- [Test MC_05 - Manual Modes (Inside)](test_cards/mc_05_indoor_flight_manual_modes.md)
- [Test MC_06 - Optical Flow (Inside)](test_cards/mc_06_optical_flow.md)
- [Test MC_07 - VIO (Inside)](test_cards/mc_07_vio.md)
- [Test MC_08 - DSHOT ESC](test_cards/mc_08_dshot.md)
- [Модульні Тести](test_and_ci/unit_tests.md)
- [Fuzz Tests](test_and_ci/fuzz_tests.md)
- [Безперервна інтеграція](test_and_ci/continous_integration.md)
+2 -29
View File
@@ -95,8 +95,6 @@ NuttX має інтегрований інтерпретатор оболонк
Найкращий спосіб змінити запуск системи - це ввести [нову конфігурацію планера](../dev_airframes/adding_a_new_frame.md).
Файл конфігурації планеру може бути включений у прошивку або на SD карту.
#### Dynamic customization
Якщо вам потрібно "підлаштувати" конфігурацію що існує, наприклад запустити один або більше застосунків або встановити значення кількох параметрів, можна вказати це створивши два файли у директорії `/etc/` на SD картці:
- [/etc/config.txt](#customizing-the-configuration-config-txt): modify parameter values
@@ -113,7 +111,7 @@ NuttX має інтегрований інтерпретатор оболонк
Ці файли згадуються в коді PX4 як `/fs/microsd/etc/config.txt` та `/fs/microsd/etc/extras.txt`, де коренева директорія microSD карти визначається шляхом `/fs/microsd`.
:::
##### Налаштування конфігурації (config.txt)
#### Налаштування конфігурації (config.txt)
Файл `config.txt` можна використовувати для зміни параметрів.
Він завантажується після того, як головна система була налаштована та _перед тим_ як завантажена.
@@ -125,7 +123,7 @@ param set-default PWM_MAIN_DIS3 1000
param set-default PWM_MAIN_MIN3 1120
```
##### Запуск додаткових застосунків (extras.txt)
#### Запуск додаткових застосунків (extras.txt)
`extras.txt` можна використовувати для запуску додаткових застосунків після завантаження основної системи.
Зазвичай це будуть контролери корисного навантаження або подібні необов'язкові користувацькі компоненти.
@@ -152,28 +150,3 @@ param set-default PWM_MAIN_MIN3 1120
mandatory_app start # Will abort boot if mandatory_app is unknown or fails
```
#### Additional customization
In rare cases where the desired setup cannot be achieved through frame configuration or dynamic customization,
you can add a script that will be contained in the binary.
**Note**: In almost all cases, you should use a frame configuration. This method should only be used for
edge-cases such as customizing `cannode` based boards.
- Add a new init script in `boards/<vendor>/<board>/init` that will run during board startup. Наприклад:
```sh
# File: boards/<vendor>/<board>/init/rc.additional
param set-default <param> <value>
```
- Add a new board variant in `boards/<vendor>/<board>/<variant>.px4board` that includes the additional script. Наприклад:
```sh
# File: boards/<vendor>/<board>/var.px4board
CONFIG_BOARD_ADDITIONAL_INIT="rc.additional"
```
- Compile the firmware with your new variant by appending the variant name to the compile target. Наприклад:
```sh
make <target>_var
```
+11 -56
View File
@@ -27,18 +27,10 @@
That is the minimum setup to use the rover in [Manual mode](../flight_modes_rover/manual.md#manual-mode).
:::info
The rest of the tuning on this page is not mandatory for [Manual mode](../flight_modes_rover/manual.md#manual-mode), but it will have an effect on the behaviour of the rover.
:::
:::warning
Do not skip the rest of this setup if you intend to use more sophisticated modes!
All parameters will be mandatory for all subsequent modes, except those tagged as `(Optional)`.
:::
## Geometric Parameters
First, we set up the geometric parameters of the rover:
Manual mode is also affected by (optional) acceleration/deceleration limits set using the geometric described below.
These limits are mandatory for all other modes.
![Geometric parameters](../../assets/config/rover/geometric_parameters.png)
@@ -50,7 +42,7 @@ Navigate to [Parameters](../advanced_config/parameters.md) in QGroundControl and
2. [RA_MAX_STR_ANG](#RA_MAX_STR_ANG) [deg]: Measure the maximum steering angle.
3. (Optional) [RA_STR_RATE_LIM](#RA_STR_RATE_LIM) [deg/s]: Maximum steering rate you want to allow for your rover.
::: tip
:::tip
This value depends on your rover and use case.
For bigger rovers there might be a mechanical limit that is easy to identify by steering the rover at a standstill and increasing
[RA_STR_RATE_LIM](#RA_STR_RATE_LIM) until you observe the steering rate to no longer be limited by the parameter.
@@ -59,7 +51,7 @@ Navigate to [Parameters](../advanced_config/parameters.md) in QGroundControl and
:::
::: warning
:::warning
A low maximum steering rate makes the rover worse at tracking steering setpoints, which can lead to a poor performance in the subsequent modes.
:::
@@ -84,7 +76,7 @@ Navigate to [Parameters](../advanced_config/parameters.md) in QGroundControl and
2. (Optional) [RO_ACCEL_LIM](#RO_ACCEL_LIM) [m/s^2]: Maximum acceleration you want to allow for your rover.
<a id="RO_ACCEL_LIM_CONSIDERATIONS"></a>
<a id="RO_ACCEL_LIM_CONSIDERATIONS"></a>
:::tip
Your rover has a maximum possible acceleration which is determined by the maximum torque the motor can supply.
@@ -117,39 +109,6 @@ Navigate to [Parameters](../advanced_config/parameters.md) in QGroundControl and
:::
## (Optional) Stick Input Mapping
Input shaping can be used to adjust the default linear mapping from stick inputs $\in [-1, 1]$ to normalized setpoints $\in [-1, 1]$. Applying this specifically to the steering input, can provide a smoother driving experience, by enabling the user to make small adjustments when the stick is close to the center, but still send large inputs when moving them to the edges.
We provide this input shaping through the super exponential function:
$$
\delta = \frac{(f \cdot x^3 + x(1-f)) \cdot (1-g)}{1-g \cdot |x|}
$$
with:
- $\delta \in [-1, 1]=$ Normalized steering setpoint.
- $x \in [-1, 1]=$ Normalized stick input.
- $f=$ [RO_YAW_EXPO](#RO_YAW_EXPO): `0` Purely linear input curve, `1` Purely cubic input curve.
- $g=$ [RO_YAW_SUPEXPO](#RO_YAW_SUPEXPO): `0` Pure Expo function, `0.7` reasonable shape enhancement for intuitive stick feel, `0.95` very strong bent input curve only near maxima have effect.
In [Manual mode](../flight_modes_rover/manual.md#manual-mode) we can additionally scale $\delta$ with an additional parameter $r$:
- Differential Rover: $r=$ [RD_YAW_STK_GAIN](#RD_YAW_STK_GAIN), which enables adjusting the slope of the input mapping. This leads to a normalized steering input $\hat{\delta} = \delta \cdot r \in$ [-[RD_YAW_STK_GAIN](#RD_YAW_STK_GAIN), [RD_YAW_STK_GAIN](#RD_YAW_STK_GAIN)].
- Mecanum Rover: $r=$ [RM_YAW_STK_GAIN](#RM_YAW_STK_GAIN), which enables adjusting the slope of the input mapping. This leads to a normalized steering input $\hat{\delta} = \delta \cdot r \in$ [-[RM_YAW_STK_GAIN](#RM_YAW_STK_GAIN), [RM_YAW_STK_GAIN](#RM_YAW_STK_GAIN)].
This scaling is useful to limit the normalized steering setpoint, if it is too aggresive for your rover in manual mode.
You can experiment with the relationships graphically using the [PX4 SuperExpo Rover calculator](https://www.desmos.com/calculator/gwm8lrlanx).
:::info
In [Acro](../flight_modes_rover/manual.md#acro-mode), [Stabilized](../flight_modes_rover/manual.md#stabilized-mode) and [Position](../flight_modes_rover/manual.md#position-mode) Mode, $\delta$ is instead scaled by $r=$ [RO_YAW_RATE_LIM](../advanced_config/parameter_reference.md#RO_MAX_THR_SPEED) for all rovers. This leads to a yaw rate setpoint $\dot{\psi} = \delta \cdot r \in$ [-[RO_YAW_RATE_LIM](../advanced_config/parameter_reference.md#RO_MAX_THR_SPEED), [RO_YAW_RATE_LIM](../advanced_config/parameter_reference.md#RO_MAX_THR_SPEED)]. This parameter is setup during [rate tuning](rate_tuning.md).
:::
:::info
The input shaping through [RO_YAW_EXPO](#RO_YAW_EXPO) and [RO_YAW_SUPEXPO](#RO_YAW_SUPEXPO) applies for all manual modes, while [RD_YAW_STK_GAIN](#RD_YAW_STK_GAIN)/[RM_YAW_STK_GAIN](#RM_YAW_STK_GAIN) only affects full manual mode.
:::
You can now continue the configuration process with [rate tuning](rate_tuning.md).
## Огляд параметрів
@@ -159,8 +118,6 @@ You can now continue the configuration process with [rate tuning](rate_tuning.md
| <a id="RO_MAX_THR_SPEED"></a>[RO_MAX_THR_SPEED](../advanced_config/parameter_reference.md#RO_MAX_THR_SPEED) | Speed the rover drives at maximum throttle | $m/s$ |
| <a id="RO_ACCEL_LIM"></a>[RO_ACCEL_LIM](../advanced_config/parameter_reference.md#RO_ACCEL_LIM) | (Optional) Maximum allowed acceleration | $m/s^2$ |
| <a id="RO_DECEL_LIM"></a>[RO_DECEL_LIM](../advanced_config/parameter_reference.md#RO_DECEL_LIM) | (Optional) Maximum allowed deceleration | $m/s^2$ |
| <a id="RO_YAW_EXPO"></a>[RO_YAW_EXPO](../advanced_config/parameter_reference.md#RO_YAW_EXPO) | (Optional) Yaw rate expo factor | $-$ |
| <a id="RO_YAW_SUPEXPO"></a>[RO_YAW_SUPEXPO](../advanced_config/parameter_reference.md#RO_YAW_SUPEXPO) | (Optional) Yaw rate super expo factor | $-$ |
### Ackermann Specific
@@ -172,14 +129,12 @@ You can now continue the configuration process with [rate tuning](rate_tuning.md
### Differential Specific
| Параметр | Опис | Unit |
| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------ | ---- |
| <a id="RD_WHEEL_TRACK"></a>[RD_WHEEL_TRACK](../advanced_config/parameter_reference.md#RD_WHEEL_TRACK) | Wheel track | $m$ |
| <a id="RD_YAW_STK_GAIN"></a>[RD_YAW_STK_GAIN](../advanced_config/parameter_reference.md#RD_YAW_STK_GAIN) | (Optional) Yaw stick gain for Manual mode | $-$ |
| Параметр | Опис | Unit |
| ----------------------------------------------------------------------------------------------------------------------------------------------- | ----------- | ---- |
| <a id="RD_WHEEL_TRACK"></a>[RD_WHEEL_TRACK](../advanced_config/parameter_reference.md#RD_WHEEL_TRACK) | Wheel track | m |
### Mecanum Specific
| Параметр | Опис | Unit |
| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------ | ---- |
| <a id="RM_WHEEL_TRACK"></a>[RM_WHEEL_TRACK](../advanced_config/parameter_reference.md#RM_WHEEL_TRACK) | Wheel track | $m$ |
| <a id="RM_YAW_STK_GAIN"></a>[RM_YAW_STK_GAIN](../advanced_config/parameter_reference.md#RM_YAW_STK_GAIN) | (Optional) Yaw stick gain for Manual mode | $-$ |
| Параметр | Опис | Unit |
| ----------------------------------------------------------------------------------------------------------------------------------------------- | ----------- | ---- |
| <a id="RM_WHEEL_TRACK"></a>[RM_WHEEL_TRACK](../advanced_config/parameter_reference.md#RM_WHEEL_TRACK) | Wheel track | m |
+2 -2
View File
@@ -20,7 +20,7 @@ To tune the velocity controller configure the following [parameters](../advanced
2. [RO_MAX_THR_SPEED](#RO_MAX_THR_SPEED) [m/s]: This parameter is used to calculate the feed-forward term of the closed loop speed control which linearly maps desired speeds to normalized motor commands.
As mentioned in the [Manual mode](../flight_modes_rover/manual.md#manual-mode) configuration , a good starting point is the observed ground speed when the rover drives at maximum throttle in [Manual mode](../flight_modes_rover/manual.md#manual-mode).
<a id="RA_SPEED_TUNING"></a>
<a id="RA_SPEED_TUNING"></a>
::: tip
To further tune this parameter:
@@ -94,7 +94,7 @@ These steps are only necessary if you are tuning/want to unlock the manual [Posi
The rover is now ready to drive in [Position mode](../flight_modes_rover/manual.md#position-mode) and the configuration can be continued with [position tuning](position_tuning.md).
## Velocity Controller Structure (Info Only)
## Attitude Controller Structure (Info Only)
This section provides additional information for developers and people with experience in control system design.

Some files were not shown because too many files have changed in this diff Show More