Compare commits

..

4 Commits

Author SHA1 Message Date
Junwoo Hwang 4b33632615 Only command Gripper grab when we are actually initializing gripper
- Previously, on every parameter update, gripper grab was being
commanded
- This commit narrows that scope to only when we are actually
initializing the gripper
2022-10-07 12:23:56 +02:00
Junwoo Hwang 5b94731f35 payload_deliverer & gripper: Improve intermediate state & vcmd_ack
Gripper:
- Don't command gripper (via uORB `gripper` topic, which maps into an
actuator via Control Allocation) if we are already at the state we want
(e.g. Grabbed / Released) or in the intermediate state to the state we
want -> This prevents spamming on `gripper` topic

Payload Deliverer:
- Add read-once function for Gripper's released / grabbed state
- Send vehicle_command_ack for both release/grab actions.

TODO: target_system & target_component for the released/grabbed vcmd_ack
is incomplete, since we are not keeping track of the vehicle_command
that corresponds to this. This needs to be dealt with in the future, not
sure what the best solution it is for now.

Possible solutions:
- Queue-ing the vehicle command?
- Tying the gripper's action to specific vehicle command one-on-one, to make sure if we send multiple vehicle commands, we know
which command resulted in the action exactly?)
2022-09-30 11:39:40 +02:00
Junwoo Hwang 7f95c6486f Fix wrong GRIPPER_ACTION conversion from floating point to int32_t
- Due to the MAVLink spec, we actually just convert enums into floating
point, so in PX4 we need to convert the float directly into integer as
well (although there can be precision issues on large numbers)
- This is a limitation in MAVLink spec, and should hopefully be
changed in MAVLink v2
2022-09-30 10:36:15 +02:00
Junwoo Hwang 634b650b9c [NEED-UPSTREAMING] Send IN_PROGRESS command ack when actuating gripper
- This hopefully then alerts the GCS that the command is getting
processed
- Referenced commander's `handle_command` function to implement this. As
it seems like GCS needs the acknowledgement of the command being
processed to execute such commands properly
- Also send FAILED command ack if we can't actuate the gripper
2022-09-30 10:33:50 +02:00
676 changed files with 26681 additions and 24774 deletions
+7
View File
@@ -69,18 +69,24 @@ pipeline {
"matek_h743-slim_default",
"matek_h743_default",
"modalai_fc-v1_default",
"modalai_fc-v1_rtps",
"modalai_fc-v2_default",
"modalai_voxl2-io_default",
"mro_ctrl-zero-f7_default",
"mro_ctrl-zero-f7-oem_default",
"mro_ctrl-zero-h7-oem_default",
"mro_ctrl-zero-h7-oem_rtps",
"mro_ctrl-zero-h7_default",
"mro_ctrl-zero-h7_rtps",
"mro_pixracerpro_default",
"mro_pixracerpro_rtps",
"mro_x21-777_default",
"mro_x21_default",
"nxp_fmuk66-e_default",
"nxp_fmuk66-e_rtps",
"nxp_fmuk66-e_socketcan",
"nxp_fmuk66-v3_default",
"nxp_fmuk66-v3_rtps",
"nxp_fmuk66-v3_socketcan",
"nxp_fmurt1062-v1_default",
"nxp_ucans32k146_canbootloader",
@@ -98,6 +104,7 @@ pipeline {
"px4_fmu-v5_debug",
"px4_fmu-v5_default",
"px4_fmu-v5_lto",
"px4_fmu-v5_rtps",
"px4_fmu-v5_stackcheck",
"px4_fmu-v5_uavcanv0periph",
"px4_fmu-v5x_default",
+1 -1
View File
@@ -937,7 +937,7 @@ void printTopics() {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener vehicle_odometry" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener vehicle_rates_setpoint" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener vehicle_status" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener failsafe_flags" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener vehicle_status_flags" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener vtol_vehicle_status" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener yaw_estimator_status" || true'
}
+1
View File
@@ -23,6 +23,7 @@ jobs:
"shellcheck_all",
"NO_NINJA_BUILD=1 px4_fmu-v5_default",
"NO_NINJA_BUILD=1 px4_sitl_default",
"BUILD_MICRORTPS_AGENT=1 px4_sitl_rtps",
"airframe_metadata",
"module_documentation",
"parameters_metadata",
-44
View File
@@ -1,44 +0,0 @@
name: Failsafe Simulator Build
on:
push:
branches:
- 'main'
pull_request:
branches:
- '*'
jobs:
build:
runs-on: ubuntu-latest
defaults:
run:
shell: bash
strategy:
fail-fast: false
matrix:
check: [
"failsafe_web",
]
container:
image: px4io/px4-dev-nuttx-focal:2021-09-08
options: --privileged --ulimit core=-1 --security-opt seccomp=unconfined
steps:
- uses: actions/checkout@v1
with:
token: ${{ secrets.ACCESS_TOKEN }}
- name: check environment
run: |
export
ulimit -a
- name: install emscripten
run: |
git clone https://github.com/emscripten-core/emsdk.git _emscripten_sdk
cd _emscripten_sdk
./emsdk install latest
./emsdk activate latest
- name: ${{matrix.check}}
run: |
. ./_emscripten_sdk/emsdk_env.sh
make ${{matrix.check}}
+30 -4
View File
@@ -116,7 +116,7 @@ jobs:
ls -ls *
# TODO: deploy graph_px4_sitl.json to S3 px4-travis:Firmware/master/
ROS2_msgs:
micrortps_agent:
runs-on: ubuntu-latest
container: px4io/px4-dev-base-focal:2021-09-08
steps:
@@ -124,8 +124,34 @@ jobs:
with:
token: ${{ secrets.ACCESS_TOKEN }}
- name: PX4 ROS2 msgs
- name: microRTPS agent
run: |
make px4_sitl_rtps
git clone https://github.com/PX4/micrortps_agent.git
cp -R build/px4_sitl_rtps/src/modules/micrortps_bridge/micrortps_agent/* micrortps_agent
ROS_msgs:
runs-on: ubuntu-latest
container: px4io/px4-dev-base-focal:2021-09-08
steps:
- uses: actions/checkout@v1
with:
token: ${{ secrets.ACCESS_TOKEN }}
- name: PX4 ROS msgs
run: |
git clone https://github.com/PX4/px4_msgs.git
rm px4_msgs/msg/*.msg
cp msg/*.msg px4_msgs/msg/
python3 msg/tools/uorb_to_ros_msgs.py msg/ px4_msgs/msg/
ROS2_bridge:
runs-on: ubuntu-latest
container: px4io/px4-dev-base-focal:2021-09-08
steps:
- uses: actions/checkout@v1
with:
token: ${{ secrets.ACCESS_TOKEN }}
- name: PX4 ROS2 bridge
run: |
git clone https://github.com/PX4/px4_ros_com.git
./msg/tools/uorb_to_ros_urtps_topics.py -i msg/tools/urtps_bridge_topics.yaml -o px4_ros_com/templates/urtps_bridge_topics.yaml
+8 -6
View File
@@ -9,15 +9,19 @@
[submodule "Tools/simulation/jmavsim/jMAVSim"]
path = Tools/simulation/jmavsim/jMAVSim
url = https://github.com/PX4/jMAVSim.git
branch = main
branch = master
[submodule "Tools/simulation/gazebo/sitl_gazebo"]
path = Tools/simulation/gazebo/sitl_gazebo
url = https://github.com/PX4/PX4-SITL_gazebo.git
branch = main
branch = master
[submodule "src/drivers/gps/devices"]
path = src/drivers/gps/devices
url = https://github.com/PX4/PX4-GPSDrivers.git
branch = main
branch = master
[submodule "src/modules/micrortps_bridge/micro-CDR"]
path = src/modules/micrortps_bridge/micro-CDR
url = https://github.com/PX4/Micro-CDR.git
branch = master
[submodule "platforms/nuttx/NuttX/nuttx"]
path = platforms/nuttx/NuttX/nuttx
url = https://github.com/PX4/NuttX.git
@@ -49,7 +53,6 @@
[submodule "src/lib/events/libevents"]
path = src/lib/events/libevents
url = https://github.com/mavlink/libevents.git
branch = main
[submodule "src/lib/crypto/libtomcrypt"]
path = src/lib/crypto/libtomcrypt
url = https://github.com/PX4/libtomcrypt.git
@@ -60,5 +63,4 @@
branch = px4
[submodule "src/modules/microdds_client/Micro-XRCE-DDS-Client"]
path = src/modules/microdds_client/Micro-XRCE-DDS-Client
url = https://github.com/PX4/Micro-XRCE-DDS-Client.git
branch = px4
url = https://github.com/eProsima/Micro-XRCE-DDS-Client.git
+3 -3
View File
@@ -6,11 +6,11 @@ CONFIG:
buildType: RelWithDebInfo
settings:
CONFIG: px4_sitl_default
px4_sitl_nolockstep:
short: px4_sitl_nolockstep
px4_sitl_rtps:
short: px4_sitl_rtps
buildType: RelWithDebInfo
settings:
CONFIG: px4_sitl_nolockstep
CONFIG: px4_sitl_rtps
px4_sitl_asan:
short: px4_sitl (AddressSanitizer)
buildType: AddressSanitizer
+1 -1
View File
@@ -410,7 +410,7 @@ if(BUILD_TESTING)
include(gtest)
add_custom_target(test_results
COMMAND GTEST_COLOR=1 ${CMAKE_CTEST_COMMAND} --output-on-failure -T Test -R \"${TESTFILTER}\" USES_TERMINAL
COMMAND GTEST_COLOR=1 ${CMAKE_CTEST_COMMAND} --output-on-failure -T Test -R ${TESTFILTER} USES_TERMINAL
DEPENDS
px4
examples__dyn_hello
+1
View File
@@ -829,6 +829,7 @@ RECURSIVE = YES
# run.
EXCLUDE = @CMAKE_SOURCE_DIR@/src/modules/uavcan/libuavcan \
@CMAKE_SOURCE_DIR@/src/modules/micrortps_bridge/micro-CDR \
@CMAKE_SOURCE_DIR@/src/examples \
@CMAKE_SOURCE_DIR@/src/templates
Vendored
+154 -34
View File
@@ -13,6 +13,76 @@ pipeline {
}
}
parallel {
// stage('Catkin build on ROS workspace') {
// agent {
// docker {
// image 'px4io/px4-dev-ros-melodic:2021-08-18'
// args '-e CCACHE_BASEDIR=$WORKSPACE -v ${CCACHE_DIR}:${CCACHE_DIR}:rw -e HOME=$WORKSPACE'
// }
// }
// steps {
// sh 'ls -l'
// sh '''#!/bin/bash -l
// echo $0;
// mkdir -p catkin_ws/src;
// cd catkin_ws;
// git -C ${WORKSPACE}/catkin_ws/src/Firmware submodule update --init --recursive --force Tools/simulation/gazebo/sitl_gazebo
// git clone --recursive ${WORKSPACE}/catkin_ws/src/Firmware/Tools/simulation/gazebo/sitl_gazebo src/mavlink_sitl_gazebo;
// git -C ${WORKSPACE}/catkin_ws/src/Firmware fetch --tags;
// source /opt/ros/melodic/setup.bash;
// export PYTHONPATH=/opt/ros/$ROS_DISTRO/lib/python2.7/dist-packages:/usr/lib/python2.7/dist-packages:/usr/local/lib/python2.7/dist-packages;
// catkin init;
// catkin build -j$(nproc) -l$(nproc);
// '''
// // test if the binary was correctly installed and runs using 'mavros_posix_sitl.launch'
// sh '''#!/bin/bash -l
// echo $0;
// source catkin_ws/devel/setup.bash;
// rostest px4 pub_test.launch;
// '''
// }
// post {
// always {
// sh 'rm -rf catkin_ws'
// }
// failure {
// archiveArtifacts(allowEmptyArchive: false, artifacts: '.ros/**/*.xml, .ros/**/*.log')
// }
// }
// options {
// checkoutToSubdirectory('catkin_ws/src/Firmware')
// }
// }
stage('Colcon build on ROS2 workspace') {
agent {
docker {
image 'px4io/px4-dev-ros2-foxy:2021-08-18'
args '-e CCACHE_BASEDIR=$WORKSPACE -v ${CCACHE_DIR}:${CCACHE_DIR}:rw -e HOME=$WORKSPACE'
}
}
steps {
sh 'ls -l'
sh '''#!/bin/bash -l
echo $0;
unset ROS_DISTRO;
mkdir -p colcon_ws/src;
cd colcon_ws;
git -C ${WORKSPACE}/colcon_ws/src/Firmware submodule update --init --recursive --force Tools/simulation/gazebo/sitl_gazebo;
git -C ${WORKSPACE}/colcon_ws/src/Firmware fetch --tags;
source /opt/ros/foxy/setup.sh;
colcon build --event-handlers console_direct+ --symlink-install;
'''
}
post {
always {
sh 'rm -rf colcon_ws'
}
}
options {
checkoutToSubdirectory('colcon_ws/src/Firmware')
}
}
stage('Airframe') {
agent {
@@ -79,7 +149,7 @@ pipeline {
docker { image 'px4io/px4-dev-base-focal:2021-08-18' }
}
steps {
sh 'mkdir -p build/msg_docs; ./Tools/msg/generate_msg_docs.py -d build/msg_docs'
sh 'mkdir -p build/msg_docs; ./msg/tools/generate_msg_docs.py -d build/msg_docs'
dir('build') {
archiveArtifacts(artifacts: 'msg_docs/*.md')
stash includes: 'msg_docs/*.md', name: 'msg_documentation'
@@ -92,35 +162,6 @@ pipeline {
}
}
stage('failsafe docs') {
agent {
docker { image 'px4io/px4-dev-base-focal:2021-08-18' }
}
steps {
sh '''#!/bin/bash -l
echo $0;
git clone https://github.com/emscripten-core/emsdk.git _emscripten_sdk;
cd _emscripten_sdk;
./emsdk install latest;
./emsdk activate latest;
. ./_emscripten_sdk/emsdk_env.sh;
make failsafe_web;
cd build/px4_sitl_default_failsafe_web;
mkdir -p failsafe_sim;
cp index.* parameters.json failsafe_sim;
'''
dir('build/px4_sitl_default_failsafe_web') {
archiveArtifacts(artifacts: 'failsafe_sim/*')
stash includes: 'failsafe_sim/*', name: 'failsafe_sim'
}
}
post {
always {
sh 'make distclean; git clean -ff -x -d .'
}
}
}
stage('uORB graphs') {
agent {
docker {
@@ -162,7 +203,6 @@ pipeline {
unstash 'metadata_parameters'
unstash 'metadata_module_documentation'
unstash 'msg_documentation'
unstash 'failsafe_sim'
unstash 'uorb_graph'
withCredentials([usernamePassword(credentialsId: 'px4buildbot_github_personal_token', passwordVariable: 'GIT_PASS', usernameVariable: 'GIT_USER')]) {
sh('git clone https://${GIT_USER}:${GIT_PASS}@github.com/PX4/PX4-user_guide.git')
@@ -171,7 +211,6 @@ pipeline {
sh('cp -R modules/*.md PX4-user_guide/en/modules/')
sh('cp -R graph_*.json PX4-user_guide/.vuepress/public/en/middleware/')
sh('cp -R msg_docs/*.md PX4-user_guide/en/msg_docs/')
sh('cp -R failsafe_sim/* PX4-user_guide/.vuepress/public/en/config/failsafe')
sh('cd PX4-user_guide; git status; git add .; git commit -a -m "Update PX4 Firmware metadata `date`" || true')
sh('cd PX4-user_guide; git push origin main || true')
sh('rm -rf PX4-user_guide')
@@ -218,6 +257,37 @@ pipeline {
}
}
stage('microRTPS agent') {
agent {
docker { image 'px4io/px4-dev-base-focal:2021-08-18' }
}
steps {
sh('export')
sh('git fetch --all --tags')
sh('make distclean; git clean -ff -x -d .')
sh('make px4_sitl_rtps')
withCredentials([usernamePassword(credentialsId: 'px4buildbot_github_personal_token', passwordVariable: 'GIT_PASS', usernameVariable: 'GIT_USER')]) {
sh("git clone https://${GIT_USER}:${GIT_PASS}@github.com/PX4/micrortps_agent.git -b ${BRANCH_NAME}")
sh("rm -rf micrortps_agent/src micrortps_agent/idl")
sh('cp -R build/px4_sitl_rtps/src/modules/micrortps_bridge/micrortps_agent/* micrortps_agent')
sh('cd micrortps_agent; git status; git add src; git commit -a -m "Update microRTPS agent source code `date`" || true')
sh('cd micrortps_agent; git push origin ${BRANCH_NAME} || true')
sh('cd micrortps_agent; git status; git add idl; git commit -a -m "Update IDL definitions `date`" || true')
sh('cd micrortps_agent; git push origin ${BRANCH_NAME} || true')
sh('cd micrortps_agent; git status; git add CMakeLists.txt; git commit -a -m "Update CMakeLists.txt `date`" || true')
sh('cd micrortps_agent; git push origin ${BRANCH_NAME} || true')
sh('rm -rf micrortps_agent')
}
}
when {
anyOf {
branch 'main'
branch 'master' // should be removed, but in case there is something going on...
branch 'pr-jenkins' // for testing
}
}
}
stage('PX4 ROS msgs') {
agent {
docker { image 'px4io/px4-dev-base-focal:2021-08-18' }
@@ -228,16 +298,66 @@ pipeline {
withCredentials([usernamePassword(credentialsId: 'px4buildbot_github_personal_token', passwordVariable: 'GIT_PASS', usernameVariable: 'GIT_USER')]) {
sh("git clone https://${GIT_USER}:${GIT_PASS}@github.com/PX4/px4_msgs.git")
// 'main' branch
sh('rm -f px4_msgs/msg/*.msg')
sh('cp msg/*.msg px4_msgs/msg/')
sh('./msg/tools/uorb_to_ros_msgs.py msg/ px4_msgs/msg/')
sh('cd px4_msgs; git status; git add .; git commit -a -m "Update message definitions `date`" || true')
sh('cd px4_msgs; git push origin main || true')
// 'ros1' branch
sh('cd px4_msgs; git checkout ros1')
sh('./msg/tools/uorb_to_ros_msgs.py msg/ px4_msgs/msg/')
sh('cd px4_msgs; git status; git add .; git commit -a -m "Update message definitions `date`" || true')
sh('cd px4_msgs; git push origin ros1 || true')
sh('rm -rf px4_msgs')
}
}
when {
anyOf {
branch 'main'
branch 'master' // should be removed, but in case there is something going on...
branch 'pr-jenkins' // for testing
}
}
}
stage('PX4 ROS2 bridge') {
agent {
docker { image 'px4io/px4-dev-base-focal:2021-08-18' }
}
steps {
sh('export')
sh('make distclean; git clean -ff -x -d .')
withCredentials([usernamePassword(credentialsId: 'px4buildbot_github_personal_token', passwordVariable: 'GIT_PASS', usernameVariable: 'GIT_USER')]) {
sh("git clone https://${GIT_USER}:${GIT_PASS}@github.com/PX4/px4_ros_com.git -b ${BRANCH_NAME}")
// deploy uORB RTPS ID map
sh('./msg/tools/uorb_to_ros_urtps_topics.py -i msg/tools/urtps_bridge_topics.yaml -o px4_ros_com/templates/urtps_bridge_topics.yaml')
sh('cd px4_ros_com; git status; git add .; git commit -a -m "Update uORB RTPS ID map `date`" || true')
sh('cd px4_ros_com; git push origin ${BRANCH_NAME} || true')
// deploy uORB RTPS required tools
sh('cp msg/tools/uorb_rtps_classifier.py px4_ros_com/scripts/uorb_rtps_classifier.py')
sh('cp msg/tools/generate_microRTPS_bridge.py px4_ros_com/scripts/generate_microRTPS_bridge.py')
sh('cp msg/tools/px_generate_uorb_topic_files.py px4_ros_com/scripts/px_generate_uorb_topic_files.py')
sh('cp msg/tools/px_generate_uorb_topic_helper.py px4_ros_com/scripts/px_generate_uorb_topic_helper.py')
// deploy templates
sh('cp msg/templates/urtps/microRTPS_agent.cpp.em px4_ros_com/templates/microRTPS_agent.cpp.em')
sh('cp msg/templates/urtps/microRTPS_timesync.cpp.em px4_ros_com/templates/microRTPS_timesync.cpp.em')
sh('cp msg/templates/urtps/microRTPS_timesync.h.em px4_ros_com/templates/microRTPS_timesync.h.em')
sh('cp msg/templates/urtps/microRTPS_transport.cpp px4_ros_com/templates/microRTPS_transport.cpp')
sh('cp msg/templates/urtps/microRTPS_transport.h px4_ros_com/templates/microRTPS_transport.h')
sh('cp msg/templates/urtps/Publisher.cpp.em px4_ros_com/templates/Publisher.cpp.em')
sh('cp msg/templates/urtps/Publisher.h.em px4_ros_com/templates/Publisher.h.em')
sh('cp msg/templates/urtps/Subscriber.cpp.em px4_ros_com/templates/Subscriber.cpp.em')
sh('cp msg/templates/urtps/Subscriber.h.em px4_ros_com/templates/Subscriber.h.em')
sh('cp msg/templates/urtps/RtpsTopics.cpp.em px4_ros_com/templates/RtpsTopics.cpp.em')
sh('cp msg/templates/urtps/RtpsTopics.h.em px4_ros_com/templates/RtpsTopics.h.em')
sh('cd px4_ros_com; git status; git add .; git commit -a -m "Update uORB RTPS script tools `date`" || true')
sh('cd px4_ros_com; git push origin ${BRANCH_NAME} || true')
sh('rm -rf px4_msgs')
}
}
when {
anyOf {
branch 'main'
branch 'master' // should be removed, but in case there is something going on...
branch 'pr-jenkins' // for testing
}
}
}
+30 -16
View File
@@ -172,6 +172,11 @@ ifdef PYTHON_EXECUTABLE
override CMAKE_ARGS += -DPYTHON_EXECUTABLE=${PYTHON_EXECUTABLE}
endif
# Check if the microRTPS agent is to be built
ifdef BUILD_MICRORTPS_AGENT
override CMAKE_ARGS += -DBUILD_MICRORTPS_AGENT=ON
endif
# Functions
# --------------------------------------------------------------------
# describe how to build a cmake config
@@ -248,7 +253,7 @@ endef
# Other targets
# --------------------------------------------------------------------
.PHONY: qgc_firmware px4fmu_firmware misc_qgc_extra_firmware
.PHONY: qgc_firmware px4fmu_firmware misc_qgc_extra_firmware check_rtps
# QGroundControl flashable NuttX firmware
qgc_firmware: px4fmu_firmware misc_qgc_extra_firmware
@@ -273,7 +278,15 @@ misc_qgc_extra_firmware: \
check_airmind_mindpx-v2_default \
sizes
.PHONY: sizes check quick_check uorb_graphs
# builds with RTPS
check_rtps: \
check_px4_fmu-v3_rtps \
check_px4_fmu-v4_rtps \
check_px4_fmu-v4pro_rtps \
check_px4_sitl_rtps \
sizes
.PHONY: sizes check quick_check check_rtps uorb_graphs
sizes:
@-find build -name *.elf -type f | xargs size 2> /dev/null || :
@@ -386,8 +399,6 @@ tests_coverage:
@mkdir -p coverage
@lcov --directory build/px4_sitl_test --base-directory build/px4_sitl_test --gcov-tool gcov --capture -o coverage/lcov.info
test_unit:
@$(MAKE) tests TESTFILTER="unit\|functional"
rostest: px4_sitl_default
@$(MAKE) --no-print-directory px4_sitl_default sitl_gazebo
@@ -484,9 +495,7 @@ shellcheck_all:
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/microdds_client/dds_topics.yaml" \
-not -path "$(SRC_DIR)/src/lib/crypto/libtommath/*" -print0 | \
-not -path "$(SRC_DIR)/src/lib/mixer_module/*" -not -path "$(SRC_DIR)/src/lib/crypto/libtommath/*" -print0 | \
xargs -0 "$(SRC_DIR)"/Tools/validate_yaml.py --schema-file "$(SRC_DIR)"/validation/module_schema.yaml
# Cleanup
@@ -552,12 +561,17 @@ check_px4: $(call make_list,nuttx,"px4") \
check_nxp: $(call make_list,nuttx,"nxp") \
sizes
.PHONY: failsafe_web run_failsafe_web_server
failsafe_web:
@if ! command -v emcc; then echo -e "Install emscripten first: https://emscripten.org/docs/getting_started/downloads.html\nAnd source the env: source <path>/emsdk_env.sh"; exit 1; fi
@$(MAKE) --no-print-directory px4_sitl_default failsafe_test parameters_xml \
PX4_CMAKE_BUILD_TYPE=Release BUILD_DIR_SUFFIX=_failsafe_web \
CMAKE_ARGS="-DCMAKE_CXX_COMPILER=em++ -DCMAKE_C_COMPILER=emcc"
run_failsafe_web_server: failsafe_web
@cd build/px4_sitl_default_failsafe_web && \
python3 -m http.server
ifneq ($(ROS2_WS_DIR),)
ROS2_WS_DIR := $(basename ${ROS2_WS_DIR})
else
ROS2_WS_DIR := ~/colcon_ws
endif
update_ros2_bridge:
@Tools/update_px4_ros2_bridge.sh --ws_dir ${ROS2_WS_DIR} --all
update_px4_ros_com:
@Tools/update_px4_ros2_bridge.sh --ws_dir ${ROS2_WS_DIR} --px4_ros_com
update_px4_msgs:
@Tools/update_px4_ros2_bridge.sh --ws_dir ${ROS2_WS_DIR} --px4_msgs
+2 -2
View File
@@ -4,7 +4,7 @@
[![Nuttx Targets](https://github.com/PX4/PX4-Autopilot/workflows/Nuttx%20Targets/badge.svg)](https://github.com/PX4/PX4-Autopilot/actions?query=workflow%3A%22Nuttx+Targets%22?branch=master) [![SITL Tests](https://github.com/PX4/PX4-Autopilot/workflows/SITL%20Tests/badge.svg?branch=master)](https://github.com/PX4/PX4-Autopilot/actions?query=workflow%3A%22SITL+Tests%22)
[![Discord Shield](https://discordapp.com/api/guilds/1022170275984457759/widget.png?style=shield)](https://discord.gg/dronecode)
[![Slack](/.github/slack.svg)](https://join.slack.com/t/px4/shared_invite/zt-si4xo5qs-R4baYFmMjlrT4rQK5yUnaA)
This repository holds the [PX4](http://px4.io) flight control solution for drones, with the main applications located in the [src/modules](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules) directory. It also contains the PX4 Drone Middleware Platform, which provides drivers and middleware to run drones.
@@ -75,7 +75,7 @@ The PX4 Dev Team syncs up on a [weekly dev call](https://docs.px4.io/main/en/con
* [Paul Riseborough](https://github.com/priseborough)
* Vision based navigation and Obstacle Avoidance
* [Markus Achtelik](https://github.com/markusachtelik)
* DDS/ROS2 Interface
* RTPS/ROS2 Interface
* [Nuno Marques](https://github.com/TSC21)
See also [maintainers list](https://px4.io/community/maintainers/) (px4.io) and the [contributors list](https://github.com/PX4/PX4-Autopilot/graphs/contributors) (Github).
@@ -36,6 +36,7 @@ add_subdirectory(airframes)
px4_add_romfs_files(
px4-rc.mavlink
px4-rc.params
px4-rc.rtps
px4-rc.simulator
rc.replay
rcS
@@ -0,0 +1,4 @@
#!/bin/sh
# shellcheck disable=SC2154
micrortps_client start -t UDP -r $((2019+2*px4_instance)) -s $((2020+2*px4_instance))
@@ -41,20 +41,6 @@ elif [ "$PX4_SIMULATOR" = "gz" ]; then
fi
gz_world=$( ign topic -l | grep -m 1 -e "/world/.*/clock" | sed 's/\/world\///g; s/\/clock//g' )
gz_version_major=$( ign gazebo --versions | sed 's/\..*//g' )
gz_version_minor=$( ign gazebo --versions | sed 's/'"${gz_version_major}"\.'//; s/\..*//g' )
gz_version_point=$( ign gazebo --versions | sed 's/'"${gz_version_major}"\.'//; s/'"${gz_version_minor}"\.'//')
if [ "$gz_version_major" -gt "6" ] || { [ "$gz_version_major" -eq "6" ] && [ "$gz_version_minor" -gt "12" ]; } || { [ "$gz_version_major" -eq "6" ] && [ "$gz_version_minor" -eq "12" ] && [ "$gz_version_point" -gt "0" ]; }; then
echo "INFO [init] using latest version of MultiCopterMotor plugin."
else
echo "WARN [init] using older version of MultiCopterMotor plugin, please update to latest gazebo > 6.12.0."
if [ "$PX4_SIM_MODEL" = "x500" ]; then
PX4_SIM_MODEL="x500-Legacy"
echo "WARN [init] setting PX4_SIM_MODEL -> $PX4_SIM_MODEL from x500 till gazebo > 6.12.0"
fi
fi
if [ -z $gz_world ]; then
+5 -2
View File
@@ -259,8 +259,11 @@ fi
navigator start
# Try to start the microdds_client with UDP transport if module exists
microdds_client start -t udp -p 8888
# Try to start the micrortps_client with UDP transport if module exists
if px4-micrortps_client status > /dev/null 2>&1
then
. px4-rc.rtps
fi
if param greater -s MNT_MODE_IN -1
then
@@ -38,6 +38,7 @@ param set-default MIS_YAW_TMT 10
param set-default MPC_ACC_HOR_MAX 2
param set-default MPC_ACC_HOR_MAX 2
param set-default MPC_THR_MIN 0.1
param set-default MPC_TKO_SPEED 1
param set-default MPC_XY_P 0.8
param set-default MPC_XY_VEL_D_ACC 0.1
param set-default MPC_XY_VEL_I_ACC 4
@@ -65,6 +65,7 @@ param set-default COM_SPOOLUP_TIME 1.5
param set-default MPC_THR_HOVER 0.45
param set-default MPC_TILTMAX_AIR 25
param set-default MPC_TKO_RAMP_T 1.8
param set-default MPC_TKO_SPEED 1
param set-default MPC_VEL_MANUAL 3
param set-default MPC_XY_CRUISE 3
param set-default MPC_XY_VEL_MAX 3.5
@@ -63,6 +63,7 @@ param set-default MPC_ACC_UP_MAX 4
param set-default MPC_MAN_Y_MAX 120
param set-default MPC_TILTMAX_AIR 45
param set-default MPC_THR_HOVER 0.3
param set-default MPC_TKO_SPEED 1
param set-default MPC_VEL_MANUAL 5
param set-default MPC_XY_CRUISE 5
param set-default MPC_XY_VEL_MAX 5
@@ -64,6 +64,7 @@ param set-default MPC_MANTHR_MIN 0
param set-default MPC_MAN_Y_MAX 120
param set-default MPC_TILTMAX_AIR 45
param set-default MPC_THR_HOVER 0.3
param set-default MPC_TKO_SPEED 1
param set-default MPC_VEL_MANUAL 5
param set-default MPC_XY_CRUISE 5
param set-default MPC_XY_VEL_MAX 5
@@ -53,6 +53,7 @@ param set-default MPC_XY_VEL_P_ACC 2.6
param set-default MPC_XY_VEL_I_ACC 1.2
param set-default MPC_XY_VEL_D_ACC 0.2
param set-default MPC_TKO_RAMP_T 1
param set-default MPC_TKO_SPEED 1.1
param set-default MPC_VEL_MANUAL 3
param set-default BAT1_SOURCE 0
@@ -62,6 +62,7 @@ param set-default MPC_XY_VEL_P_ACC 2.6
param set-default MPC_XY_VEL_I_ACC 1.2
param set-default MPC_XY_VEL_D_ACC 0.2
param set-default MPC_TKO_RAMP_T 1
param set-default MPC_TKO_SPEED 1.1
param set-default MPC_VEL_MANUAL 3
param set-default BAT1_SOURCE 0
@@ -1,75 +0,0 @@
#!/bin/sh
#
# @name Aion Robotics R1 UGV
#
# @url https://www.aionrobotics.com/r1
#
# @type Rover
# @class Rover
#
# @board px4_fmu-v2 exclude
# @board bitcraze_crazyflie exclude
#
. ${R}etc/init.d/rc.rover_defaults
param set-default BAT1_N_CELLS 4
param set-default EKF2_GBIAS_INIT 0.01
param set-default EKF2_ANGERR_INIT 0.01
param set-default EKF2_MAG_TYPE 1
param set-default FW_AIRSPD_MIN 0
param set-default FW_AIRSPD_TRIM 1
param set-default FW_AIRSPD_MAX 3
param set-default GND_SP_CTRL_MODE 1
param set-default GND_L1_DIST 5
param set-default GND_L1_PERIOD 3
param set-default GND_THR_CRUISE 0.7
param set-default GND_THR_MAX 0.5
# Because this is differential drive, it can make a turn with radius 0.
# This corresponds to a turn angle of pi radians.
# If a special case is made for differential-drive, this will need to change.
param set-default GND_MAX_ANG 3.142
param set-default GND_WHEEL_BASE 0.3
# TODO: Set to -1.0, to allow reversing. This will require many changes in the codebase
# to support negative throttle.
param set-default GND_THR_MIN 0
param set-default GND_SPEED_P 0.25
param set-default GND_SPEED_I 3
param set-default GND_SPEED_D 0.001
param set-default GND_SPEED_IMAX 0.125
param set-default GND_SPEED_THR_SC 1
param set-default MIS_LTRMIN_ALT 0.01
param set-default MIS_TAKEOFF_ALT 0.01
param set-default NAV_ACC_RAD 0.5
# Enable Airspeed check circuit breaker because Rovers will have no airspeed sensor
param set-default CBRK_AIRSPD_CHK 162128
# Differential drive acts like ackermann steering with a maximum turn angle of 180 degrees, or pi radians
param set-default GND_MAX_ANG 3.1415
param set-default RBCLW_BAUD 8
param set-default RBCLW_COUNTS_REV 1200
param set-default RBCLW_ADDRESS 128
# 104 corresponds to Telem 4
param set-default RBCLW_SER_CFG 104
# Start this driver after setting parameters, because the driver uses some of those parameters.
# roboclaw start /dev/ttyS3
# Set geometry & output configration
param set-default CA_AIRFRAME 6
param set-default CA_R_REV 3
param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
param set-default PWM_MAIN_DIS1 1500
param set-default PWM_MAIN_DIS2 1500
param set-default PWM_MAIN_TIM0 50
param set-default PWM_MAIN_TIM1 50
@@ -118,7 +118,6 @@ px4_add_romfs_files(
50000_generic_ground_vehicle
50004_nxpcup_car_dfrobot_gpx
50003_aion_robotics_r1_rover
# [60000, 61000] (Unmanned) Underwater Robots
60000_uuv_generic
+21 -21
View File
@@ -324,27 +324,6 @@ else
rc_update start
manual_control start
# Start camera trigger, capture and PPS before pwm_out as they might access
# pwm pins
if param greater -s TRIG_MODE 0
then
camera_trigger start
camera_feedback start
fi
# PPS capture driver
if param greater -s PPS_CAP_ENABLE 0
then
pps_capture start
fi
# Camera capture driver
if param greater -s CAM_CAP_FBACK 0
then
if camera_capture start
then
camera_capture on
fi
fi
#
# Sensors System (start before Commander so Preflight checks are properly run).
# Commander needs to be this early for in-air-restarts.
@@ -411,6 +390,12 @@ else
mag_bias_estimator start
fi
if param greater -s TRIG_MODE 0
then
camera_trigger start
camera_feedback start
fi
#
# Optional board mavlink streams: rc.board_mavlink
#
@@ -431,6 +416,21 @@ else
# Must be started after the serial config is read
rc_input start $RC_INPUT_ARGS
# PPS capture driver (before pwm_out)
if param greater -s PPS_CAP_ENABLE 0
then
pps_capture start
fi
# Camera capture driver (before pwm_out)
if param greater -s CAM_CAP_FBACK 0
then
if camera_capture start
then
camera_capture on
fi
fi
#
# Play the startup tune (if not disabled or there is an error)
#
@@ -8,6 +8,7 @@ if [ $# -gt 0 ]; then
fi
exec find boards msg src platforms test \
-path msg/templates/urtps -prune -o \
-path platforms/nuttx/NuttX -prune -o \
-path platforms/qurt/dspal -prune -o \
-path src/drivers/uavcan/libuavcan -prune -o \
@@ -20,6 +21,8 @@ exec find boards msg src platforms test \
-path src/modules/ekf2/EKF -prune -o \
-path src/modules/gyro_fft/CMSIS_5 -prune -o \
-path src/modules/mavlink/mavlink -prune -o \
-path src/modules/micrortps_bridge/micro-CDR -prune -o \
-path src/modules/micrortps_bridge/microRTPS_client -prune -o \
-path test/mavsdk_tests/catch2 -prune -o \
-path src/lib/crypto/monocypher -prune -o \
-path src/lib/crypto/libtomcrypt -prune -o \
+15
View File
@@ -0,0 +1,15 @@
#!/usr/bin/env bash
set -e
SCRIPT_DIR=$0
if [[ ${SCRIPT_DIR:0:1} != '/' ]]; then
SCRIPT_DIR=$(dirname $(realpath -s "$PWD/$0"))
fi
PX4_DIR=$(cd "$(dirname $(dirname $SCRIPT_DIR))" && pwd)
if [ -d $PX4_DIR/build/*_rtps ]; then
cd $PX4_DIR/build/*_rtps/src/modules/micrortps_bridge/micrortps_agent/
cmake -Bbuild
cmake --build build -j$(nproc --all)
fi
@@ -489,7 +489,7 @@ actuators = {
with open(output_file, 'w') as outfile:
indent = 2 if verbose else None
json.dump(actuators, outfile, indent=indent, sort_keys=True)
json.dump(actuators, outfile, indent=indent)
if compress:
save_compressed(output_file)
@@ -32,16 +32,16 @@ def extract_timer(line):
# Try format: initIOTimer(Timer::Timer5, DMA{DMA::Index1, DMA::Stream0, DMA::Channel6}),
search = re.search('Timer::([0-9a-zA-Z_]+)[,\)]', line, re.IGNORECASE)
if search:
return search.group(1), 'generic'
return search.group(1)
# nxp rt1062 format: initIOPWM(PWM::FlexPWM2),
search = re.search('PWM::Flex([0-9a-zA-Z_]+)[,\)]', line, re.IGNORECASE)
if search:
return search.group(1), 'imxrt'
return search.group(1)
return None, 'unknown'
return None
def extract_timer_from_channel(line, num_channels_already_found):
def extract_timer_from_channel(line):
# Try format: initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortA, GPIO::Pin0}),
search = re.search('Timer::([0-9a-zA-Z_]+), ', line, re.IGNORECASE)
if search:
@@ -50,8 +50,7 @@ def extract_timer_from_channel(line, num_channels_already_found):
# nxp rt1062 format: initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_B0_06),
search = re.search('PWM::(PWM[0-9]+)[_,\)]', line, re.IGNORECASE)
if search:
# imxrt uses a 1:1 timer group to channel association
return str(num_channels_already_found)
return search.group(1)
return None
@@ -73,14 +72,7 @@ def get_timer_groups(timer_config_file, verbose=False):
line = line.strip()
if len(line) == 0 or line.startswith('//'):
continue
timer, timer_type = extract_timer(line)
if timer_type == 'imxrt':
if verbose: print('imxrt timer found')
max_num_channels = 16 # Just add a fixed number of timers
timers = [str(i) for i in range(max_num_channels)]
dshot_support = {str(i): False for i in range(max_num_channels)}
break
timer = extract_timer(line)
if timer:
if verbose: print('found timer def: {:}'.format(timer))
@@ -109,7 +101,7 @@ def get_timer_groups(timer_config_file, verbose=False):
continue
if verbose: print('--'+line+'--')
timer = extract_timer_from_channel(line, len(channel_timers))
timer = extract_timer_from_channel(line)
if timer:
if verbose: print('Found timer: {:} in channel line {:}'.format(timer, line))
-253
View File
@@ -1,253 +0,0 @@
#!/usr/bin/env python3
#############################################################################
#
# Copyright (C) 2013-2022 PX4 Pro Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
#############################################################################
"""
px_generate_uorb_topic_files.py
Generates c/cpp header/source files for uorb topics from .msg
message files
"""
import os
import argparse
import re
import sys
try:
import em
except ImportError as e:
print("Failed to import em: " + str(e))
print("")
print("You may need to install it using:")
print(" pip3 install --user empy")
print("")
sys.exit(1)
try:
import genmsg.template_tools
except ImportError as e:
print("Failed to import genmsg: " + str(e))
print("")
print("You may need to install it using:")
print(" pip3 install --user pyros-genmsg")
print("")
sys.exit(1)
__author__ = "Sergey Belash, Thomas Gubler, Beat Kueng"
__copyright__ = "Copyright (C) 2013-2022 PX4 Development Team."
__license__ = "BSD"
__email__ = "thomasgubler@gmail.com"
TEMPLATE_FILE = ['msg.h.em', 'msg.cpp.em']
TOPICS_LIST_TEMPLATE_FILE = ['uORBTopics.hpp.em', 'uORBTopics.cpp.em']
OUTPUT_FILE_EXT = ['.h', '.cpp']
INCL_DEFAULT = ['std_msgs:./msg/std_msgs']
PACKAGE = 'px4'
TOPICS_TOKEN = '# TOPICS '
def get_topics(filename):
"""
Get TOPICS names from a "# TOPICS" line
"""
ofile = open(filename, 'r')
text = ofile.read()
result = []
for each_line in text.split('\n'):
if each_line.startswith(TOPICS_TOKEN):
topic_names_str = each_line.strip()
topic_names_str = topic_names_str.replace(TOPICS_TOKEN, "")
topic_names_list = topic_names_str.split(" ")
for topic in topic_names_list:
# topic name PascalCase (file name) to snake_case (topic name)
topic_name = re.sub(r'(?<!^)(?=[A-Z])', '_', topic).lower()
result.append(topic_name)
ofile.close()
if len(result) == 0:
# topic name PascalCase (file name) to snake_case (topic name)
file_base_name = os.path.basename(filename).replace(".msg", "")
topic_name = re.sub(r'(?<!^)(?=[A-Z])', '_', file_base_name).lower()
result.append(topic_name)
return result
def generate_output_from_file(format_idx, filename, outputdir, package, templatedir, includepath):
"""
Converts a single .msg file to an uorb header/source file
"""
msg_context = genmsg.msg_loader.MsgContext.create_default()
full_type_name = genmsg.gentools.compute_full_type_name(package, os.path.basename(filename))
file_base_name = os.path.basename(filename).replace(".msg", "")
full_type_name_snake = re.sub(r'(?<!^)(?=[A-Z])', '_', file_base_name).lower()
spec = genmsg.msg_loader.load_msg_from_file(msg_context, filename, full_type_name)
field_name_and_type = {}
for field in spec.parsed_fields():
field_name_and_type.update({field.name: field.type})
# assert if the timestamp field exists
try:
assert 'timestamp' in field_name_and_type
except AssertionError:
print("[ERROR] uORB topic files generator:\n\tgenerate_output_from_file:\tNo 'timestamp' field found in " +
spec.short_name + " msg definition!")
exit(1)
# assert if the timestamp field is of type uint64
try:
assert field_name_and_type.get('timestamp') == 'uint64'
except AssertionError:
print("[ERROR] uORB topic files generator:\n\tgenerate_output_from_file:\t'timestamp' field in " + spec.short_name +
" msg definition is not of type uint64 but rather of type " + field_name_and_type.get('timestamp') + "!")
exit(1)
topics = get_topics(filename)
if includepath:
search_path = genmsg.command_line.includepath_to_dict(includepath)
else:
search_path = {}
genmsg.msg_loader.load_depends(msg_context, spec, search_path)
em_globals = {
"name_snake_case": full_type_name_snake,
"file_name_in": filename,
"search_path": search_path,
"msg_context": msg_context,
"spec": spec,
"topics": topics,
}
# Make sure output directory exists:
if not os.path.isdir(outputdir):
os.makedirs(outputdir)
template_file = os.path.join(templatedir, TEMPLATE_FILE[format_idx])
output_file = os.path.join(outputdir, full_type_name_snake + OUTPUT_FILE_EXT[format_idx])
return generate_by_template(output_file, template_file, em_globals)
def generate_by_template(output_file, template_file, em_globals):
"""
Invokes empy intepreter to geneate output_file by the
given template_file and predefined em_globals dict
"""
# check if folder exists:
folder_name = os.path.dirname(output_file)
if not os.path.exists(folder_name):
os.makedirs(folder_name)
ofile = open(output_file, 'w')
# todo, reuse interpreter
interpreter = em.Interpreter(output=ofile, globals=em_globals, options={
em.RAW_OPT: True, em.BUFFERED_OPT: True})
try:
interpreter.file(open(template_file))
except OSError as e:
ofile.close()
os.remove(output_file)
raise
interpreter.shutdown()
ofile.close()
return True
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")]:
filenames.append(re.sub(r'(?<!^)(?=[A-Z])', '_', filename).lower())
topics = []
for msg_filename in files:
topics.extend(get_topics(msg_filename))
tl_globals = {"msgs": filenames, "topics": topics}
tl_template_file = os.path.join(templatedir, template_filename)
tl_out_file = os.path.join(outputdir, template_filename.replace(".em", ""))
generate_by_template(tl_out_file, tl_template_file, tl_globals)
def append_to_include_path(path_to_append, curr_include, package):
for p in path_to_append:
curr_include.append('%s:%s' % (package, p))
if __name__ == "__main__":
parser = argparse.ArgumentParser(description='Convert msg files to uorb headers/sources')
parser.add_argument('--headers', help='Generate header files', action='store_true')
parser.add_argument('--sources', help='Generate source files', action='store_true')
parser.add_argument('-f', dest='file',
help="files to convert (use only without -d)",
nargs="+")
parser.add_argument('-i', dest="include_paths",
help='Additional Include Paths', nargs="*",
default=None)
parser.add_argument('-e', dest='templatedir',
help='directory with template files',)
parser.add_argument('-k', dest='package', default=PACKAGE,
help='package name')
parser.add_argument('-o', dest='outputdir',
help='output directory for header files')
parser.add_argument('-p', dest='prefix', default='',
help='string added as prefix to the output file '
' name when converting directories')
args = parser.parse_args()
if args.include_paths:
append_to_include_path(args.include_paths, INCL_DEFAULT, args.package)
if args.headers:
generate_idx = 0
elif args.sources:
generate_idx = 1
else:
print('Error: either --headers or --sources must be specified')
exit(-1)
if args.file is not None:
for f in args.file:
generate_output_from_file(generate_idx, f, args.outputdir, args.package, args.templatedir, INCL_DEFAULT)
# Generate topics list header and source file
if os.path.isfile(os.path.join(args.templatedir, TOPICS_LIST_TEMPLATE_FILE[generate_idx])):
generate_topics_list_file_from_files(args.file, args.outputdir, TOPICS_LIST_TEMPLATE_FILE[generate_idx], args.templatedir)
+3 -7
View File
@@ -211,11 +211,6 @@ class SourceParser(object):
ignore_event = False
def parse_message(s):
assert s[0] == '"', "Argument must be a string literal: {:}".format(s)
# unescape \x, to treat the string the same as the C++ compiler
return s[1:-1].encode("utf-8").decode('unicode_escape')
# extract function arguments
args_split = self._parse_arguments(args)
if call == "events::send" or call == "send":
@@ -233,7 +228,8 @@ class SourceParser(object):
else:
raise Exception("Could not extract event ID from {:}".format(args_split[0]))
event.name = event_name
event.message = parse_message(args_split[2])
# unescape \x, to treat the string the same as the C++ compiler
event.message = args_split[2][1:-1].encode("utf-8").decode('unicode_escape')
elif call in ['reporter.healthFailure', 'reporter.armingCheckFailure']:
assert len(args_split) == num_args + 5, \
"Unexpected Number of arguments for: {:}, {:}".format(args_split, num_args)
@@ -243,7 +239,7 @@ class SourceParser(object):
else:
raise Exception("Could not extract event ID from {:}".format(args_split[2]))
event.name = event_name
event.message = parse_message(args_split[4])
event.message = args_split[4][1:-1]
if 'health' in call:
event.group = "health"
else:
+8 -20
View File
@@ -77,23 +77,11 @@ except ImportError as e:
print("")
sys.exit(1)
# Define time to use time.time() by default
def _time():
return time.time()
# Detect python version
if sys.version_info[0] < 3:
runningPython3 = False
else:
runningPython3 = True
if sys.version_info[1] >=3:
# redefine to use monotonic time when available
def _time():
try:
return time.monotonic()
except Exception:
return time.time()
class FirmwareNotSuitableException(Exception):
def __init__(self, message):
@@ -242,7 +230,7 @@ class uploader(object):
def open(self):
# upload timeout
timeout = _time() + 0.2
timeout = time.time() + 0.2
# attempt to open the port while it exists and until timeout occurs
while self.port is not None:
@@ -252,7 +240,7 @@ class uploader(object):
except AttributeError:
portopen = self.port.isOpen()
if not portopen and _time() < timeout:
if not portopen and time.time() < timeout:
try:
self.port.open()
except OSError:
@@ -427,16 +415,16 @@ class uploader(object):
uploader.EOC)
# erase is very slow, give it 30s
deadline = _time() + 30.0
while _time() < deadline:
deadline = time.time() + 30.0
while time.time() < deadline:
usualEraseDuration = 15.0
estimatedTimeRemaining = deadline-_time()
estimatedTimeRemaining = deadline-time.time()
if estimatedTimeRemaining >= usualEraseDuration:
self.__drawProgressBar(label, 30.0-estimatedTimeRemaining, usualEraseDuration)
else:
self.__drawProgressBar(label, 10.0, 10.0)
sys.stdout.write(" (timeout: %d seconds) " % int(deadline-_time()))
sys.stdout.write(" (timeout: %d seconds) " % int(deadline-time.time()))
sys.stdout.flush()
if self.__trySync():
@@ -584,7 +572,7 @@ class uploader(object):
# upload the firmware
def upload(self, fw, force=False, boot_delay=None):
# Make sure we are doing the right thing
start = _time()
start = time.time()
if self.board_type != fw.property('board_id'):
msg = "Firmware not suitable for this board (Firmware board_type=%u board_id=%u)" % (
self.board_type, fw.property('board_id'))
@@ -680,7 +668,7 @@ class uploader(object):
print("\nRebooting.", end='')
self.__reboot()
self.port.close()
print(" Elapsed Time %3.3f\n" % (_time() - start))
print(" Elapsed Time %3.3f\n" % (time.time() - start))
def __next_baud_flightstack(self):
if self.baudrate_flightstack_idx + 1 >= len(self.baudrate_flightstack):
+3 -1
View File
@@ -9,6 +9,8 @@
## - jMAVSim simulator (omit with arg: --no-sim-tools)
## - Gazebo simulator (not by default, use --gazebo)
##
## Not Installs:
## - FastRTPS and FastCDR
INSTALL_NUTTX="true"
INSTALL_SIM="true"
@@ -120,7 +122,7 @@ if [[ $INSTALL_SIM == "true" ]]; then
echo
echo "Installing PX4 simulation dependencies"
# java (jmavsim)
# java (jmavsim or fastrtps)
sudo pacman -S --noconfirm --needed \
ant \
jdk-openjdk \
+4 -2
View File
@@ -2,7 +2,7 @@
set -e
## Bash script to setup PX4 development environment on Ubuntu LTS (22.04, 20.04, 18.04).
## Bash script to setup PX4 development environment on Ubuntu LTS (20.04, 18.04, 16.04).
## Can also be used in docker.
##
## Installs:
@@ -10,6 +10,8 @@ set -e
## - NuttX toolchain (omit with arg: --no-nuttx)
## - jMAVSim and Gazebo9 simulator (omit with arg: --no-sim-tools)
##
## Not Installs:
## - FastRTPS and FastCDR
INSTALL_NUTTX="true"
INSTALL_SIM="true"
@@ -214,7 +216,7 @@ if [[ $INSTALL_SIM == "true" ]]; then
else
java_version=14
fi
# Java (jmavsim)
# Java (jmavsim or fastrtps)
sudo DEBIAN_FRONTEND=noninteractive apt-get -y --quiet --no-install-recommends install \
ant \
openjdk-$java_version-jre \
@@ -1,11 +0,0 @@
<?xml version="1.0"?>
<model>
<name>x500-Legacy</name>
<version>1.0</version>
<sdf version="1.9">model.sdf</sdf>
<author>
<name>Benjamin Perseghetti</name>
<email>bperseghetti@rudislabs.com</email>
</author>
<description>Model of the NXP HoverGames Drone development kit (KIT-HGDRONEK66). The PX4 software compatible kit provides mechanical, RC remote and other components needed to evaluate the RDDRONE-FMUK66 reference design. The FMU includes 100Base-T1 Automotive Ethernet, dual CAN transceivers, as well as SE050 secure element, and works with add on boards NavQPlus, MR-T1ETH8, MR-T1ADAPT, and CAN-nodes such as UCANS32K1SIC. Kit may be used with, and contains the components needed for the HoverGames.com coding challenges.</description>
</model>
@@ -1,76 +0,0 @@
<?xml version="1.0" encoding="UTF-8"?>
<sdf version='1.9'>
<model name='x500-Legacy'>
<include merge='true'>
<uri>model://x500-NoPlugin</uri>
</include>
<plugin filename="ignition-gazebo-multicopter-motor-model-system" name="ignition::gazebo::systems::MulticopterMotorModel">
<robotNamespace>/x500-Legacy_0</robotNamespace>
<jointName>rotor_0_joint</jointName>
<linkName>rotor_0</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1000.0</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>0</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<plugin filename="ignition-gazebo-multicopter-motor-model-system" name="ignition::gazebo::systems::MulticopterMotorModel">
<robotNamespace>/x500-Legacy_0</robotNamespace>
<jointName>rotor_1_joint</jointName>
<linkName>rotor_1</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1000.0</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>1</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<plugin filename="ignition-gazebo-multicopter-motor-model-system" name="ignition::gazebo::systems::MulticopterMotorModel">
<robotNamespace>/x500-Legacy_0</robotNamespace>
<jointName>rotor_2_joint</jointName>
<linkName>rotor_2</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1000.0</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>2</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<plugin filename="ignition-gazebo-multicopter-motor-model-system" name="ignition::gazebo::systems::MulticopterMotorModel">
<robotNamespace>/x500-Legacy_0</robotNamespace>
<jointName>rotor_3_joint</jointName>
<linkName>rotor_3</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1000.0</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>3</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
</model>
</sdf>
Binary file not shown.

Before

Width:  |  Height:  |  Size: 32 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 51 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 28 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 27 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 23 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 1.5 MiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 25 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 26 KiB

File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
Binary file not shown.

Before

Width:  |  Height:  |  Size: 1.5 MiB

File diff suppressed because one or more lines are too long
@@ -1,11 +0,0 @@
<?xml version="1.0"?>
<model>
<name>x500-NoPlugin</name>
<version>1.0</version>
<sdf version="1.9">model.sdf</sdf>
<author>
<name>Benjamin Perseghetti</name>
<email>bperseghetti@rudislabs.com</email>
</author>
<description>Model of the NXP HoverGames Drone development kit (KIT-HGDRONEK66). The PX4 software compatible kit provides mechanical, RC remote and other components needed to evaluate the RDDRONE-FMUK66 reference design. The FMU includes 100Base-T1 Automotive Ethernet, dual CAN transceivers, as well as SE050 secure element, and works with add on boards NavQPlus, MR-T1ETH8, MR-T1ADAPT, and CAN-nodes such as UCANS32K1SIC. Kit may be used with, and contains the components needed for the HoverGames.com coding challenges.</description>
</model>
@@ -1,516 +0,0 @@
<?xml version="1.0" encoding="UTF-8"?>
<sdf version='1.9'>
<model name='x500-NoPlugin'>
<pose>0 0 .24 0 0 0</pose>
<self_collide>false</self_collide>
<static>false</static>
<link name="base_link">
<inertial>
<mass>2.0</mass>
<inertia>
<ixx>0.02166666666666667</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.02166666666666667</iyy>
<iyz>0</iyz>
<izz>0.04000000000000001</izz>
</inertia>
</inertial>
<gravity>true</gravity>
<velocity_decay/>
<visual name="base_link_visual">
<pose>0 0 .025 0 0 3.141592654</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://x500-NoPlugin/meshes/NXP-HGD-CF.dae</uri>
</mesh>
</geometry>
</visual>
<visual name="5010_motor_base_0">
<pose>0.174 0.174 .032 0 0 -.45</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://x500-NoPlugin/meshes/5010Base.dae</uri>
</mesh>
</geometry>
</visual>
<visual name="5010_motor_base_1">
<pose>-0.174 0.174 .032 0 0 -.45</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://x500-NoPlugin/meshes/5010Base.dae</uri>
</mesh>
</geometry>
</visual>
<visual name="5010_motor_base_2">
<pose>0.174 -0.174 .032 0 0 -.45</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://x500-NoPlugin/meshes/5010Base.dae</uri>
</mesh>
</geometry>
</visual>
<visual name="5010_motor_base_3">
<pose>-0.174 -0.174 .032 0 0 -.45</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://x500-NoPlugin/meshes/5010Base.dae</uri>
</mesh>
</geometry>
</visual>
<visual name="NXP_FMUK66_FRONT">
<pose>0.047 .001 .043 1 0 1.57</pose>
<cast_shadows>false</cast_shadows>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>.013 .007</size>
</plane>
</geometry>
<material>
<diffuse>1.0 1.0 1.0</diffuse>
<specular>1.0 1.0 1.0</specular>
<pbr>
<metal>
<albedo_map>model://x500-NoPlugin/materials/textures/nxp.png</albedo_map>
</metal>
</pbr>
</material>
</visual>
<visual name="NXP_FMUK66_TOP">
<pose>-0.023 0 .0515 0 0 -1.57</pose>
<cast_shadows>false</cast_shadows>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>.013 .007</size>
</plane>
</geometry>
<material>
<diffuse>1.0 1.0 1.0</diffuse>
<specular>1.0 1.0 1.0</specular>
<pbr>
<metal>
<albedo_map>model://x500-NoPlugin/materials/textures/nxp.png</albedo_map>
</metal>
</pbr>
</material>
</visual>
<visual name="RDDRONE_FMUK66_TOP">
<pose>-.03 0 .0515 0 0 -1.57</pose>
<cast_shadows>false</cast_shadows>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>.032 .0034</size>
</plane>
</geometry>
<material>
<diffuse>1.0 1.0 1.0</diffuse>
<specular>1.0 1.0 1.0</specular>
<pbr>
<metal>
<albedo_map>model://x500-NoPlugin/materials/textures/rd.png</albedo_map>
</metal>
</pbr>
</material>
</visual>
<collision name="base_link_collision_0">
<pose>0 0 .007 0 0 0</pose>
<geometry>
<box>
<size>0.35355339059327373 0.35355339059327373 0.05</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<min_depth>0.001</min_depth>
<max_vel>0</max_vel>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<collision name="base_link_collision_1">
<pose>0 -0.098 -.123 -0.35 0 0</pose>
<geometry>
<box>
<size>0.015 0.015 0.21</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<min_depth>0.001</min_depth>
<max_vel>0</max_vel>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<collision name="base_link_collision_2">
<pose>0 0.098 -.123 0.35 0 0</pose>
<geometry>
<box>
<size>0.015 0.015 0.21</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<min_depth>0.001</min_depth>
<max_vel>0</max_vel>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<collision name="base_link_collision_3">
<pose>0 -0.132 -.2195 0 0 0</pose>
<geometry>
<box>
<size>0.25 0.015 0.015</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<min_depth>0.001</min_depth>
<max_vel>0</max_vel>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<collision name="base_link_collision_4">
<pose>0 0.132 -.2195 0 0 0</pose>
<geometry>
<box>
<size>0.25 0.015 0.015</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<min_depth>0.001</min_depth>
<max_vel>0</max_vel>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>250</update_rate>
</sensor>
</link>
<link name="rotor_0">
<gravity>true</gravity>
<self_collide>false</self_collide>
<velocity_decay/>
<pose>0.174 -0.174 0.06 0 0 0</pose>
<inertial>
<mass>0.016076923076923075</mass>
<inertia>
<ixx>3.8464910483993325e-07</ixx>
<iyy>2.6115851691700804e-05</iyy>
<izz>2.649858234714004e-05</izz>
</inertia>
</inertial>
<visual name="rotor_0_visual">
<pose>-0.022 -0.14638461538461536 -0.016 0 0 0</pose>
<geometry>
<mesh>
<scale>0.8461538461538461 0.8461538461538461 0.8461538461538461</scale>
<uri>model://x500-NoPlugin/meshes/1345_prop_ccw.stl</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/DarkGrey</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
<visual name="rotor_0_visual_motor_bell">
<pose>0 0 -.032 0 0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://x500-NoPlugin/meshes/5010Bell.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="rotor_0_collision">
<pose>0 0 0 0 0 0 </pose>
<geometry>
<box>
<size>0.2792307692307692 0.016923076923076923 0.0008461538461538462</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<min_depth>0.001</min_depth>
<max_vel>0</max_vel>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
</link>
<joint name="rotor_0_joint" type="revolute">
<parent>base_link</parent>
<child>rotor_0</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<link name="rotor_1">
<gravity>true</gravity>
<self_collide>false</self_collide>
<velocity_decay/>
<pose>-0.174 0.174 0.06 0 0 0</pose>
<inertial>
<mass>0.016076923076923075</mass>
<inertia>
<ixx>3.8464910483993325e-07</ixx>
<iyy>2.6115851691700804e-05</iyy>
<izz>2.649858234714004e-05</izz>
</inertia>
</inertial>
<visual name="rotor_1_visual">
<pose>-0.022 -0.14638461538461536 -0.016 0 0 0</pose>
<geometry>
<mesh>
<scale>0.8461538461538461 0.8461538461538461 0.8461538461538461</scale>
<uri>model://x500-NoPlugin/meshes/1345_prop_ccw.stl</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/DarkGrey</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
<visual name="rotor_1_visual_motor_top">
<pose>0 0 -.032 0 0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://x500-NoPlugin/meshes/5010Bell.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="rotor_1_collision">
<pose>0 0 0 0 0 0 </pose>
<geometry>
<box>
<size>0.2792307692307692 0.016923076923076923 0.0008461538461538462</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<min_depth>0.001</min_depth>
<max_vel>0</max_vel>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
</link>
<joint name="rotor_1_joint" type="revolute">
<parent>base_link</parent>
<child>rotor_1</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<link name="rotor_2">
<gravity>true</gravity>
<self_collide>false</self_collide>
<velocity_decay/>
<pose>0.174 0.174 0.06 0 0 0</pose>
<inertial>
<mass>0.016076923076923075</mass>
<inertia>
<ixx>3.8464910483993325e-07</ixx>
<iyy>2.6115851691700804e-05</iyy>
<izz>2.649858234714004e-05</izz>
</inertia>
</inertial>
<visual name="rotor_2_visual">
<pose>-0.022 -0.14638461538461536 -0.016 0 0 0</pose>
<geometry>
<mesh>
<scale>0.8461538461538461 0.8461538461538461 0.8461538461538461</scale>
<uri>model://x500-NoPlugin/meshes/1345_prop_cw.stl</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/DarkGrey</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
<visual name="rotor_2_visual_motor_top">
<pose>0 0 -.032 0 0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://x500-NoPlugin/meshes/5010Bell.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="rotor_2_collision">
<pose>0 0 0 0 0 0 </pose>
<geometry>
<box>
<size>0.2792307692307692 0.016923076923076923 0.0008461538461538462</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<min_depth>0.001</min_depth>
<max_vel>0</max_vel>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
</link>
<joint name="rotor_2_joint" type="revolute">
<parent>base_link</parent>
<child>rotor_2</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<link name="rotor_3">
<gravity>true</gravity>
<self_collide>false</self_collide>
<velocity_decay/>
<pose>-0.174 -0.174 0.06 0 0 0</pose>
<inertial>
<mass>0.016076923076923075</mass>
<inertia>
<ixx>3.8464910483993325e-07</ixx>
<iyy>2.6115851691700804e-05</iyy>
<izz>2.649858234714004e-05</izz>
</inertia>
</inertial>
<visual name="rotor_3_visual">
<pose>-0.022 -0.14638461538461536 -0.016 0 0 0</pose>
<geometry>
<mesh>
<scale>0.8461538461538461 0.8461538461538461 0.8461538461538461</scale>
<uri>model://x500-NoPlugin/meshes/1345_prop_cw.stl</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/DarkGrey</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
<visual name="rotor_3_visual_motor_top">
<pose>0 0 -.032 0 0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://x500-NoPlugin/meshes/5010Bell.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="rotor_3_collision">
<pose>0 0 0 0 0 0 </pose>
<geometry>
<box>
<size>0.2792307692307692 0.016923076923076923 0.0008461538461538462</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<min_depth>0.001</min_depth>
<max_vel>0</max_vel>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
</link>
<joint name="rotor_3_joint" type="revolute">
<parent>base_link</parent>
<child>rotor_3</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
</model>
</sdf>
Binary file not shown.

Before

Width:  |  Height:  |  Size: 32 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 51 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 28 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 27 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 23 KiB

+1 -65
View File
@@ -2,71 +2,7 @@
<sdf version='1.9'>
<model name='x500'>
<include merge='true'>
<uri>model://x500-NoPlugin</uri>
<uri>https://fuel.gazebosim.org/1.0/RudisLaboratories/models/x500-Base</uri>
</include>
<plugin filename="ignition-gazebo-multicopter-motor-model-system" name="ignition::gazebo::systems::MulticopterMotorModel">
<jointName>rotor_0_joint</jointName>
<linkName>rotor_0</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1000.0</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>0</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<plugin filename="ignition-gazebo-multicopter-motor-model-system" name="ignition::gazebo::systems::MulticopterMotorModel">
<jointName>rotor_1_joint</jointName>
<linkName>rotor_1</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1000.0</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>1</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<plugin filename="ignition-gazebo-multicopter-motor-model-system" name="ignition::gazebo::systems::MulticopterMotorModel">
<jointName>rotor_2_joint</jointName>
<linkName>rotor_2</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1000.0</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>2</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
<plugin filename="ignition-gazebo-multicopter-motor-model-system" name="ignition::gazebo::systems::MulticopterMotorModel">
<jointName>rotor_3_joint</jointName>
<linkName>rotor_3</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1000.0</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>3</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
<motorType>velocity</motorType>
</plugin>
</model>
</sdf>
+135
View File
@@ -0,0 +1,135 @@
#!/usr/bin/env bash
set -e
agent_template_files_updated=0
code_generator_files_updated=0
# parse help argument
if [[ $1 == "-h" ]] || [[ $1 == "--help" ]]; then
echo -e "Usage: update_px4_ros2_bridge.bash [options...] \t This script allows to update px4_ros_com and px4_msgs in a specified directory." >&2
echo
echo -e "\t--ws_dir \t\t Location of the ament/colcon workspace. Default: $HOME/colcon_ws."
echo -e "\t--px4_ros_com \t\t Updates px4_ros_com microRTPS agent code generation and templates."
echo -e "\t--px4_msgs \t\t Updates px4_msgs messages definition files."
echo -e "\t--all \t\t Updates both px4_ros_com and px4_msgs."
echo
exit 0
fi
# parse the arguments
while [ $# -gt 0 ]; do
if [[ $1 == *"--"* ]]; then
v="${1/--/}"
if [ ! -z $2 ]; then
declare $v="$2"
else
declare $v=1
fi
fi
shift
done
# get script directory
SCRIPT_DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )"
# get PX4-Autopilot directory
PX4_DIR=$(cd "$(dirname "$SCRIPT_DIR")" && pwd)
function compare_and_update () {
cmp -s "$1" "$2"
if [ $? -eq 1 ]; then
cp "$1" "$2"
return 0
fi
return 1;
}
# update microRTPS agent code generators / helpers
function update_agent_code {
declare -a templates=( \
"microRTPS_agent.cpp.em" \
"microRTPS_timesync.cpp.em" \
"microRTPS_timesync.h.em" \
"microRTPS_transport.cpp" \
"microRTPS_transport.h" \
"Publisher.cpp.em" \
"Publisher.h.em" \
"Subscriber.cpp.em" \
"Subscriber.h.em" \
"RtpsTopics.cpp.em" \
"RtpsTopics.h.em" \
)
for file in ${templates[@]}; do
compare_and_update "$PX4_DIR/msg/templates/urtps/$file" "$ws_dir/src/px4_ros_com/templates/$file" \
&& echo -e "--\t\t- '$ws_dir/src/px4_ros_com/templates/$file' updated" && ((agent_template_files_updated+=1))
done
if [ $agent_template_files_updated -eq 0 ]; then
echo -e "--\t\t- No template files updated"
elif [ $agent_template_files_updated -eq 1 ]; then
echo -e "--\t\t - 1 template file updated"
else
echo -e "--\t\t - $agent_template_files_updated template files updated"
fi
}
# update microRTPS agent code templates
function update_agent_templates {
declare -a code_generators=( \
"uorb_rtps_classifier.py" \
"generate_microRTPS_bridge.py" \
"px_generate_uorb_topic_files.py" \
)
for file in ${code_generators[@]}; do
compare_and_update "$PX4_DIR/msg/tools/$file $ws_dir/src/px4_ros_com/scripts/$file" \
&& echo -e "--\t\t- '$ws_dir/src/px4_ros_com/scripts/$file' updated" && ((code_generator_files_updated+=1))
done
if [ $code_generator_files_updated -eq 0 ]; then
echo -e "--\t\t- No code generators / helpers files updated"
elif [ $code_generator_files_updated -eq 1 ]; then
echo -e "--\t\t - 1 code generator / helper file updated"
else
echo -e "--\t\t - $code_generator_files_updated code generator / helper files updated"
fi
}
# update px4_ros_com files
function update_px4_ros_com {
python3 $PX4_DIR/msg/tools/uorb_to_ros_urtps_topics.py -i $PX4_DIR/msg/tools/urtps_bridge_topics.yaml -o $ws_dir/src/px4_ros_com/templates/urtps_bridge_topics.yaml
echo -e "--------------- \033[1mmicroRTPS agent code generation and templates update\033[0m ----------------"
echo "-------------------------------------------------------------------------------------------------------"
update_agent_code
update_agent_templates
return 0
}
# function to update px4_msgs
function update_px4_msgs {
find "$ws_dir/src/px4_msgs/msg/" -maxdepth 1 -type f -delete
python3 $PX4_DIR/msg/tools/uorb_to_ros_msgs.py $PX4_DIR/msg/ $ws_dir/src/px4_msgs/msg/
}
# decisor
echo "-------------------------------------------------------------------------------------------------------"
if [ -d "${ws_dir}" ]; then
ws_dir=$(cd "$ws_dir" && pwd)
if [ ! -z ${all} ]; then
update_px4_ros_com
echo "-------------------------------------------------------------------------------------------------------"
update_px4_msgs
elif [ ! -z ${px4_ros_com} ]; then
update_px4_ros_com
echo "-------------------------------------------------------------------------------------------------------"
elif [ ! -z ${px4_msgs} ]; then
update_px4_msgs
fi
echo -e "-------------------------------- \033[0;32mUpdate successful!\033[0m ---------------------------------"
echo "-------------------------------------------------------------------------------------------------------"
exit 0
else
echo -e "-- \033[0;31mWorkspace directory doesn't exist...\033[0m"
echo -e "---------------------------------- \033[0;31mUpdate failed!\033[0m -----------------------------------"
echo "-------------------------------------------------------------------------------------------------------"
exit $ERRCODE
fi
-1
View File
@@ -48,7 +48,6 @@ 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_MICRODDS_CLIENT=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
+2 -1
View File
@@ -34,6 +34,7 @@ CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_DRIVERS_TRANSPONDER_SAGETECH_MXS=y
CONFIG_DRIVERS_UAVCAN=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
@@ -52,6 +53,7 @@ CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=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
@@ -61,7 +63,6 @@ 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_MICRODDS_CLIENT=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
@@ -15,6 +15,7 @@ CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y
CONFIG_DRIVERS_MAGNETOMETER_AKM_AK8963=y
CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y
CONFIG_DRIVERS_OSD=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
-1
View File
@@ -50,7 +50,6 @@ 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_MICRODDS_CLIENT=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
-1
View File
@@ -29,7 +29,6 @@ CONFIG_MODULES_MAVLINK=y
CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_MICRODDS_CLIENT=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
-1
View File
@@ -56,7 +56,6 @@ 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_MICRODDS_CLIENT=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
-1
View File
@@ -53,7 +53,6 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_MICRODDS_CLIENT=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
-1
View File
@@ -52,7 +52,6 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_MICRODDS_CLIENT=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
-1
View File
@@ -53,7 +53,6 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_MICRODDS_CLIENT=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
-1
View File
@@ -66,7 +66,6 @@ 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_MICRODDS_CLIENT=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
+1
View File
@@ -0,0 +1 @@
CONFIG_MODULES_MICRORTPS_BRIDGE=y
+2 -1
View File
@@ -36,6 +36,7 @@ CONFIG_DRIVERS_UAVCAN=y
CONFIG_BOARD_UAVCAN_INTERFACES=1
CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2
CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
@@ -53,6 +54,7 @@ CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=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
@@ -62,7 +64,6 @@ 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_MICRODDS_CLIENT=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
@@ -62,7 +62,6 @@ 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_MICRODDS_CLIENT=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
@@ -62,7 +62,6 @@ 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_MICRODDS_CLIENT=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
@@ -0,0 +1 @@
CONFIG_MODULES_MICRORTPS_BRIDGE=y
-1
View File
@@ -63,7 +63,6 @@ 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_MICRODDS_CLIENT=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
+1
View File
@@ -0,0 +1 @@
CONFIG_MODULES_MICRORTPS_BRIDGE=y
-1
View File
@@ -62,7 +62,6 @@ 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_MICRODDS_CLIENT=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
+1
View File
@@ -0,0 +1 @@
CONFIG_MODULES_MICRORTPS_BRIDGE=y
+2 -3
View File
@@ -41,7 +41,6 @@ CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
@@ -50,7 +49,6 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_FW_ATT_CONTROL=y
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_FW_POS_CONTROL_L1=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
@@ -66,7 +64,7 @@ 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_MICRODDS_CLIENT=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
@@ -77,6 +75,7 @@ CONFIG_MODULES_SIMULATION_SENSOR_GPS_SIM=y
CONFIG_MODULES_SIMULATION_SENSOR_MAG_SIM=y
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
@@ -127,6 +127,7 @@ CONFIG_MTD_RAMTRON=y
CONFIG_NETDEV_PHY_IOCTL=y
CONFIG_NETINIT_THREAD=y
CONFIG_NETINIT_THREAD_PRIORITY=49
CONFIG_NETUTILS_TELNETD=y
CONFIG_NET_ARP_IPIN=y
CONFIG_NET_ARP_SEND=y
CONFIG_NET_BROADCAST=y
@@ -156,6 +157,7 @@ CONFIG_NSH_DISABLE_UNAME=y
CONFIG_NSH_DISABLE_WGET=y
CONFIG_NSH_DISABLE_XD=y
CONFIG_NSH_FILEIOSIZE=512
CONFIG_NSH_IOBUFFER_SIZE=256
CONFIG_NSH_LINELEN=128
CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
@@ -163,6 +165,8 @@ CONFIG_NSH_READLINE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_TELNETD_CLIENTSTACKSIZE=1280
CONFIG_NSH_TELNETD_DAEMONSTACKSIZE=1024
CONFIG_NSH_VARS=y
CONFIG_PIPES=y
CONFIG_PREALLOC_TIMERS=50
@@ -200,6 +204,10 @@ CONFIG_SYSTEM_CUTERM_DEFAULT_BAUD=57600
CONFIG_SYSTEM_NSH=y
CONFIG_SYSTEM_PING=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_TELNET_IOTHREAD_STACKSIZE=512
CONFIG_TELNET_MAXLCLIENTS=1
CONFIG_TELNET_RXBUFFER_SIZE=128
CONFIG_TELNET_TXBUFFER_SIZE=128
CONFIG_UART0_IFLOWCONTROL=y
CONFIG_UART0_OFLOWCONTROL=y
CONFIG_UART1_RXBUFSIZE=600
+1
View File
@@ -0,0 +1 @@
CONFIG_MODULES_MICRORTPS_BRIDGE=y
-1
View File
@@ -68,7 +68,6 @@ 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_MICRODDS_CLIENT=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
@@ -95,9 +95,7 @@ CONFIG_KINETIS_SDHC=y
CONFIG_KINETIS_SERIALBRK_BSDCOMPAT=y
CONFIG_KINETIS_SPI0=y
CONFIG_KINETIS_SPI1=y
CONFIG_KINETIS_SPI1_DMA=y
CONFIG_KINETIS_SPI2=y
CONFIG_KINETIS_SPI_DMA=y
CONFIG_KINETIS_UART0=y
CONFIG_KINETIS_UART0_RXDMA=y
CONFIG_KINETIS_UART1=y
@@ -127,6 +125,7 @@ CONFIG_MTD_RAMTRON=y
CONFIG_NETDEV_PHY_IOCTL=y
CONFIG_NETINIT_THREAD=y
CONFIG_NETINIT_THREAD_PRIORITY=49
CONFIG_NETUTILS_TELNETD=y
CONFIG_NET_ARP_IPIN=y
CONFIG_NET_ARP_SEND=y
CONFIG_NET_BROADCAST=y
@@ -156,6 +155,7 @@ CONFIG_NSH_DISABLE_UNAME=y
CONFIG_NSH_DISABLE_WGET=y
CONFIG_NSH_DISABLE_XD=y
CONFIG_NSH_FILEIOSIZE=512
CONFIG_NSH_IOBUFFER_SIZE=256
CONFIG_NSH_LINELEN=128
CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
@@ -163,6 +163,8 @@ CONFIG_NSH_READLINE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_TELNETD_CLIENTSTACKSIZE=1280
CONFIG_NSH_TELNETD_DAEMONSTACKSIZE=1024
CONFIG_NSH_VARS=y
CONFIG_PIPES=y
CONFIG_PREALLOC_TIMERS=50
@@ -200,6 +202,10 @@ CONFIG_SYSTEM_CUTERM_DEFAULT_BAUD=57600
CONFIG_SYSTEM_NSH=y
CONFIG_SYSTEM_PING=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_TELNET_IOTHREAD_STACKSIZE=512
CONFIG_TELNET_MAXLCLIENTS=1
CONFIG_TELNET_RXBUFFER_SIZE=128
CONFIG_TELNET_TXBUFFER_SIZE=128
CONFIG_UART1_RXBUFSIZE=600
CONFIG_UART1_TXBUFSIZE=1100
CONFIG_UART4_BAUD=57600
+1
View File
@@ -0,0 +1 @@
CONFIG_MODULES_MICRORTPS_BRIDGE=y
-1
View File
@@ -45,7 +45,6 @@ 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_MICRODDS_CLIENT=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
@@ -236,7 +236,6 @@
*/
#define DIRECT_PWM_OUTPUT_CHANNELS 8
#define BOARD_NUM_IO_TIMERS 8
// Input Capture not supported on MVP
+3 -8
View File
@@ -76,14 +76,9 @@
#define rENBL REG(IMXRT_TMR_ENBL_OFFSET)
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
initIOPWM(PWM::FlexPWM2, PWM::Submodule0),
initIOPWM(PWM::FlexPWM2, PWM::Submodule1),
initIOPWM(PWM::FlexPWM2, PWM::Submodule2),
initIOPWM(PWM::FlexPWM2, PWM::Submodule3),
initIOPWM(PWM::FlexPWM3, PWM::Submodule2),
initIOPWM(PWM::FlexPWM3, PWM::Submodule0),
initIOPWM(PWM::FlexPWM4, PWM::Submodule2),
initIOPWM(PWM::FlexPWM4, PWM::Submodule0),
initIOPWM(PWM::FlexPWM2),
initIOPWM(PWM::FlexPWM3),
initIOPWM(PWM::FlexPWM4),
};
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
-1
View File
@@ -29,7 +29,6 @@ CONFIG_MODULES_MAVLINK=y
CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_MICRODDS_CLIENT=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
+1 -1
View File
@@ -100,7 +100,7 @@ else
# V3 build hwtypecmp supports V2|V2M|V30
if ! ver hwtypecmp V2M
then
mpu9250 -s -b 1 -R 14 -q start
mpu9250 -s -b 1 -R 14 start
# else: On the PixhawkMini the mpu9250 has been disabled due to HW errata
fi
+1 -1
View File
@@ -100,7 +100,7 @@ else
# V3 build hwtypecmp supports V2|V2M|V30
if ! ver hwtypecmp V2M
then
mpu9250 -s -b 1 -R 14 -q start
mpu9250 -s -b 1 -R 14 start
# else: On the PixhawkMini the mpu9250 has been disabled due to HW errata
fi
+1
View File
@@ -0,0 +1 @@
CONFIG_MODULES_MICRORTPS_BRIDGE=y
+1 -3
View File
@@ -1,7 +1,5 @@
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n
CONFIG_BOARD_CRYPTO=y
CONFIG_DRIVERS_STUB_KEYSTORE=y
CONFIG_DRIVERS_SW_CRYPTO=y
CONFIG_DRIVERS_STUB_KEYSTORE=y
CONFIG_PUBLIC_KEY0="../../../Tools/test_keys/key0.pub"
CONFIG_PUBLIC_KEY1="../../../Tools/test_keys/rsa2048.pub"
-1
View File
@@ -73,7 +73,6 @@ 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_MICRODDS_CLIENT=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
+4 -7
View File
@@ -4,13 +4,9 @@ CONFIG_COMMON_DIFFERENTIAL_PRESSURE=n
CONFIG_COMMON_DISTANCE_SENSOR=n
CONFIG_COMMON_OPTICAL_FLOW=n
CONFIG_COMMON_TELEMETRY=n
CONFIG_DRIVERS_CAMERA_CAPTURE=n
CONFIG_DRIVERS_CAMERA_TRIGGER=n
CONFIG_DRIVERS_IRLOCK=n
CONFIG_DRIVERS_PCA9685=n
CONFIG_DRIVERS_PCA9685_PWM_OUT=n
CONFIG_DRIVERS_PWM_INPUT=n
CONFIG_DRIVERS_OSD=n
CONFIG_DRIVERS_ROBOCLAW=n
CONFIG_DRIVERS_RPM=n
CONFIG_DRIVERS_UAVCAN=n
CONFIG_EXAMPLES_FAKE_GPS=n
CONFIG_MODULES_AIRSPEED_SELECTOR=n
@@ -21,8 +17,8 @@ CONFIG_MODULES_FW_ATT_CONTROL=n
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_FW_POS_CONTROL_L1=n
CONFIG_MODULES_GYRO_FFT=n
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n
CONFIG_MODULES_ROVER_POS_CONTROL=n
CONFIG_MODULES_SIH=n
CONFIG_MODULES_TEMPERATURE_COMPENSATION=n
CONFIG_MODULES_UUV_ATT_CONTROL=n
CONFIG_MODULES_UUV_POS_CONTROL=n
@@ -34,6 +30,7 @@ CONFIG_SYSTEMCMDS_DUMPFILE=n
CONFIG_SYSTEMCMDS_GPIO=n
CONFIG_SYSTEMCMDS_I2CDETECT=n
CONFIG_SYSTEMCMDS_LED_CONTROL=n
CONFIG_SYSTEMCMDS_MOTOR_TEST=n
CONFIG_SYSTEMCMDS_MTD=n
CONFIG_SYSTEMCMDS_NSHTERM=n
CONFIG_SYSTEMCMDS_REFLECT=n
+3
View File
@@ -0,0 +1,3 @@
CONFIG_DRIVERS_HEATER=n
CONFIG_DRIVERS_OSD=n
CONFIG_MODULES_MICRORTPS_BRIDGE=y
+7 -7
View File
@@ -1,43 +1,43 @@
# CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE is not set
CONFIG_COMMON_BAROMETERS=n
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=n
CONFIG_COMMON_DISTANCE_SENSOR=n
CONFIG_COMMON_HYGROMETERS=n
CONFIG_COMMON_TELEMETRY=n
CONFIG_DRIVERS_ADC_ADS1115=n
CONFIG_DRIVERS_BATT_SMBUS=n
CONFIG_DRIVERS_CAMERA_CAPTURE=n
CONFIG_DRIVERS_CAMERA_TRIGGER=n
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=n
CONFIG_COMMON_DISTANCE_SENSOR=n
CONFIG_DRIVERS_HEATER=n
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=n
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=n
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20689=n
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=n
CONFIG_DRIVERS_IRLOCK=n
CONFIG_DRIVERS_OSD=n
CONFIG_DRIVERS_PCA9685=n
CONFIG_DRIVERS_PCA9685_PWM_OUT=n
CONFIG_DRIVERS_POWER_MONITOR_INA226=n
CONFIG_DRIVERS_PWM_INPUT=n
CONFIG_DRIVERS_PWM_OUT_SIM=n
CONFIG_DRIVERS_ROBOCLAW=n
CONFIG_DRIVERS_RPM=n
CONFIG_DRIVERS_SMART_BATTERY_BATMON=n
CONFIG_DRIVERS_UAVCAN=n
CONFIG_EXAMPLES_FAKE_GPS=n
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n
CONFIG_MODULES_CAMERA_FEEDBACK=n
CONFIG_MODULES_ESC_BATTERY=n
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_GIMBAL=n
CONFIG_MODULES_GYRO_CALIBRATION=n
CONFIG_MODULES_GYRO_FFT=n
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_ROVER_POS_CONTROL=n
CONFIG_MODULES_SIH=n
CONFIG_MODULES_TEMPERATURE_COMPENSATION=n
CONFIG_MODULES_UUV_ATT_CONTROL=n
CONFIG_MODULES_UUV_POS_CONTROL=n
CONFIG_SYSTEMCMDS_MOTOR_TEST=n
CONFIG_SYSTEMCMDS_REFLECT=n
CONFIG_SYSTEMCMDS_SERIAL_TEST=n
CONFIG_BOARD_CONSTRAINED_FLASH=y
CONFIG_BOARD_TESTING=y
CONFIG_DRIVERS_BAROMETER_MS5611=y
+3 -2
View File
@@ -4,8 +4,8 @@ CONFIG_COMMON_DIFFERENTIAL_PRESSURE=n
CONFIG_COMMON_HYGROMETERS=n
CONFIG_COMMON_TELEMETRY=n
CONFIG_DRIVERS_ADC_ADS1115=n
CONFIG_DRIVERS_GPS=n
CONFIG_DRIVERS_HEATER=n
CONFIG_DRIVERS_GPS=n
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=n
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=n
CONFIG_DRIVERS_IRLOCK=n
@@ -14,14 +14,15 @@ CONFIG_DRIVERS_PCA9685=n
CONFIG_DRIVERS_PCA9685_PWM_OUT=n
CONFIG_DRIVERS_PWM_INPUT=n
CONFIG_DRIVERS_ROBOCLAW=n
CONFIG_DRIVERS_RPM=n
CONFIG_DRIVERS_SMART_BATTERY_BATMON=n
CONFIG_EXAMPLES_FAKE_GPS=n
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n
CONFIG_MODULES_ESC_BATTERY=n
CONFIG_MODULES_GYRO_FFT=n
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n
CONFIG_MODULES_MICRODDS_CLIENT=n
CONFIG_MODULES_ROVER_POS_CONTROL=n
CONFIG_MODULES_SIH=n
CONFIG_MODULES_TEMPERATURE_COMPENSATION=n
CONFIG_MODULES_UUV_ATT_CONTROL=n
CONFIG_MODULES_UUV_POS_CONTROL=n
+7 -3
View File
@@ -9,8 +9,7 @@ CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1"
CONFIG_BOARD_SERIAL_PPB="/dev/ttyS3"
CONFIG_DRIVERS_ADC_ADS1115=y
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_DRIVERS_BAROMETER_BMP388=y
CONFIG_DRIVERS_BAROMETER_MS5611=y
CONFIG_COMMON_BAROMETERS=y
CONFIG_DRIVERS_BATT_SMBUS=y
CONFIG_DRIVERS_CAMERA_CAPTURE=y
CONFIG_DRIVERS_CAMERA_TRIGGER=y
@@ -31,9 +30,12 @@ CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_COMMON_OSD=y
CONFIG_DRIVERS_PCA9685=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
CONFIG_DRIVERS_PWM_INPUT=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_PX4IO=y
CONFIG_COMMON_RC=y
@@ -74,7 +76,6 @@ 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_MICRODDS_CLIENT=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_PAYLOAD_DELIVERER=y
CONFIG_MODULES_RC_UPDATE=y
@@ -87,6 +88,7 @@ CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
@@ -101,6 +103,7 @@ CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_REFLECT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SD_STRESS=y
CONFIG_SYSTEMCMDS_SERIAL_TEST=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
@@ -109,3 +112,4 @@ CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_USB_CONNECTED=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
CONFIG_EXAMPLES_FAKE_GPS=y
+15
View File
@@ -0,0 +1,15 @@
CONFIG_COMMON_BAROMETERS=n
CONFIG_COMMON_TELEMETRY=n
CONFIG_DRIVERS_OSD=n
CONFIG_EXAMPLES_FAKE_GPS=n
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=n
CONFIG_SYSTEMCMDS_DUMPFILE=n
CONFIG_SYSTEMCMDS_GPIO=n
CONFIG_SYSTEMCMDS_MOTOR_TEST=n
CONFIG_SYSTEMCMDS_REFLECT=n
CONFIG_SYSTEMCMDS_SD_BENCH=n
CONFIG_SYSTEMCMDS_SD_STRESS=n
CONFIG_SYSTEMCMDS_SERIAL_TEST=n
CONFIG_DRIVERS_BAROMETER_BMP388=y
CONFIG_DRIVERS_BAROMETER_MS5611=y
CONFIG_MODULES_MICRORTPS_BRIDGE=y

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