diff --git a/docs/en/SUMMARY.md b/docs/en/SUMMARY.md index eee592b4f3b0..37b0c914a735 100644 --- a/docs/en/SUMMARY.md +++ b/docs/en/SUMMARY.md @@ -162,7 +162,6 @@ - [ARK Electronics ARKV6X](flight_controller/ark_v6x.md) - [ARK FPV Flight Controller](flight_controller/ark_fpv.md) - [ARK Pi6X Flow Flight Controller](flight_controller/ark_pi6x.md) - - [CUAV X7](flight_controller/cuav_x7.md) - [CUAV Nora](flight_controller/cuav_nora.md) - [CUAV V5+ (FMUv5)](flight_controller/cuav_v5_plus.md) - [Wiring Quickstart](assembly/quick_start_cuav_v5_plus.md) @@ -183,8 +182,7 @@ - [ModalAI Flight Core v1](flight_controller/modalai_fc_v1.md) - [ModalAI VOXL Flight](flight_controller/modalai_voxl_flight.md) - [ModalAI VOXL 2](flight_controller/modalai_voxl_2.md) - - [mRobotics-X2.1 (FMUv2)](flight_controller/mro_x2.1.md) - - [mRo Control Zero F7)](flight_controller/mro_control_zero_f7.md) + - [mRo Control Zero F7](flight_controller/mro_control_zero_f7.md) - [Sky-Drones AIRLink](flight_controller/airlink.md) - [SPRacing SPRacingH7EXTREME](flight_controller/spracingh7extreme.md) - [ThePeach FCC-K1](flight_controller/thepeach_k1.md) @@ -201,11 +199,13 @@ - [BetaFPV Beta75X 2S Brushless Whoop](complete_vehicles_mc/betafpv_beta75x.md) - [Bitcraze Crazyflie 2.0 ](complete_vehicles_mc/crazyflie2.md) - [Aerotenna OcPoC-Zynq Mini](flight_controller/ocpoc_zynq.md) + - [CUAV X7](flight_controller/cuav_x7.md) - [CUAV v5](flight_controller/cuav_v5.md) - [CUAV Pixhack v3 (FMUv3)](flight_controller/pixhack_v3.md) - [Holybro Kakute F7](flight_controller/kakutef7.md) - [Holybro Pixfalcon](flight_controller/pixfalcon.md) - [Holybro pix32 (FMUv2)](flight_controller/holybro_pix32.md) + - [mRo X2.1 (FMUv2)](flight_controller/mro_x2.1.md) - [mRo AUAV-X2](flight_controller/auav_x2.md) - [NXP RDDRONE-FMUK66 FMU](flight_controller/nxp_rddrone_fmuk66.md) - [3DR Pixhawk 1](flight_controller/pixhawk.md) diff --git a/docs/en/advanced/realsense_intel_driver.md b/docs/en/advanced/realsense_intel_driver.md index 766ef8adfa4d..5205950c642f 100644 --- a/docs/en/advanced/realsense_intel_driver.md +++ b/docs/en/advanced/realsense_intel_driver.md @@ -41,7 +41,7 @@ The tutorial is ordered in the following way: In a first part it is shown how to ## Installing ROS Indigo -- Follow instructions given at [ROS indigo installation guide](http://wiki.ros.org/indigo/Installation/Ubuntu): +- Follow instructions given at [ROS indigo installation guide](https://wiki.ros.org/indigo/Installation/Ubuntu): - Install Desktop-Full version. - Execute steps described in the sections "Initialize rosdep" and "Environment setup". @@ -54,7 +54,6 @@ The tutorial is ordered in the following way: In a first part it is shown how to ``` - Download and install the driver: - - Clone [RealSense_ROS repository](https://github.com/bestmodule/RealSense_ROS): ```sh @@ -62,7 +61,6 @@ The tutorial is ordered in the following way: In a first part it is shown how to ``` - Follow instructions given in [here](https://github.com/bestmodule/RealSense_ROS/tree/master/r200_install). - - Press the enter button when the questions whether to install the following installation packages show up: ```sh @@ -86,11 +84,9 @@ The tutorial is ordered in the following way: In a first part it is shown how to - After the installation has completed, reboot the Virtual Machine. - Test camera driver: - - Connect the Intel RealSense camera head with the computer with a USB3 cable that is plugged into a USB3 receptacle on the computer. - Click on Devices->USB-> Intel Corp Intel RealSense 3D Camera R200 in the menu bar of the Virtual Box, in order to forward the camera USB connection to the Virtual Machine. - Execute the file [unpacked folder]/Bin/DSReadCameraInfo: - - If the following error message appears, unplug the camera (physically unplug USB cable from the computer). Plug it in again + Click on Devices->USB-> Intel Corp Intel RealSense 3D Camera R200 in the menu bar of the Virtual Box again and execute again the file [unpacked folder]/Bin/DSReadCameraInfo. ```sh diff --git a/docs/en/advanced/system_tunes.md b/docs/en/advanced/system_tunes.md index 8b9b1b75efb9..c9804a6946dc 100644 --- a/docs/en/advanced/system_tunes.md +++ b/docs/en/advanced/system_tunes.md @@ -25,7 +25,7 @@ On Windows, one option is to use _Melody Master_ within _Dosbox_. The steps for using the software are: -1. Download [DosBox](http://www.dosbox.com/) and install the app +1. Download [DosBox](https://www.dosbox.com/) and install the app 1. Download [Melody Master](ftp://archives.thebbs.org/ansi_utilities/melody21.zip) and unzip into a new directory 1. Open the _Dosbox_ console 1. Mount the melody master directory in Dosbox as shown below: diff --git a/docs/en/advanced_config/bootloader_update.md b/docs/en/advanced_config/bootloader_update.md index 79c27b4e33c4..89669acc81fd 100644 --- a/docs/en/advanced_config/bootloader_update.md +++ b/docs/en/advanced_config/bootloader_update.md @@ -109,7 +109,7 @@ The following steps explain how you can "manually" update the bootloader using a Bootloaders from [PX4/PX4-Bootloader](https://github.com/PX4/PX4-Bootloader) are named with the pattern `*_bl.elf`. ::: -4. The _gdb terminal_ appears and it should display the following output: +4. The _gdb terminal_ appears and it should display (something like) the following output: ```sh GNU gdb (GNU Tools for Arm Embedded Processors 7-2017-q4-major) 8.0.50.20171128-git @@ -121,9 +121,9 @@ The following steps explain how you can "manually" update the bootloader using a This GDB was configured as "--host=x86_64-linux-gnu --target=arm-none-eabi". Type "show configuration" for configuration details. For bug reporting instructions, please see: - . + . Find the GDB manual and other documentation resources online at: - . + . For help, type "help". Type "apropos word" to search for commands related to "word"... Reading symbols from px4fmuv5_bl.elf...done. diff --git a/docs/en/assembly/vibration_isolation.md b/docs/en/assembly/vibration_isolation.md index a13f9d5de3d1..9e1e1522d9e0 100644 --- a/docs/en/assembly/vibration_isolation.md +++ b/docs/en/assembly/vibration_isolation.md @@ -31,5 +31,5 @@ A few of simple steps that may reduce vibrations are: Some references that you may find useful are: -- [An Introduction to Shock & Vibration Response Spectra, Tom Irvine](http://www.vibrationdata.com/tutorials2/srs_intr.pdf) (free paper) +- [An Introduction to Shock & Vibration Response Spectra, Tom Irvine](https://www.vibrationdata.com/tutorials2/srs_intr.pdf) (free paper) - [Structural Dynamics and Vibration in Practice - An Engineering Handbook, Douglas Thorby](https://books.google.ch/books?id=PwzDuWDc8AgC&printsec=frontcover) (preview). diff --git a/docs/en/complete_vehicles_mc/index.md b/docs/en/complete_vehicles_mc/index.md index 24c477081f00..d5d2cf914caa 100644 --- a/docs/en/complete_vehicles_mc/index.md +++ b/docs/en/complete_vehicles_mc/index.md @@ -19,12 +19,12 @@ They may come either fully assembled or in parts. This section lists vehicles that are sold fully assembled and ready to fly (RTF), with PX4 installed. -- [Teal One](https://tealdrones.com/teal-one/) - [ModalAI Starling](../complete_vehicles_mc/modalai_starling.md) - [ModalAI Sentinel](https://www.modalai.com/sentinel) - [MindRacer 210](../complete_vehicles_mc/mindracer210.md) - [NanoMind 110](../complete_vehicles_mc/nanomind110.md) - [Amovlab F410](../complete_vehicles_mc/amov_F410_drone.md) +- [Teal One](https://px4.io/project/teal-one/) ([superseded](https://tealdrones.com/solutions/teal-2/)) ## PX4 Compatible diff --git a/docs/en/complete_vehicles_mc/px4_vision_kit.md b/docs/en/complete_vehicles_mc/px4_vision_kit.md index 252a1cfacb66..f13d4f6b9ec1 100644 --- a/docs/en/complete_vehicles_mc/px4_vision_kit.md +++ b/docs/en/complete_vehicles_mc/px4_vision_kit.md @@ -8,7 +8,6 @@ The kit contains a near-ready-to-fly carbon-fibre quadcopter equipped with a _Pi The guide explains the minimal additional setup required to get the vehicle ready to fly (installing an RC system and battery). It also covers the first flight, and how to get started with modifying the computer vision code. - :::warning PX4 no longer supports the avoidance software described in this document: @@ -16,7 +15,7 @@ PX4 no longer supports the avoidance software described in this document: - [Path Planning Interface](../computer_vision/path_planning_interface.md), along with obstacle avoidance in missions, and safe landing. A USB stick is included in the kit with an example of an obstacle avoidance feature implementation based on this software. -This example is intended as a reference only and serves to demonstrate the capabilities of the platform. +This example is intended as a reference only and serves to demonstrate the capabilities of the platform. ::: ::: tip @@ -73,7 +72,6 @@ What's inside the PX4 Vision V1 can be found here in the [PX4 v1.13 Docs here](h The PX4 Vision DevKit contains following components: - Core Components: - - 1x Pixhawk 4 or Pixhawk 6C (for v1.5) flight controller - 1x PMW3901 optical flow sensor - 1x TOF Infrared distance sensor (PSK‐CM8JL65‐CC5) @@ -94,7 +92,6 @@ The PX4 Vision DevKit contains following components: - WiFi 802.11 b/g/n @ 2.4 GHz (attached to external antenna #1). Allows computer to access home WiFi network for Internet access/updates. - Mechanical Specification: - - Frame: Full 5mm 3k carbon fiber twill - Motors: T-MOTOR KV1750 - ESC: BEHEli-S 20A ESC @@ -105,7 +102,6 @@ The PX4 Vision DevKit contains following components: - Telemetry: ESP8266 connected to flight controller (attached to external antenna #2). Enables wireless connection to the ground station. - A USB2.0 stick with pre-flashed software that bundles: - - Ubuntu 18.04 LTS - ROS Melodic - Occipital Structure Core ROS driver @@ -133,7 +129,6 @@ In addition, users will need ground station hardware/software: ## First-time Setup 1. Attach a [compatible RC receiver](../getting_started/rc_transmitter_receiver.md#connecting-receivers) to the vehicle (not supplied with kit): - - Remove/unscrew the top plate (where the battery goes) using an H2.0 hex key tool. - [Connect the receiver to the flight controller](../assembly/quick_start_pixhawk4.md#radio-control). - Re-attach the top plate. @@ -155,7 +150,6 @@ In addition, users will need ground station hardware/software: Ensure propellers are removed before connecting the battery. ::: 1. Connect the ground station to the vehicle WiFi network (after a few seconds) using the following default credentials: - - **SSID:** pixhawk4 - **Password:** pixhawk4 @@ -171,7 +165,6 @@ In addition, users will need ground station hardware/software: The vehicle should arrive pre-calibrated (e.g. with firmware, airframe, battery, and sensors all setup). You will however need to calibrate the radio system (that you just connected) and it is often worth re-doing the compass calibration. ::: - - [Calibrate the Radio System](../config/radio.md) - [Calibrate the Compass](../config/compass.md) @@ -182,7 +175,6 @@ In addition, users will need ground station hardware/software: ::: We recommend RC controller switches are define for: - - [Position Mode](../flight_modes_mc/position.md) - a safe manual flight mode that can be used to test collision prevention. - [Mission Mode](../flight_modes_mc/mission.md) - run missions and test obstacle avoidance. - [Return Mode](../flight_modes_mc/return.md) - return vehicle safely to its launch point and land. @@ -190,7 +182,6 @@ In addition, users will need ground station hardware/software: 1. Attach the propellers with the rotations as shown: ![Motor Order Diagram](../../assets/hardware/px4_vision_devkit/motor_order_diagram.png) - - The propellers directions can be determined from the labels: _6045_ (normal, counter-clockwise) and _6045_**R** (reversed, clockwise). ![Propeller identification](../../assets/hardware/px4_vision_devkit/propeller_directions.jpg) @@ -212,7 +203,6 @@ When the vehicle setup described above is complete: ::: 1. Check that the avoidance system has started properly: - - The _QGroundControl_ notification log displays the message: **Avoidance system connected**. ![QGC Log showing avoidance system has started](../../assets/hardware/px4_vision_devkit/qgc_console_vision_system_started.jpg) @@ -309,7 +299,6 @@ To login to the companion computer: 1. Connect a keyboard and mouse to the _UP Core_ via port `USB2`: ![UP Core: USB2](../../assets/hardware/px4_vision_devkit/upcore_port_usb2.png) - - Use the USB-JST cable from the kit to get a USB A connector ![USB to JST cable](../../assets/hardware/px4_vision_devkit/usb_jst_cable.jpg) @@ -323,7 +312,6 @@ To login to the companion computer: The Ubuntu login screen should then appear on the monitor. 1. Login to the _UP Core_ using the credentials: - - **Username:** px4vision - **Password:** px4vision @@ -375,7 +363,7 @@ To integrate a different planner, this needs to be disabled. ``` The ROS workspace is placed in `~/catkin_ws`. -For reference on developing in ROS and using the catkin workspace, see the [ROS catkin tutorials](http://wiki.ros.org/catkin/Tutorials). +For reference on developing in ROS and using the catkin workspace, see the [ROS catkin tutorials](https://wiki.ros.org/catkin/Tutorials). ### Developing PX4 Firmware @@ -385,7 +373,6 @@ You can modify PX4 itself, and [install it as custom firmware](../config/firmwar - Select the _PX4 Vision DevKit_ airframe after loading new firmware: ![Airframe Selection - PX4 Vision DevKit](../../assets/hardware/px4_vision_devkit/qgc_airframe_px4_vision_devkit_platform.jpg) - ## PX4 Vision Carrier Board Pinouts Information for the PX4 Vision 1.15 can be found at [https://docs.holybro.com](https://docs.holybro.com/drone-development-kit/px4-vision-dev-kit-v1.5). diff --git a/docs/en/computer_vision/visual_inertial_odometry.md b/docs/en/computer_vision/visual_inertial_odometry.md index 96f9a10c8a9f..6b5d9ff178b0 100644 --- a/docs/en/computer_vision/visual_inertial_odometry.md +++ b/docs/en/computer_vision/visual_inertial_odometry.md @@ -42,9 +42,7 @@ To setup ROS and PX4: - [Verify that VIO is set up correctly](#verify_estimate) before your first flight! - - -### ROS VIO node +### ROS VIO node {#vio_ros_node} In this suggested setup, a ROS node is required to @@ -54,17 +52,16 @@ In this suggested setup, a ROS node is required to The implementation of the ROS node will be specific to the camera used and will need to be developed to use the interface and drivers appropriate for the camera. -The odometry messages should be of the type [`nav_msgs/Odometry`](http://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Odometry.html) and published to the topic `/mavros/odometry/out`. +The odometry messages should be of the type [`nav_msgs/Odometry`](https://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Odometry.html) and published to the topic `/mavros/odometry/out`. -System status messages of the type [`mavros_msgs/CompanionProcessStatus`](https://github.com/mavlink/mavros/blob/master/mavros_msgs/msg/CompanionProcessStatus.msg) should be published to the topic `/mavros/companion_process/status`. These should identify the component as `MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY` (197) and indicate the `state` of the system. Recommended status values are: +System status messages of the type [`mavros_msgs/CompanionProcessStatus`](https://github.com/mavlink/mavros/blob/master/mavros_msgs/msg/CompanionProcessStatus.msg) should be published to the topic `/mavros/companion_process/status`. +These should identify the component as `MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY` (197) and indicate the `state` of the system. Recommended status values are: - `MAV_STATE_ACTIVE` when the VIO system is functioning as expected, - `MAV_STATE_CRITICAL` when the VIO system is functioning, but with low confidence, and - `MAV_STATE_FLIGHT_TERMINATION` when the system has failed or the estimate confidence is unacceptably low. - - -### PX4 Tuning +### PX4 Tuning {#ekf2_tuning} The following parameters must be set to use external position information with EKF2. @@ -79,9 +76,7 @@ These can be set in _QGroundControl_ > **Vehicle Setup > Parameters > EKF2** (re For more detailed/additional information, see: [Using PX4's Navigation Filter (EKF2) > External Vision System](../advanced_config/tuning_the_ecl_ekf.md#external-vision-system). - - -#### Tuning EKF2_EV_DELAY +#### Tuning EKF2_EV_DELAY {#tuning-EKF2_EV_DELAY} [EKF2_EV_DELAY](../advanced_config/parameter_reference.md#EKF2_EV_DELAY) is the _Vision Position Estimator delay relative to IMU measurements_. In other words, it is the difference between the vision system timestamp and the "actual" capture time that would have been recorded by the IMU clock (the "base clock" for EKF2). @@ -100,9 +95,7 @@ A plot of external data vs. onboard estimate (as above) can be generated using [ The value can further be tuned by varying the parameter to find the value that yields the lowest EKF innovations during dynamic maneuvers. - - -## Check/Verify VIO Estimate +## Check/Verify VIO Estimate {#verify_estimate} ::: info The [MAV_ODOM_LP](../advanced_config/parameter_reference.md#MAV_ODOM_LP) parameter mentioned below was removed in PX4 v1.14. @@ -147,11 +140,9 @@ First, make sure MAVROS is able to connect successfully to the flight controller If it is connecting properly common problems/solutions are: - **Problem:** I get drift / flyaways when the drone flies, but not when I carry it around with the props off. - - If using the [T265](../peripherals/camera_t265_vio.md) try soft-mounting it (this camera is very sensitive to high-frequency vibrations). - **Problem:** I get toilet-bowling when VIO is enabled. - - Make sure the orientation of the camera matches the transform in the launch file. Use the _QGroundControl_ [MAVLink Inspector](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/analyze_view/mavlink_inspector.html) to verify that the velocities in the `ODOMETRY` message coming from MAVROS are aligned to the FRD coordinate system. diff --git a/docs/en/concept/control_allocation.md b/docs/en/concept/control_allocation.md index 2ed4156f0660..e0df52029d32 100644 --- a/docs/en/concept/control_allocation.md +++ b/docs/en/concept/control_allocation.md @@ -42,7 +42,7 @@ Notes: - publishes the servo trims separately so they can be added as an offset when [testing actuators](../config/actuators.md#actuator-testing) (using the test sliders). - the output drivers: - handle the hardware initialization and update - - use a shared library [src/libs/mixer_module](https://github.com/PX4/PX4-Autopilot/blob/main/src/lib/mixer_module/). + - use a shared library [src/libs/mixer_module](https://github.com/PX4/PX4-Autopilot/blob/main/src/lib/mixer_module). The driver defines a parameter prefix, e.g. `PWM_MAIN` that the library then uses for configuration. Its main task is to select from the input topics and assign the right data to the outputs based on the user set `_FUNCx` parameter values. For example if `PWM_MAIN_FUNC3` is set to **Motor 2**, the 3rd output is set to the 2nd motor from `actuator_motors`. diff --git a/docs/en/concept/system_startup.md b/docs/en/concept/system_startup.md index d147c38aa22d..7a135bfd9d06 100644 --- a/docs/en/concept/system_startup.md +++ b/docs/en/concept/system_startup.md @@ -31,7 +31,7 @@ For that to work, a few things are required: For that the `bin` directory with the symbolic links is added to the `PATH` variable right before executing the startup scripts. - The shell starts each module as a new (client) process. Each client process needs to communicate with the main instance of px4 (the server), where the actual modules are running as threads. - This is done through a [UNIX socket](http://man7.org/linux/man-pages/man7/unix.7.html). + This is done through a [UNIX socket](https://man7.org/linux/man-pages/man7/unix.7.html). The server listens on a socket, to which clients can connect and send a command. The server then sends the output and return code back to the client. - The startup scripts call the module directly, e.g. `commander start`, rather than using the `px4-` prefix. diff --git a/docs/en/config/joystick.md b/docs/en/config/joystick.md index 8ea3756f9400..c0ff87fc734b 100644 --- a/docs/en/config/joystick.md +++ b/docs/en/config/joystick.md @@ -12,7 +12,7 @@ Joysticks are also commonly used to allow developers to fly the vehicle in simul ::: ::: info -_QGroundControl_ uses the cross-platform [SDL2](http://www.libsdl.org/index.php) library to convert joystick movements to MAVLink [MANUAL_CONTROL](https://mavlink.io/en/messages/common.html#MANUAL_CONTROL) messages, which are then sent to PX4 over the telemetry channel. +_QGroundControl_ uses the cross-platform [SDL2](https://www.libsdl.org/index.php) library to convert joystick movements to MAVLink [MANUAL_CONTROL](https://mavlink.io/en/messages/common.html#MANUAL_CONTROL) messages, which are then sent to PX4 over the telemetry channel. In consequence, a joystick-based controller system requires a reliable high bandwidth telemetry channel to ensure that the vehicle is responsive to joystick movements. ::: diff --git a/docs/en/contribute/code.md b/docs/en/contribute/code.md index 38b6b01c8236..87d80dbcba6c 100644 --- a/docs/en/contribute/code.md +++ b/docs/en/contribute/code.md @@ -112,7 +112,7 @@ Currently we have two types of source-based documentation: - Do not add documentation that can trivially be inferred from C++ entity names. - ALWAYS specify units of variables, constants, and input/return parameters where they are defined. - Commonly you may want to add information about corner cases and error handling. - - [Doxgyen](http://www.doxygen.nl/) tags should be used if documentation is needed: `@class`, `@file`, `@param`, `@return`, `@brief`, `@var`, `@see`, `@note`. + - [Doxgyen](https://www.doxygen.nl/) tags should be used if documentation is needed: `@class`, `@file`, `@param`, `@return`, `@brief`, `@var`, `@see`, `@note`. A good example of usage is [src/modules/events/send_event.h](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/events/send_event.h). Please avoid "magic numbers", for example, where does this number in the conditional come from? What about the multiplier on yaw stick input? diff --git a/docs/en/debug/eclipse_jlink.md b/docs/en/debug/eclipse_jlink.md index 14cd86bb3e74..eaf4c7d4afe8 100644 --- a/docs/en/debug/eclipse_jlink.md +++ b/docs/en/debug/eclipse_jlink.md @@ -46,7 +46,6 @@ For more information, see: [https://gnu-mcu-eclipse.github.io/debug/jlink/instal Set it as shown in the screenshot below. ![Eclipse: Segger J-Link Path](../../assets/debug/eclipse_segger_jlink_path.png) 1. Update packs: - - Click the small icon on the top right called _Open Perspective_ and open the _Packs_ perspective. ![Eclipse: Workspace](../../assets/debug/eclipse_workspace_perspective.png) - Click the **update all** button. @@ -61,7 +60,6 @@ For more information, see: [https://gnu-mcu-eclipse.github.io/debug/jlink/instal - The STM32Fxx devices are found in the Keil folder, install by right-clicking and then selecting **install** on the according device for F4 and F7. 1. Setup debug configuration for target: - - Right click project and open the _Settings_ (menu: **C/C++ Build > Settings**) - Choose the _Devices_ Tab, _Devices_ section (Not _Boards_). - Find the FMU chip you wish to debug. @@ -73,7 +71,6 @@ For more information, see: [https://gnu-mcu-eclipse.github.io/debug/jlink/instal 1. Then select _GDB SEGGER J-Link Debugging_ and then the **New config** button on the top left. ![Eclipse: GDB Segger Debug config](../../assets/debug/eclipse_settings_debug_config_gdb_segger.png) 1. Setup build config: - - Give it a name and set the _C/C++ Application_ to the corresponding **.elf** file. - Choose _Disable Auto build_ @@ -96,7 +93,6 @@ This is quite useful since PX4 tends to run many different tasks. To enable this feature for use in Eclipse: 1. You first need to enable `CONFIG_DEBUG_TCBINFO` in the NuttX configuration for your build (to expose the TCB offsets). - - Open a terminal in the root of your PX4-Autopilot source code - In the terminal, open `menuconfig` using the appropriate make target for the build. This will be something like: @@ -136,7 +132,7 @@ Adding missing SVD files for the _Peripheral View_: ![Eclipse: MCU Packages](../../assets/debug/eclipse_mcu_packages.png) -2. Download missing packages from: http://www.keil.com/dd2/Pack/ +2. Download missing packages from: https://www.keil.arm.com/devices/ 3. Open downloaded pack with a decompression tool, and extract the **.SVD** files from: **/CMSIS/SVD**. 4. Select desired **.SVD** file in: **Debug Options > GDB SEGGER JLink Debugging > SVD Path** diff --git a/docs/en/debug/profiling.md b/docs/en/debug/profiling.md index b7b051676020..a9718835a337 100644 --- a/docs/en/debug/profiling.md +++ b/docs/en/debug/profiling.md @@ -9,7 +9,7 @@ PMSP is a shell script that operates by interrupting execution of the firmware p Sampled stack traces are appended into a text file. Once sampling is finished (which normally takes about an hour or more), the collected stack traces are _folded_. The result of _folding_ is another text file that contains the same stack traces, except that all similar stack traces (i.e. those that were obtained at the same point in the program) are joined together, and the number of their occurrences is recorded. -The folded stacks are then fed into the visualization script, for which purpose we employ [FlameGraph - an open source stack trace visualizer](http://www.brendangregg.com/flamegraphs.html). +The folded stacks are then fed into the visualization script, for which purpose we employ [FlameGraph - an open source stack trace visualizer](https://www.brendangregg.com/flamegraphs.html). ## Basic Usage diff --git a/docs/en/debug/system_console.md b/docs/en/debug/system_console.md index 5bcdb2a55ab3..4477fc86c745 100644 --- a/docs/en/debug/system_console.md +++ b/docs/en/debug/system_console.md @@ -72,7 +72,7 @@ screen /dev/ttyXXX BAUDRATE 8N1 ### Windows: PuTTY -Download [PuTTY](http://www.chiark.greenend.org.uk/~sgtatham/putty/download.html) and start it. +Download [PuTTY](https://www.chiark.greenend.org.uk/~sgtatham/putty/latest.html) and start it. Then select 'serial connection' and set the port parameters to: diff --git a/docs/en/dev_log/logging.md b/docs/en/dev_log/logging.md index 5a2f85856982..de8de43b9e64 100644 --- a/docs/en/dev_log/logging.md +++ b/docs/en/dev_log/logging.md @@ -28,7 +28,7 @@ logger help ## Configuration -The logging system is configured by default to collect sensible logs for [flight reporting](../getting_started/flight_reporting.md) with [Flight Review](http://logs.px4.io). +The logging system is configured by default to collect sensible logs for [flight reporting](../getting_started/flight_reporting.md) with [Flight Review](https://logs.px4.io/). Logging may further be configured using the [SD Logging](../advanced_config/parameter_reference.md#sd-logging) parameters. The parameters you are most likely to change are listed below. @@ -185,7 +185,6 @@ There are different clients that support ulog streaming: Also make sure `txerr` stays at 0. If this goes up, either the NuttX sending buffer is too small, the physical link is saturated or the hardware is too slow to handle the data. - ## See Also - [Encrypted logging](../dev_log/log_encryption.md) diff --git a/docs/en/dronecan/cuav_can_pmu.md b/docs/en/dronecan/cuav_can_pmu.md index ab241cc55917..02b993cebd65 100644 --- a/docs/en/dronecan/cuav_can_pmu.md +++ b/docs/en/dronecan/cuav_can_pmu.md @@ -71,4 +71,4 @@ Set the following parameters in _QGroundControl_ [Vehicle Setup > Parameters](.. [CAN PMU Manual](http://manual.cuav.net/power-module/CAN-PMU.pdf) -[CAN PMU Power detection module > Enable CAN PMU > PX4 firmware](http://doc.cuav.net/power-module/can-pmu/en/) (CUAV docs) +[CAN PMU Power detection module > Enable CAN PMU > PX4 firmware](https://doc.cuav.net/power-module/can-pmu/en/) (CUAV docs) diff --git a/docs/en/dronecan/development.md b/docs/en/dronecan/development.md index 48ef25bcdab2..3d9aeca1623f 100644 --- a/docs/en/dronecan/development.md +++ b/docs/en/dronecan/development.md @@ -8,6 +8,6 @@ Additional documentation on how to use Babel/other SLCAN adapters, the DroneCAN ## Debugging with Zubax Babel -A great tool to debug the transmission on the CAN bus is the [Zubax Babel](https://zubax.com/products/babel) in combination with the [GUI tool](http://dronecan.github.io/GUI_Tool/Overview/). +A great tool to debug the transmission on the CAN bus is the [Zubax Babel](https://zubax.com/products/babel) in combination with the [GUI tool](https://dronecan.github.io/GUI_Tool/Overview/). They can also be used independently from Pixhawk hardware in order to test a node or manually control DroneCAN enabled ESCs. diff --git a/docs/en/flight_controller/auav_x2.md b/docs/en/flight_controller/auav_x2.md index e1dc3fe051cd..5908263a8c52 100644 --- a/docs/en/flight_controller/auav_x2.md +++ b/docs/en/flight_controller/auav_x2.md @@ -11,13 +11,13 @@ PX4 does not manufacture this (or any) autopilot. Contact the [manufacturer](https://store.mrobotics.io/) for hardware support or compliance issues. ::: -The [AUAV®](http://www.auav.com/) _AUAV-X2 autopilot_ is based on the [Pixhawk®-project](https://pixhawk.org/) **FMUv2** open hardware design. It runs PX4 on the [NuttX](https://nuttx.apache.org/) OS. +The AUAV-X2 autopilot is based on the [Pixhawk®-project](https://pixhawk.org/) **FMUv2** open hardware design. It runs PX4 on the [NuttX](https://nuttx.apache.org/) OS. ![AUAVX2_case2](../../assets/flight_controller/auav_x2/auavx2_case2.jpg) ## Quick Summary -- Main System-on-Chip: [STM32F427](http://www.st.com/web/en/catalog/mmc/FM141/SC1169/SS1577/LN1789) +- Main System-on-Chip: [STM32F427](https://www.st.com/en/microcontrollers-microprocessors/stm32f427-437.html) - CPU: STM32F427VIT6 ARM microcontroller - Revision 3 - IO: STM32F100C8T6 ARM microcontroller - Sensors: @@ -58,7 +58,7 @@ mRobotics is the distributor for the AUAV Products from August 2017. ## Key Links - [User Manual](http://arsovtech.com/wp-content/uploads/2015/08/AUAV-X2-user-manual-EN.pdf) -- [DIY Drones Post](http://diydrones.com/profiles/blogs/introducing-the-auav-x2-1-flight-controller) +- [DIY Drones Post](https://diydrones.com/profiles/blogs/introducing-the-auav-x2-1-flight-controller) ## Wiring Guide diff --git a/docs/en/flight_controller/autopilot_discontinued.md b/docs/en/flight_controller/autopilot_discontinued.md index cebad2f1e91b..62a0bd0223fa 100644 --- a/docs/en/flight_controller/autopilot_discontinued.md +++ b/docs/en/flight_controller/autopilot_discontinued.md @@ -8,6 +8,7 @@ They are listed because you may be using them in an existing drone, and because - [Drotek DroPix](../flight_controller/dropix.md) (FMUv2) - [Omnibus F4 SD](../flight_controller/omnibus_f4_sd.md) +- [CUAV X7](../flight_controller/cuav_x7.md) - [CUAV v5](../flight_controller/cuav_v5.md) (Pixhawk FMUv5) - [CUAV Pixhack v3](../flight_controller/pixhack_v3.md) (FMUv3) - [Aerotenna OcPoC-Zynq Mini](../flight_controller/ocpoc_zynq.md) @@ -16,6 +17,7 @@ They are listed because you may be using them in an existing drone, and because - [Holybro Pixhawk Mini](../flight_controller/pixhawk_mini.md) (FMUv3) - [Holybro Pixfalcon](../flight_controller/pixfalcon.md) (Pixhawk FMUv2) - [Holybro Pix32](../flight_controller/holybro_pix32.md) (FMUv2) +- [mRobotics-X2.1](../flight_controller/mro_x2.1.md) (FMUv2) - [mRo AUAV-X2](../flight_controller/auav_x2.md) (Pixhawk FMUv2) - [NXP FMUK66](../flight_controller/nxp_rddrone_fmuk66.md) (Discontinued) - [3DR Pixhawk 1](../flight_controller/pixhawk.md) (Pixhawk FMUv2) diff --git a/docs/en/flight_controller/autopilot_manufacturer_supported.md b/docs/en/flight_controller/autopilot_manufacturer_supported.md index db7c019aa598..27512351bef0 100644 --- a/docs/en/flight_controller/autopilot_manufacturer_supported.md +++ b/docs/en/flight_controller/autopilot_manufacturer_supported.md @@ -17,7 +17,6 @@ The boards in this category are: - [ARK Electronics ARKV6X](../flight_controller/ark_v6x.md) (and [ARK Electronics Pixhawk Autopilot Bus Carrier](../flight_controller/ark_pab.md)) - [ARK FPV Flight Controller](../flight_controller/ark_fpv.md) - [ARK Pi6X Flow Flight Controller](../flight_controller/ark_pi6x.md) -- [CUAV X7](../flight_controller/cuav_x7.md) - [CUAV Nora](../flight_controller/cuav_nora.md)(CUAV X7 variant) - [CUAV V5+](../flight_controller/cuav_v5_plus.md) (FMUv5) - [CUAV V5 nano](../flight_controller/cuav_v5_nano.md) (FMUv5) @@ -33,7 +32,6 @@ The boards in this category are: - [ModalAI Flight Core v1](../flight_controller/modalai_fc_v1.md) - [ModalAI VOXL Flight](../flight_controller/modalai_voxl_flight.md) - [ModalAI VOXL 2](../flight_controller/modalai_voxl_2.md) -- [mRobotics-X2.1](../flight_controller/mro_x2.1.md) (FMUv2) - [mRo Control Zero](../flight_controller/mro_control_zero_f7.md) - [Sky-Drones AIRLink](../flight_controller/airlink.md) - [SPRacing SPRacingH7EXTREME](../flight_controller/spracingh7extreme.md) diff --git a/docs/en/flight_controller/beaglebone_blue.md b/docs/en/flight_controller/beaglebone_blue.md index 8bd6f77fd717..f881d6b779bd 100644 --- a/docs/en/flight_controller/beaglebone_blue.md +++ b/docs/en/flight_controller/beaglebone_blue.md @@ -122,7 +122,7 @@ echo "PermitRootLogin yes" >> /etc/ssh/sshd_config && systemctl restart sshd Download and unpack [gcc-linaro-13.0.0-2022.06-x86_64_arm-linux-gnueabihf.tar.xz](https://snapshots.linaro.org/gnu-toolchain/13.0-2022.06-1/arm-linux-gnueabihf/gcc-linaro-13.0.0-2022.06-x86_64_arm-linux-gnueabihf.tar.xz) to the bbblue_toolchain folder. - Different ARM Cross Compiler versions for _BeagleBone Blue_ can be found at [Linaro Toolchain Binaries site](http://www.linaro.org/downloads/). + Different ARM Cross Compiler versions for _BeagleBone Blue_ can be found at [Linaro Toolchain Binaries site](https://www.linaro.org/downloads/). ```sh wget https://snapshots.linaro.org/gnu-toolchain/13.0-2022.06-1/arm-linux-gnueabihf/gcc-linaro-13.0.0-2022.06-x86_64_arm-linux-gnueabihf.tar.xz diff --git a/docs/en/flight_controller/cuav_nora.md b/docs/en/flight_controller/cuav_nora.md index 0974b77230f1..c482f7ad16df 100644 --- a/docs/en/flight_controller/cuav_nora.md +++ b/docs/en/flight_controller/cuav_nora.md @@ -39,7 +39,6 @@ They should be used by preference as they contain the most complete and up to da - Main FMU Processor: STM32H743 - On-board sensors: - - Accelerometer/Gyroscope: ICM-20689 - Accelerometer/Gyroscope: ICM-20649 - Accelerometer/Gyroscope: BMI088 @@ -169,5 +168,5 @@ The complete set of supported configurations can be seen in the [Airframes Refer ## Further info - [Quick start](https://doc.cuav.net/flight-controller/x7/en/quick-start/quick-start-nora.html) -- [CUAV docs](http://doc.cuav.net) +- [CUAV docs](https://doc.cuav.net/) - [nora schematic](https://github.com/cuav/hardware/tree/master/X7_Autopilot) diff --git a/docs/en/flight_controller/cuav_v5.md b/docs/en/flight_controller/cuav_v5.md index e12a5e71d747..25841b91eace 100644 --- a/docs/en/flight_controller/cuav_v5.md +++ b/docs/en/flight_controller/cuav_v5.md @@ -1,6 +1,6 @@ # CUAV v5 (Discontinued) - + :::warning This flight controller has been [discontinued](../flight_controller/autopilot_experimental.md) and is no longer commercially available. @@ -25,7 +25,6 @@ It is intended primarily for academic and commercial developers. - IO Processor: STM32F100 - 32 Bit Arm® Cortex®-M3, 24MHz, 8KB SRAM - On-board sensors: - - Accelerometer/Gyroscope: ICM-20689 - Accelerometer/Gyroscope: BMI055 - Magnetometer: IST8310 @@ -142,5 +141,4 @@ The complete set of supported configurations can be seen in the [Airframes Refer ## Further info - [FMUv5 reference design pinout](https://docs.google.com/spreadsheets/d/1-n0__BYDedQrc_2NHqBenG1DNepAgnHpSGglke-QQwY/edit#gid=912976165). -- [CUAV v5 docs](http://doc.cuav.net/flight-controller/v5-autopilot/en/v5.html) - [CUAV Github](https://github.com/cuav) diff --git a/docs/en/flight_controller/cuav_x7.md b/docs/en/flight_controller/cuav_x7.md index d902f44dda59..5f59f3904b5b 100644 --- a/docs/en/flight_controller/cuav_x7.md +++ b/docs/en/flight_controller/cuav_x7.md @@ -1,4 +1,11 @@ -# CUAV X7 Flight Controller +# CUAV X7 Flight Controller (Discontinued) + + + +:::warning +This flight controller has been [discontinued](../flight_controller/autopilot_experimental.md) and is no longer commercially available. +It has been superseded by the [CUAV X7+](https://doc.cuav.net/controller/x7/en/). +::: :::warning PX4 does not manufacture this (or any) autopilot. @@ -40,7 +47,6 @@ They should be used by preference as they contain the most complete and up to da - Main FMU Processor: STM32H743 - On-board sensors: - - Accelerometer/Gyroscope: ICM-20689 - Accelerometer/Gyroscope: ICM-20649 - Accelerometer/Gyroscope: BMI088 @@ -81,7 +87,7 @@ When it runs PX4 firmware, only 8 pwm works, the remaining 6 pwm are still being ## Connections (Wiring) -[CUAV X7 Wiring Quickstart](http://doc.cuav.net/flight-controller/x7/en/quick-start/quick-start-x7.html) +[CUAV X7 Wiring Quickstart](https://doc.cuav.net/controller/x7/en/quick-start/quick-start-x7-plus.html) ## Size and Pinouts @@ -173,5 +179,5 @@ The complete set of supported configurations can be seen in the [Airframes Refer ## Further info - [Quick start](http://doc.cuav.net/flight-controller/x7/en/quick-start/quick-start-x7.html) -- [CUAV docs](http://doc.cuav.net) +- [CUAV docs](https://doc.cuav.net/) - [x7 schematic](https://github.com/cuav/hardware/tree/master/X7_Autopilot) diff --git a/docs/en/flight_controller/cubepilot_cube_orange.md b/docs/en/flight_controller/cubepilot_cube_orange.md index aa7e4fc4e0a7..dc12957b5dcb 100644 --- a/docs/en/flight_controller/cubepilot_cube_orange.md +++ b/docs/en/flight_controller/cubepilot_cube_orange.md @@ -53,7 +53,7 @@ The manufacturer [Cube User Guide](https://docs.cubepilot.org/user-guides/autopi - 400 MHz - 1 MB RAM - 2 MB Flash \(fully accessible\) -- **Failsafe co-processor:** +- **Failsafe co-processor:** - STM32F103 (32bit _ARM Cortex-M3_) - 24 MHz - 8 KB SRAM diff --git a/docs/en/flight_controller/cubepilot_cube_orangeplus.md b/docs/en/flight_controller/cubepilot_cube_orangeplus.md index 5ee5fb31721a..440d8ae01c98 100644 --- a/docs/en/flight_controller/cubepilot_cube_orangeplus.md +++ b/docs/en/flight_controller/cubepilot_cube_orangeplus.md @@ -54,7 +54,7 @@ The manufacturer [Cube User Guide](https://docs.cubepilot.org/user-guides/autopi - 400 MHz - 1 MB RAM - 2 MB Flash \(fully accessible\) -- **Failsafe co-processor:** +- **Failsafe co-processor:** - STM32F103 (32bit _ARM Cortex-M3_) - 24 MHz - 8 KB SRAM diff --git a/docs/en/flight_controller/cubepilot_cube_yellow.md b/docs/en/flight_controller/cubepilot_cube_yellow.md index 90ca2f398266..778d647bc671 100644 --- a/docs/en/flight_controller/cubepilot_cube_yellow.md +++ b/docs/en/flight_controller/cubepilot_cube_yellow.md @@ -49,7 +49,7 @@ The manufacturer [Cube User Guide](https://docs.cubepilot.org/user-guides/autopi - 400 MHz - 512 KB MB RAM - 2 MB Flash -- **Failsafe co-processor:** +- **Failsafe co-processor:** - STM32F100 (32bit _ARM Cortex-M3_) - 24 MHz - 8 KB SRAM diff --git a/docs/en/flight_controller/holybro_pix32.md b/docs/en/flight_controller/holybro_pix32.md index 3ed152d63027..1ff578578b75 100644 --- a/docs/en/flight_controller/holybro_pix32.md +++ b/docs/en/flight_controller/holybro_pix32.md @@ -26,7 +26,7 @@ This flight controller is [manufacturer supported](../flight_controller/autopilo ## Key Features -- Main System-on-Chip: [STM32F427](http://www.st.com/web/en/catalog/mmc/FM141/SC1169/SS1577/LN1789) +- Main System-on-Chip: [STM32F427](https://www.st.com/en/microcontrollers-microprocessors/stm32f427-437.html) - CPU: 32-bit STM32F427 Cortex® M4 core with FPU - RAM: 168 MHz/256 KB - Flash: 2 MB diff --git a/docs/en/flight_controller/mro_x2.1.md b/docs/en/flight_controller/mro_x2.1.md index 5db10f075cb9..a0333c74de5e 100644 --- a/docs/en/flight_controller/mro_x2.1.md +++ b/docs/en/flight_controller/mro_x2.1.md @@ -1,4 +1,10 @@ -# mRo-X2.1 Autopilot +# mRo-X2.1 Autopilot (Discontinued) + + + +:::warning +This flight controller has been [discontinued](../flight_controller/autopilot_experimental.md) and is no longer commercially available. +::: :::warning PX4 does not manufacture this (or any) autopilot. @@ -16,7 +22,7 @@ This flight controller is [manufacturer supported](../flight_controller/autopilo ## Quick Summary -- Main System-on-Chip: [STM32F427](http://www.st.com/web/en/catalog/mmc/FM141/SC1169/SS1577/LN1789) +- Main System-on-Chip: [STM32F427](https://www.st.com/en/microcontrollers-microprocessors/stm32f427-437.html) - CPU: STM32F427VIT6 ARM® microcontroller - Revision 3 - IO: STM32F100C8T6 ARM® microcontroller - Sensors: @@ -29,8 +35,10 @@ This flight controller is [manufacturer supported](../flight_controller/autopilo - Mounting Points: 30.5mm x 30.5mm 3.2mm diameter - Weight: 10.9g -The diagram below provides a side-by-side comparison with a Pixhawk 1. The mRo features almost identical hardware and connectivity but -has a much smaller footprint. Major differences are updated sensors and Rev 3 FMU. +The diagram below provides a side-by-side comparison with a Pixhawk 1. +The mRo features almost identical hardware and connectivity but +has a much smaller footprint. +Major differences are updated sensors and Rev 3 FMU. ![Mro Pixhawk 1 vs X2.1 comparison](../../assets/flight_controller/mro/px1_x21.jpg) diff --git a/docs/en/flight_controller/omnibus_f4_sd.md b/docs/en/flight_controller/omnibus_f4_sd.md index 1851c188a08a..0a429a584d48 100644 --- a/docs/en/flight_controller/omnibus_f4_sd.md +++ b/docs/en/flight_controller/omnibus_f4_sd.md @@ -187,9 +187,9 @@ If you use CRSF Telemetry you will need to build custom PX4 firmware. By contrast, FrSky telemetry can use prebuilt firmware. ::: -For Omnibus we recommend the [TBS Crossfire Nano RX](http://team-blacksheep.com/products/prod:crossfire_nano_rx), since it is specifically designed for small Quads. +For Omnibus we recommend the [TBS Crossfire Nano RX](https://www.team-blacksheep.com/products/prod:crossfire_nano_rx), since it is specifically designed for small Quads. -On the handheld controller (e.g. Taranis) you will also need a [Transmitter Module](http://team-blacksheep.com/shop/cat:rc_transmitters#product_listing). +On the handheld controller (e.g. Taranis) you will also need a [Transmitter Module](https://www.team-blacksheep.com/shop/cat:tbs-crossfire-radio-transmitter#product_listing). This can be plugged into the back of the RC controller. ::: info @@ -213,13 +213,9 @@ Instructions for this are provided in the [TBS Crossfire Manual](https://www.tea You will need to build custom firmware to use CRSF. For more information see [CRSF Telemetry](../telemetry/crsf_telemetry.md#px4-configuration). -## Schematics + -The schematics are provided by [Airbot](https://myairbot.com/): [OmnibusF4-Pro-Sch.pdf](http://bit.ly/obf4pro). - - - -## PX4 Bootloader Update +## PX4 Bootloader Update {#bootloader} The board comes pre-installed with [Betaflight](https://github.com/betaflight/betaflight/wiki). Before PX4 firmware can be installed, the _PX4 bootloader_ must be flashed. diff --git a/docs/en/flight_controller/pixfalcon.md b/docs/en/flight_controller/pixfalcon.md index e32691650c90..cbfd1a76aa26 100644 --- a/docs/en/flight_controller/pixfalcon.md +++ b/docs/en/flight_controller/pixfalcon.md @@ -17,7 +17,7 @@ The Pixfalcon autopilot (designed by [Holybro®](https://holybro.c ## Quick Summary -- Main System-on-Chip: [STM32F427](http://www.st.com/web/en/catalog/mmc/FM141/SC1169/SS1577/LN1789) +- Main System-on-Chip: [STM32F427](https://www.st.com/en/microcontrollers-microprocessors/stm32f427-437.html) - CPU: 180 MHz ARM® Cortex® M4 with single-precision FPU - RAM: 256 KB SRAM (L1) - Failsafe System-on-Chip: STM32F100 diff --git a/docs/en/flight_controller/pixhawk-2.md b/docs/en/flight_controller/pixhawk-2.md index 581aedd442cd..4b0d4e64f4fc 100644 --- a/docs/en/flight_controller/pixhawk-2.md +++ b/docs/en/flight_controller/pixhawk-2.md @@ -51,7 +51,7 @@ This autopilot is [supported](../flight_controller/autopilot_pixhawk_standard.md ## Where to Buy -[Cube Black](http://www.proficnc.com/61-system-kits) (ProfiCNC) +[Cube Black](https://www.cubepilot.com/#/reseller/list) (Reseller list) ## Assembly diff --git a/docs/en/flight_controller/pixhawk.md b/docs/en/flight_controller/pixhawk.md index 6029d79a200e..e439318eddcf 100644 --- a/docs/en/flight_controller/pixhawk.md +++ b/docs/en/flight_controller/pixhawk.md @@ -19,7 +19,7 @@ Assembly/setup instructions for use with PX4 are provided here: [Pixhawk Wiring ## Key Features -- Main System-on-Chip: [STM32F427](http://www.st.com/web/en/catalog/mmc/FM141/SC1169/SS1577/LN1789) +- Main System-on-Chip: [STM32F427](https://www.st.com/en/microcontrollers-microprocessors/stm32f427-437.html) - CPU: 180 MHz ARM® Cortex® M4 with single-precision FPU - RAM: 256 KB SRAM (L1) - Failsafe System-on-Chip: STM32F100 @@ -323,10 +323,10 @@ make px4_fmu-v2_default ## Parts / Housings -- **ARM MINI JTAG (J6)**: 1.27 mm 10pos header (SHROUDED), for Black Magic Probe: FCI 20021521-00010D4LF ([Distrelec](https://www.distrelec.ch/en/minitek-127-straight-male-pcb-header-surface-mount-rows-10-contacts-27mm-pitch-amphenol-fci-20021521-00010d4lf/p/14352308), [Digi-Key](https://www.digikey.com/en/products/detail/20021521-00010T1LF/609-4054-ND/2414951),) or Samtec FTSH-105-01-F-DV-K (untested) or Harwin M50-3600542 ([Digikey](https://www.digikey.com/en/products/detail/harwin-inc/M50-3600542/2264370) or [Mouser](http://ch.mouser.com/ProductDetail/Harwin/M50-3600542/?qs=%2fha2pyFadujTt%2fIEz8xdzrYzHAVUnbxh8Ki%252bwWYPNeEa09PYvTkIOQ%3d%3d)) +- **ARM MINI JTAG (J6)**: 1.27 mm 10pos header (SHROUDED), for Black Magic Probe: FCI 20021521-00010D4LF ([Distrelec](https://www.distrelec.ch/en/minitek-127-straight-male-pcb-header-surface-mount-rows-10-contacts-27mm-pitch-amphenol-fci-20021521-00010d4lf/p/14352308), [Digi-Key](https://www.digikey.com/en/products/detail/20021521-00010T1LF/609-4054-ND/2414951),) or Samtec FTSH-105-01-F-DV-K (untested) or Harwin M50-3600542 ([Digikey](https://www.digikey.com/en/products/detail/harwin-inc/M50-3600542/2264370)) - JTAG Adapter Option #1: [BlackMagic Probe](https://1bitsquared.com/products/black-magic-probe). Note, may come without cables (check with manufacturer). - If so, you will need the **Samtec FFSD-05-D-06.00-01-N** cable ([Samtec sample service](https://www.samtec.com/products/ffsd-05-d-06.00-01-n) or [Digi-Key Link: SAM8218-ND](http://www.digikey.com/product-search/en?x=0&y=0&lang=en&site=us&KeyWords=FFSD-05-D-06.00-01-N)) or [Tag Connect Ribbon](http://www.tag-connect.com/CORTEXRIBBON10) and a Mini-USB cable. - - JTAG Adapter Option #2: [Digi-Key Link: ST-LINK/V2](https://www.digikey.com/product-detail/en/stmicroelectronics/ST-LINK-V2/497-10484-ND) / [ST USER MANUAL](http://www.st.com/internet/com/TECHNICAL_RESOURCES/TECHNICAL_LITERATURE/USER_MANUAL/DM00026748.pdf), needs an ARM Mini JTAG to 20pos adapter: [Digi-Key Link: 726-1193-ND](https://www.digikey.com/en/products/detail/texas-instruments/MDL-ADA2/1986451) + If so, you will need the **Samtec FFSD-05-D-06.00-01-N** cable ([Samtec sample service](https://www.samtec.com/products/ffsd-05-d-06.00-01-n) or [Digi-Key Link: SAM8218-ND](https://www.digikey.com/en/products/detail/samtec-inc/ffsd-05-d-06-00-01-n/1106577)) or [Tag Connect Ribbon](https://www.tag-connect.com/product/10-pin-cortex-ribbon-cable-4-length-with-50-mil-connectors) and a Mini-USB cable. + - JTAG Adapter Option #2: [Digi-Key Link: ST-LINK/V2](https://www.digikey.com/product-detail/en/stmicroelectronics/ST-LINK-V2/497-10484-ND) / [ST USER MANUAL](https://www.st.com/resource/en/user_manual/dm00026748.pdf), needs an ARM Mini JTAG to 20pos adapter: [Digi-Key Link: 726-1193-ND](https://www.digikey.com/en/products/detail/texas-instruments/MDL-ADA2/1986451) - JTAG Adapter Option #3: [Olimex ARM-TINY](https://www.olimex.com/wiki/ARM-USB-TINY) or any other OpenOCD-compatible ARM Cortex JTAG adapter, needs an ARM Mini JTAG to 20pos adapter: [Digi-Key Link: 726-1193-ND](https://www.digikey.com/en/products/detail/texas-instruments/MDL-ADA2/1986451) - **USARTs**: Hirose DF13 6 pos ([Digi-Key Link: DF13A-6P-1.25H(20)](https://www.digikey.com/products/en?keywords=H3371-ND)) - Mates: Hirose DF13 6 pos housing ([Digi-Key Link: Hirose DF13-6S-1.25C](https://www.digikey.com/products/en?keywords=H2182-ND)) diff --git a/docs/en/flight_controller/pixhawk6c_mini.md b/docs/en/flight_controller/pixhawk6c_mini.md index 12d172465c0a..bdd7ebeab777 100644 --- a/docs/en/flight_controller/pixhawk6c_mini.md +++ b/docs/en/flight_controller/pixhawk6c_mini.md @@ -112,7 +112,7 @@ Please refer to the [Pixhawk 4 Mini Wiring Quick Start](../assembly/quick_start_ | UART7 | /dev/ttyS5 | TELEM1 | TELEM1 | | UART8 | /dev/ttyS6 | GPS2 | GPS2 | - + ## Dimensions diff --git a/docs/en/flight_controller/pixracer.md b/docs/en/flight_controller/pixracer.md index ee37397a80af..32f0cc9b9d6c 100644 --- a/docs/en/flight_controller/pixracer.md +++ b/docs/en/flight_controller/pixracer.md @@ -16,7 +16,7 @@ This autopilot is [supported](../flight_controller/autopilot_pixhawk_standard.md ## Key Features -- Main System-on-Chip: [STM32F427VIT6 rev.3](http://www.st.com/web/en/catalog/mmc/FM141/SC1169/SS1577/LN1789) +- Main System-on-Chip: [STM32F427VIT6 rev.3](https://www.st.com/en/microcontrollers-microprocessors/stm32f427-437.html) - CPU: 180 MHz ARM Cortex® M4 with single-precision FPU - RAM: 256 KB SRAM (L1) - Standard FPV form factor: 36x36 mm with standard 30.5 mm hole pattern @@ -41,7 +41,8 @@ Accessories include: ## Kit -The Pixracer is designed to use a separate avionics power supply. This is necessary to avoid current surges from motors or ESCs to flow back to the flight controller and disturb its delicate sensors. +The Pixracer is designed to use a separate avionics power supply. +This is necessary to avoid current surges from motors or ESCs to flow back to the flight controller and disturb its delicate sensors. - Power module (with voltage and current sensing) - I2C splitter (supporting AUAV, Hobbyking and 3DR® peripherals) @@ -53,7 +54,7 @@ One of the main features of the board is its ability to use Wifi for flashing ne This frees it of the need of any desktop system. - [ESP8266 Wifi](../telemetry/esp8266_wifi_module.md) -- [Custom ESP8266 MAVLink firmware](https://github.com/dogmaphobic/mavesp8266) +- [Custom ESP8266 MAVLink firmware](https://github.com/BeyondRobotix/mavesp8266) ::: info Firmware upgrade is not yet enabled over WiFi (it is supported by the default bootloader but not yet enabled). diff --git a/docs/en/flight_controller/raccoonlab_fmu6x.md b/docs/en/flight_controller/raccoonlab_fmu6x.md index 728a87de242b..b84e140a36df 100644 --- a/docs/en/flight_controller/raccoonlab_fmu6x.md +++ b/docs/en/flight_controller/raccoonlab_fmu6x.md @@ -159,4 +159,4 @@ The complete set of supported configurations can be seen in the [Airframes Refer - [Pixhawk Autopilot FMUv6X Standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-012%20Pixhawk%20Autopilot%20v6X%20Standard.pdf) - [Pixhawk Autopilot Bus Standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-010%20Pixhawk%20Autopilot%20Bus%20Standard.pdf) - [Pixhawk Connector Standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-009%20Pixhawk%20Connector%20Standard.pdf) -- [RaccoonLab docs](http://docs.raccoonlab.co) +- [RaccoonLab docs](https://docs.raccoonlab.co/) diff --git a/docs/en/flight_controller/thepeach_k1.md b/docs/en/flight_controller/thepeach_k1.md index 739a9e7be500..59eab31f545c 100644 --- a/docs/en/flight_controller/thepeach_k1.md +++ b/docs/en/flight_controller/thepeach_k1.md @@ -14,21 +14,17 @@ It is based on the **Pixhawk-project FMUv3** open hardware design and runs **PX4 ## Specifications - Main Processor: STM32F427VIT6 - - 32bit ARM Cortex-M4, 168 MHz 256 KB RAM 2 MB Flash memory - IO Processor: STM32F100C8T6 - - ARM Cortex-M3, 32bit ARM Cortex-M3, 24 MHz, 8KB SRAM - On-board sensors - - Accel/Gyro: ICM-20602 - Accel/Gyro/Mag: MPU-9250 - Barometer: MS5611 - Interfaces - - 8+5 PWM output (8 from IO, 5 from FMU) - Spektrum DSM / DSM2 / DSM-X Satellite compatible input - Futaba S.BUS compatible input and output @@ -98,4 +94,4 @@ make thepeach_k1_default ## Where to buy -Order from [ThePeach](http://thepeach.shop/) +Order from [ThePeach](https://thepeach.shop/) diff --git a/docs/en/flight_controller/thepeach_r1.md b/docs/en/flight_controller/thepeach_r1.md index 0af61445b9d8..8881d2dc3a84 100644 --- a/docs/en/flight_controller/thepeach_r1.md +++ b/docs/en/flight_controller/thepeach_r1.md @@ -14,21 +14,17 @@ It is based on the **Pixhawk-project FMUv3** open hardware design and runs **PX4 ## Specifications - Main Processor: STM32F427VIT6 - - 32bit ARM Cortex-M4, 168 MHz 256 KB RAM 2 MB Flash memory - IO Processor: STM32F100C8T6 - - ARM Cortex-M3, 32bit ARM Cortex-M3, 24 MHz, 8KB SRAM - On-board sensors - - Accel/Gyro: ICM-20602 - Accel/Gyro/Mag: MPU-9250 - Barometer: MS5611 - Interfaces - - 8+6 PWM output (8 from IO, 6 from FMU) - Spektrum DSM / DSM2 / DSM-X Satellite compatible input - Futaba S.BUS compatible input and output @@ -42,7 +38,6 @@ It is based on the **Pixhawk-project FMUv3** open hardware design and runs **PX4 - Analog inputs for voltage / Current of 1 battery - Interfaces For Raspberry Pi CM3+ - - VBUS - DDR2 Connector: Raspberry Pi CM3+ - 1x UART @@ -103,4 +98,4 @@ make thepeach_r1_default ## Where to buy -Order from [ThePeach](http://thepeach.shop/) +Order from [ThePeach](https://thepeach.shop/) diff --git a/docs/en/flight_modes/offboard.md b/docs/en/flight_modes/offboard.md index c1d0cbd43f49..0a21e7e451f0 100644 --- a/docs/en/flight_modes/offboard.md +++ b/docs/en/flight_modes/offboard.md @@ -85,9 +85,7 @@ Before using offboard mode with ROS 2, please spend a few minutes understanding ### Copter - [px4_msgs::msg::TrajectorySetpoint](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TrajectorySetpoint.msg) - - The following input combinations are supported: - - Position setpoint (`position` different from `NaN`). Non-`NaN` values of velocity and acceleration are used as feedforward terms for the inner loop controllers. - Velocity setpoint (`velocity` different from `NaN` and `position` set to `NaN`). Non-`NaN` values acceleration are used as feedforward terms for the inner loop controllers. - Acceleration setpoint (`acceleration` different from `NaN` and `position` and `velocity` set to `NaN`) @@ -95,18 +93,14 @@ Before using offboard mode with ROS 2, please spend a few minutes understanding - All values are interpreted in NED (Nord, East, Down) coordinate system and the units are \[m\], \[m/s\] and \[m/s^2\] for position, velocity and acceleration, respectively. - [px4_msgs::msg::VehicleAttitudeSetpoint](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleAttitudeSetpoint.msg) - - The following input combination is supported: - - quaternion `q_d` + thrust setpoint `thrust_body`. Non-`NaN` values of `yaw_sp_move_rate` are used as feedforward terms expressed in Earth frame and in \[rad/s\]. - The quaternion represents the rotation between the drone body FRD (front, right, down) frame and the NED frame. The thrust is in the drone body FRD frame and expressed in normalized \[-1, 1\] values. - [px4_msgs::msg::VehicleRatesSetpoint](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleRatesSetpoint.msg) - - The following input combination is supported: - - `roll`, `pitch`, `yaw` and `thrust_body`. - All the values are in the drone body FRD frame. The rates are in \[rad/s\] while thrust_body is normalized in \[-1, 1\]. @@ -116,7 +110,6 @@ Before using offboard mode with ROS 2, please spend a few minutes understanding The following offboard control modes bypass all internal PX4 control loops and should be used with great care. - [px4_msgs::msg::VehicleThrustSetpoint](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg) + [px4_msgs::msg::VehicleTorqueSetpoint](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg) - - The following input combination is supported: - `xyz` for thrust and `xyz` for torque. - All the values are in the drone body FRD frame and normalized in \[-1, 1\]. @@ -134,9 +127,7 @@ The following MAVLink messages and their particular fields and field values are ### Copter/VTOL - [SET_POSITION_TARGET_LOCAL_NED](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_LOCAL_NED) - - The following input combinations are supported: - - Position setpoint (only `x`, `y`, `z`) - Velocity setpoint (only `vx`, `vy`, `vz`) - Acceleration setpoint (only `afx`, `afy`, `afz`) @@ -146,9 +137,7 @@ The following MAVLink messages and their particular fields and field values are - PX4 supports the following `coordinate_frame` values (only): [MAV_FRAME_LOCAL_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_NED) and [MAV_FRAME_BODY_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_BODY_NED). - [SET_POSITION_TARGET_GLOBAL_INT](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_GLOBAL_INT) - - The following input combinations are supported: - - Position setpoint (only `lat_int`, `lon_int`, `alt`) - Velocity setpoint (only `vx`, `vy`, `vz`) - _Thrust_ setpoint (only `afx`, `afy`, `afz`) @@ -169,18 +158,14 @@ The following MAVLink messages and their particular fields and field values are ### Fixed-wing - [SET_POSITION_TARGET_LOCAL_NED](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_LOCAL_NED) - - The following input combinations are supported (via `type_mask`): - - Position setpoint (`x`, `y`, `z` only; velocity and acceleration setpoints are ignored). - - Specify the _type_ of the setpoint in `type_mask` (if these bits are not set the vehicle will fly in a flower-like pattern): ::: info Some of the _setpoint type_ values below are not part of the MAVLink standard for the `type_mask` field. ::: The values are: - - 292: Gliding setpoint. This configures TECS to prioritize airspeed over altitude in order to make the vehicle glide when there is no thrust (i.e. pitch is controlled to regulate airspeed). It is equivalent to setting `type_mask` as `POSITION_TARGET_TYPEMASK_Z_IGNORE`, `POSITION_TARGET_TYPEMASK_VZ_IGNORE`, `POSITION_TARGET_TYPEMASK_AZ_IGNORE`. @@ -192,11 +177,8 @@ The following MAVLink messages and their particular fields and field values are - PX4 supports the coordinate frames (`coordinate_frame` field): [MAV_FRAME_LOCAL_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_NED) and [MAV_FRAME_BODY_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_BODY_NED). - [SET_POSITION_TARGET_GLOBAL_INT](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_GLOBAL_INT) - - The following input combinations are supported (via `type_mask`): - - Position setpoint (only `lat_int`, `lon_int`, `alt`) - - Specify the _type_ of the setpoint in `type_mask` (if these bits are not set the vehicle will fly in a flower-like pattern): ::: info @@ -204,7 +186,6 @@ The following MAVLink messages and their particular fields and field values are ::: The values are: - - 4096: Takeoff setpoint. - 8192: Land setpoint. - 12288: Loiter setpoint (fly a circle centred on setpoint). @@ -220,11 +201,8 @@ The following MAVLink messages and their particular fields and field values are ### Rover - [SET_POSITION_TARGET_LOCAL_NED](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_LOCAL_NED) - - The following input combinations are supported (in `type_mask`): - - Position setpoint (only `x`, `y`, `z`) - - Specify the _type_ of the setpoint in `type_mask`: ::: info @@ -232,7 +210,6 @@ The following MAVLink messages and their particular fields and field values are :: The values are: - - 12288: Loiter setpoint (vehicle stops when close enough to setpoint). - Velocity setpoint (only `vx`, `vy`, `vz`) @@ -240,12 +217,10 @@ The following MAVLink messages and their particular fields and field values are - PX4 supports the coordinate frames (`coordinate_frame` field): [MAV_FRAME_LOCAL_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_NED) and [MAV_FRAME_BODY_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_BODY_NED). - [SET_POSITION_TARGET_GLOBAL_INT](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_GLOBAL_INT) - - The following input combinations are supported (in `type_mask`): - Position setpoint (only `lat_int`, `lon_int`, `alt`) - Specify the _type_ of the setpoint in `type_mask` (not part of the MAVLink standard). The values are: - - Following bits not set then normal behaviour. - 12288: Loiter setpoint (vehicle stops when close enough to setpoint). @@ -272,7 +247,7 @@ _Offboard mode_ is affected by the following parameters: ## Developer Resources -Typically developers do not directly work at the MAVLink layer, but instead use a robotics API like [MAVSDK](https://mavsdk.mavlink.io/) or [ROS](http://www.ros.org/) (these provide a developer friendly API, and take care of managing and maintaining connections, sending messages and monitoring responses - the minutiae of working with _Offboard mode_ and MAVLink). +Typically developers do not directly work at the MAVLink layer, but instead use a robotics API like [MAVSDK](https://mavsdk.mavlink.io/) or [ROS](https://www.ros.org/) (these provide a developer friendly API, and take care of managing and maintaining connections, sending messages and monitoring responses - the minutiae of working with _Offboard mode_ and MAVLink). The following resources may be useful for a developer audience: diff --git a/docs/en/frames_plane/reptile_dragon_2.md b/docs/en/frames_plane/reptile_dragon_2.md index e0e20d08893b..7349ecccfc63 100644 --- a/docs/en/frames_plane/reptile_dragon_2.md +++ b/docs/en/frames_plane/reptile_dragon_2.md @@ -52,7 +52,7 @@ Key build features - [Caddx Vista FPV air unit](https://caddxfpv.com/products/caddx-vista-kit) - [Emax ES08MA ii](https://emaxmodel.com/products/emax-es08ma-ii-12g-mini-metal-gear-analog-servo-for-rc-model-robot-pwm-servo) - [DJI FPV Goggles](https://www.dji.com/fpv) -- [ExpressLRS Matek Diversity RX](http://www.mateksys.com/?portfolio=elrs-r24) +- [ExpressLRS Matek Diversity RX](https://www.mateksys.com/?portfolio=elrs-r24) - [5V BEC](https://www.readymaderc.com/products/details/rmrc-3a-power-regulator-5-to-6-volt-ubec) - [6s2p 18650 LiIon flight battery](https://www.upgradeenergytech.com/product-page/6s-22-2v-5600mah-30c-dark-lithium-liion-drone-battery) (select XT60 connector) - [Custom designed 3D printed parts](https://github.com/PX4/PX4-Autopilot/raw/main/docs/assets/airframes/fw/reptile_dragon_2/rd2_3d_printed_parts.zip) diff --git a/docs/en/frames_plane/turbo_timber_evolution.md b/docs/en/frames_plane/turbo_timber_evolution.md index 8e9877fc6876..778e857b72a7 100644 --- a/docs/en/frames_plane/turbo_timber_evolution.md +++ b/docs/en/frames_plane/turbo_timber_evolution.md @@ -46,7 +46,7 @@ Key Build Features: - MS4525DO differential pressure module and pitot tube - [Caddx Vista FPV air unit](https://caddxfpv.com/products/caddx-vista-kit) - [DJI FPV Goggles](https://www.dji.com/fpv) -- [ExpressLRS Matek Diversity RX](http://www.mateksys.com/?portfolio=elrs-r24) +- [ExpressLRS Matek Diversity RX](https://www.mateksys.com/?portfolio=elrs-r24) - [Custom designed 3D printed parts](https://github.com/PX4/PX4-Autopilot/raw/main/docs/assets/airframes/fw/turbo_timber_evolution/3d_printed_parts.zip) - Pixhawk 4 Mini mount and top GPS mount - FPV pod and camera mount diff --git a/docs/en/frames_rover/rover_position_control.md b/docs/en/frames_rover/rover_position_control.md index 89c320c1e65f..b3679cbe327c 100644 --- a/docs/en/frames_rover/rover_position_control.md +++ b/docs/en/frames_rover/rover_position_control.md @@ -110,8 +110,8 @@ The idea was to develop a platform that allows for easy control of wheeled UGVs - [Pixhawk Mini (Discontinued)](../flight_controller/pixhawk_mini.md) - 3DR 10S Power Module - 3DR 433MHz Telemetry Module (EU) -- [Spektrum Dxe Controller](http://www.spektrumrc.com/Products/Default.aspx?ProdId=SPM1000) or other PX4-compatible remotes -- [Spektrum Quad Race Serial Receiver w/Diversity](http://www.spektrumrc.com/Products/Default.aspx?ProdID=SPM4648) +- [Spektrum Dxe Controller](https://www.spektrumrc.com/product/dxe-dsmx-transmitter-with-ar610/SPM1000.html) or other PX4-compatible remotes +- [Spektrum Quad Race Serial Receiver w/Diversity](https://www.spektrumrc.com/product/dsmx-quad-race-serial-receiver-with-diversity/SPM4648.html) - [PX4Flow](../sensor/px4flow.md) (Deprecated) ### Assembly diff --git a/docs/en/frames_vtol/vtol_tiltrotor_omp_hobby_zmo_fpv.md b/docs/en/frames_vtol/vtol_tiltrotor_omp_hobby_zmo_fpv.md index 2182a3190af7..d8a783e98185 100644 --- a/docs/en/frames_vtol/vtol_tiltrotor_omp_hobby_zmo_fpv.md +++ b/docs/en/frames_vtol/vtol_tiltrotor_omp_hobby_zmo_fpv.md @@ -47,7 +47,7 @@ The approximate maximum size of the FC is: 50x110x22mm - [Airspeed sensor (cheaper alternative)](https://holybro.com/products/digital-air-speed-sensor?pr_prod_strat=use_description&pr_rec_id=236dfda00&pr_rec_pid=7150470561981&pr_ref_pid=7150472462525&pr_seq=uniform) - [Lidar Lightware lw20-c (included in Skynode eval. kit)](../sensor/sfxx_lidar.md) (Optional) - [Lidar Seeed Studio PSK-CM8JL65-CC5 (cheaper alternative)](https://www.seeedstudio.com/PSK-CM8JL65-CC5-Infrared-Distance-Measuring-Sensor-p-4028.html) (Optional) -- [5V BEC](http://www.mateksys.com/?portfolio=bec12s-pro) +- [5V BEC](https://www.mateksys.com/?portfolio=bec12s-pro) - [Radio (RC) System](../getting_started/rc_transmitter_receiver.md) of your preference - [Servo cable extension cable male 30cm 10 pcs](https://www.getfpv.com/male-to-male-servo-extension-cable-twisted-22awg-jr-style-5-pcs.html) - [USB-C extension cable](https://www.digitec.ch/en/s1/product/powerguard-usb-c-usb-c-025-m-usb-cables-22529949?dbq=1&gclid=Cj0KCQjw2cWgBhDYARIsALggUhrh-z-7DSU0wKfLBVa8filkXLQaxUpi7pC0ffQyRzLng8Ph01h2R1gaAp0mEALw_wcB&gclsrc=aw.ds) diff --git a/docs/en/getting_started/flight_reporting.md b/docs/en/getting_started/flight_reporting.md index cc2a22a990a7..1485d71592a1 100644 --- a/docs/en/getting_started/flight_reporting.md +++ b/docs/en/getting_started/flight_reporting.md @@ -21,7 +21,7 @@ You can also host a [private Flight Review server](../dev_log/log_encryption.md# ## Analyzing the Logs -Upload the log file to the online [Flight Review](http://logs.px4.io) tool. +Upload the log file to the online [Flight Review](https://logs.px4.io/) tool. After upload you'll be emailed a link to the analysis page for the log. [Log Analysis using Flight Review](../log/flight_review.md) explains how to interpret the plots, and can help you to verify/reject the causes of common problems: excessive vibration, poor PID tuning, saturated controllers, imbalanced vehicles, GPS noise, etc. @@ -38,17 +38,17 @@ For more information see [Settings > MAVLink Settings > MAVLink 2 Logging (PX4 o ## Sharing the Log Files for Review by PX4 Developers -The [Flight Review](http://logs.px4.io) log file link can be shared for discussion in the [support forums](../contribute/support.md#forums-and-chat) or a [Github issue](../index.md#reporting-bugs-issues). +The [Flight Review](https://logs.px4.io/) log file link can be shared for discussion in the [support forums](../contribute/support.md#forums-and-chat) or a [Github issue](../index.md#reporting-bugs-issues). ## Log Configuration -The logging system is configured by default to collect sensible logs for use with [Flight Review](http://logs.px4.io). +The logging system is configured by default to collect sensible logs for use with [Flight Review](https://logs.px4.io/). Logging may further be configured using the [SD Logging](../advanced_config/parameter_reference.md#sd-logging) parameters or with a file on the SD card. Details on configuration can be found in the [logging configuration documentation](../dev_log/logging.md#configuration). ## Key Links -- [Flight Review](http://logs.px4.io) +- [Flight Review](https://logs.px4.io/) - [Log Analysis using Flight Review](../log/flight_review.md) - [Flight Log Analysis](../dev_log/flight_log_analysis.md) diff --git a/docs/en/getting_started/px4_basic_concepts.md b/docs/en/getting_started/px4_basic_concepts.md index a2eb70e4a7a8..b18d788dd8d1 100644 --- a/docs/en/getting_started/px4_basic_concepts.md +++ b/docs/en/getting_started/px4_basic_concepts.md @@ -62,9 +62,9 @@ Some of PX4's key features are: - Supports many different vehicle frames/types, including: [multicopters](../frames_multicopter/index.md), [fixed-wing aircraft](../frames_plane/index.md) (planes), [VTOLs](../frames_vtol/index.md) (hybrid multicopter/fixed-wing), [ground vehicles](../frames_rover/index.md), and [underwater vehicles](../frames_sub/index.md). - Great choice of drone components for [flight controller](#flight-controller), [sensors](#sensors), [payloads](#payloads), and other peripherals. - Flexible and powerful [flight modes](#flight-modes) and [safety features](#safety-settings-failsafe). -- Robust and deep integration with [companion computers](#offboard-companion-computer) and [robotics APIs](../robotics/index.md) such as [ROS 2](../ros2/user_guide.md) and [MAVSDK](http://mavsdk.mavlink.io). +- Robust and deep integration with [companion computers](#offboard-companion-computer) and [robotics APIs](../robotics/index.md) such as [ROS 2](../ros2/user_guide.md) and [MAVSDK](https://mavsdk.mavlink.io/main/en/index.html). -PX4 is a core part of a broader drone platform that includes the [QGroundControl](#qgc) ground station, [Pixhawk hardware](https://pixhawk.org/), and [MAVSDK](http://mavsdk.mavlink.io) for integration with companion computers, cameras and other hardware using the MAVLink protocol. +PX4 is a core part of a broader drone platform that includes the [QGroundControl](#qgc) ground station, [Pixhawk hardware](https://pixhawk.org/), and [MAVSDK](https://mavsdk.mavlink.io/main/en/index.html) for integration with companion computers, cameras and other hardware using the MAVLink protocol. PX4 is supported by the [Dronecode Project](https://www.dronecode.org/). ## Ground Control Stations diff --git a/docs/en/gps_compass/gps_hex_here2.md b/docs/en/gps_compass/gps_hex_here2.md index e772abcd9fc1..6bea19739d9b 100644 --- a/docs/en/gps_compass/gps_hex_here2.md +++ b/docs/en/gps_compass/gps_hex_here2.md @@ -4,7 +4,7 @@ This has been superseded by the [Cube Here 3](https://www.cubepilot.com/#/here/here3) ::: -The [Here2 GPS receiver](http://www.proficnc.com/all-products/152-gps-module.html) is an update to the Here GPS module from HEX. +The _Here2 GPS receiver_ is an update to the Here GPS module from HEX. Main features include: @@ -18,8 +18,7 @@ Main features include: ## Where to Buy -- [ProfiCNC](http://www.proficnc.com/all-products/152-gps-module.html) (Australia) -- [Other resellers](http://www.proficnc.com/stores) +- [Resellers](https://www.cubepilot.com/#/reseller/list) ## Configuration @@ -33,7 +32,7 @@ Setup and use on PX4 is largely plug and play. ## Wiring and Connections -The Here2 GPS comes with an 8 pin connector that can be inserted directly into the [Pixhawk 2](http://www.hex.aero/wp-content/uploads/2016/07/DRS_Pixhawk-2-17th-march-2016.pdf) GPS UART port. +The Here2 GPS comes with an 8 pin connector that can be inserted directly into the Pixhawk 2 `GPS` UART port. The Pixhawk 3 Pro and Pixracer have a 6 pin GPS port connector. For these controllers you can modify the GPS cable (as shown below) to remove pin 6 and 7. diff --git a/docs/en/gps_compass/rtk_gps_trimble_mb_two.md b/docs/en/gps_compass/rtk_gps_trimble_mb_two.md index cb9e7321ce3d..efdf5cb43830 100644 --- a/docs/en/gps_compass/rtk_gps_trimble_mb_two.md +++ b/docs/en/gps_compass/rtk_gps_trimble_mb_two.md @@ -18,7 +18,7 @@ The following firmware options need to be selected when buying the device: ## Antennas and Cable The Trimble MB-Two requires two dual-frequency (L1/L2) antennas. -A good example is the [Maxtenna M1227HCT-A2-SMA](http://www.maxtena.com/products/helicore/m1227hct-a2-sma/) +A good example is the [Maxtenna M1227HCT-A2-SMA](https://www.maxtena.com/products/helicore/m1227hct-a2-sma/) (which can be bought, for instance, from [Farnell](https://uk.farnell.com/maxtena/m1227hct-a2-sma/antenna-1-217-1-25-1-565-1-61ghz/dp/2484959)). The antenna connector type on the device is MMCX. diff --git a/docs/en/hardware/board_support_guide.md b/docs/en/hardware/board_support_guide.md index 105dbc3b5854..dd9722e805e1 100644 --- a/docs/en/hardware/board_support_guide.md +++ b/docs/en/hardware/board_support_guide.md @@ -20,7 +20,6 @@ The general requirements for all supported boards are: Board needs to pass acceptance criteria to ensure quality of parts and assembly. 1. A clear and easy way to contact customer support for customers. One or more of the following is accepted: - - PX4 Discord server presence - Support email - Phone number @@ -29,7 +28,6 @@ The general requirements for all supported boards are: 1. The board needs to use the [PX4 bootloader protocol](https://github.com/PX4/PX4-Autopilot/tree/main/platforms/nuttx/src/bootloader). For more information on bootloaders see: [PX4 Nuttx Porting Guide > Bootloader](../hardware/porting_guide_nuttx.md#bootloader). 1. Adequate documentation, which includes, but is not limited to: - - A complete pinout made available publicly that maps PX4 pin definitions to: 1. Microcontroller pins 2. Physical external connectors @@ -48,13 +46,11 @@ Manufacturer supported boards may be as well/better supported than Pixhawk board ## Pixhawk Standard -A Pixhawk board is one that conforms to the Pixhawk standards. These standards are laid out on [http://pixhawk.org](http://pixhawk.org/), but at high-level require that the board passes electrical tests mandated by the standard and the manufacturer has signed the Pixhawk adopter and trademark agreement. +A Pixhawk board is one that conforms to the Pixhawk standards. These standards are laid out on [pixhawk.org](https://pixhawk.org/), but at high-level require that the board passes electrical tests mandated by the standard and the manufacturer has signed the Pixhawk adopter and trademark agreement. PX4 generally only supports boards that are commercially available, which typically means that board standards released within the last five years are supported. - - -### VER and REV ID (Hardware Revision and Version Sensing) +### VER and REV ID (Hardware Revision and Version Sensing) {#ver_rev_id} FMUv5 and onwards have an electrical sensing mechanism. This sensing coupled with optional configuration data will be used to define hardware’s configuration with respect to a mandatory device and power supply configuration. Manufacturers must obtain the VER and REV ID from PX4 board maintainers by issuing a PR to ammend the [DS-018 Pixhawk standard](https://github.com/pixhawk/Pixhawk-Standards) for board versions and revisions. diff --git a/docs/en/index.md b/docs/en/index.md index a2b1579943c1..ed3fd5571ff0 100644 --- a/docs/en/index.md +++ b/docs/en/index.md @@ -127,7 +127,7 @@ The following icons used in this library are licensed separately (as shown below _placeholder_ icon made by Smashicons from www.flaticon.com is licensed by CC 3.0 BY. - _camera-automatic-mode_ icon made by Freepik from www.flaticon.com is licensed by CC 3.0 BY. + _camera-automatic-mode_ icon made by Freepik from www.flaticon.com is licensed by CC 3.0 BY. ## Governance diff --git a/docs/en/log/flight_log_analysis.md b/docs/en/log/flight_log_analysis.md index f2b21aa4e214..2abf0f4564df 100644 --- a/docs/en/log/flight_log_analysis.md +++ b/docs/en/log/flight_log_analysis.md @@ -20,7 +20,7 @@ Before analyzing a flight log it is important to establish its context: If a log file ends mid-air, two main causes are possible: a power failure _or_ a hard fault of the operating system. -On autopilots based on the [STM32 series](http://www.st.com/en/microcontrollers/stm32-32-bit-arm-cortex-mcus.html), hard faults are logged to the SD card. +On autopilots based on the [STM32 series](https://www.st.com/en/microcontrollers-microprocessors/stm32-32-bit-arm-cortex-mcus.html), hard faults are logged to the SD card. These are located on the top level of the SD card and named _fault_date.log_, e.g. **fault_2017_04_03_00_26_05.log**. You should check for the presence of this file if a flight log ends abruptly. @@ -28,7 +28,7 @@ You should check for the presence of this file if a flight log ends abruptly. ### Flight Review (Online Tool) -[Flight Review](http://logs.px4.io) is the successor of _Log Muncher_. +[Flight Review](https://logs.px4.io/) is the successor of _Log Muncher_. It is used in combination with the new [ULog](../dev_log/ulog_file_format.md) logging format. Key features: diff --git a/docs/en/log/flight_review.md b/docs/en/log/flight_review.md index 6729f88ed2ce..a9e8ccd31838 100644 --- a/docs/en/log/flight_review.md +++ b/docs/en/log/flight_review.md @@ -1,6 +1,6 @@ # Log Analysis using Flight Review -The [Flight Review](http://logs.px4.io) plots for a flight can be used to analyze general vehicle condition. +The [Flight Review](https://logs.px4.io/) plots for a flight can be used to analyze general vehicle condition. The plots are meant to be self-explanatory, but it takes some experience to know what ranges are acceptable and what a plot should look like. This page explains how to interpret the plots and identify common problems. diff --git a/docs/en/modules/hello_sky.md b/docs/en/modules/hello_sky.md index f1b8f68328cc..ad1d9e5bc9ef 100644 --- a/docs/en/modules/hello_sky.md +++ b/docs/en/modules/hello_sky.md @@ -27,7 +27,6 @@ This consists of a single _C_ file and a _cmake_ definition (which tells the too 1. Create a new directory **PX4-Autopilot/src/examples/px4_simple_app**. 1. Create a new C file in that directory named **px4_simple_app.c**: - - Copy in the default header to the top of the page. This should be present in all contributed files! @@ -145,7 +144,6 @@ This consists of a single _C_ file and a _cmake_ definition (which tells the too ``` The `px4_add_module()` method builds a static library from a module description. - - The `MODULE` block is the Firmware-unique name of the module (by convention the module name is prefixed by parent directories back to `src`). - The `MAIN` block lists the entry point of the module, which registers the command with NuttX so that it can be called from the PX4 shell or SITL console. @@ -303,7 +301,7 @@ int sensor_sub_fd = orb_subscribe(ORB_ID(sensor_combined)); The `sensor_sub_fd` is a topic handle and can be used to very efficiently perform a blocking wait for new data. The current thread goes to sleep and is woken up automatically by the scheduler once new data is available, not consuming any CPU cycles while waiting. -To do this, we use the [poll()](http://pubs.opengroup.org/onlinepubs/007908799/xsh/poll.html) POSIX system call. +To do this, we use the [poll()](https://pubs.opengroup.org/onlinepubs/007908799/xsh/poll.html) POSIX system call. Adding `poll()` to the subscription looks like (_pseudocode, look for the full implementation below_): diff --git a/docs/en/peripherals/frsky_telemetry.md b/docs/en/peripherals/frsky_telemetry.md index 85c0091acf07..74326ca07a71 100644 --- a/docs/en/peripherals/frsky_telemetry.md +++ b/docs/en/peripherals/frsky_telemetry.md @@ -97,7 +97,7 @@ Compatible Taranis receivers (e.g. X9D Plus) running OpenTX 2.1.6 or newer can u ![Telemetry Screen on the Taranis](../../assets/hardware/telemetry/taranis_telemetry.jpg) -Instructions for installing the script can be found here: [LuaPilot Taranis Telemetry script > Taranis Setup OpenTX 2.1.6 or newer](http://ilihack.github.io/LuaPilot_Taranis_Telemetry/) +Instructions for installing the script can be found here: [LuaPilot Taranis Telemetry script > Taranis Setup OpenTX 2.1.6 or newer](https://ilihack.github.io/LuaPilot_Taranis_Telemetry/) If you open the `LuaPil.lua` script with a text editor, you can edit the configuration. Suggested modifications include: @@ -190,7 +190,7 @@ Note that the X series receivers listed below are recommended (e.g. XSR, X8R). T | R9 slim | 10km | S.Bus (16) | Smart Port | 43.3x26.8x13.9mm | 15.8g | ::: info -The above table originates from http://www.redsilico.com/frsky-receiver-chart and FrSky [product documentation](https://www.frsky-rc.com/product-category/receivers/). +The above table originates from https://blog.redsilico.com/frsky-receiver-chart and FrSky [product documentation](https://www.frsky-rc.com/product-category/receivers/). ::: @@ -199,9 +199,9 @@ The above table originates from http://www.redsilico.com/frsky-receiver-chart an Ready-made cables for use with Pixhawk FMUv4 and earlier (except for Pixracer) are available from: -- [Craft and Theory](http://www.craftandtheoryllc.com/telemetry-cable). Versions are available with DF-13 compatible _PicoBlade connectors_ (for FMUv2/3DR Pixhawk, FMUv2/HKPilot32) and _JST-GH connectors_ (for FMUv3/Pixhawk 2 "The Cube" and FMUv4/PixRacer v1). +- [Craft and Theory](https://www.craftandtheoryllc.com/store/telemetry-cables-for-smart-port-radios/). Versions are available with DF-13 compatible _PicoBlade connectors_ (for FMUv2/3DR Pixhawk, FMUv2/HKPilot32) and _JST-GH connectors_ (for FMUv3/Pixhawk 2 "The Cube" and FMUv4/PixRacer v1). - Purchase cable here from Craft and Theory + Purchase cable here from Craft and Theory diff --git a/docs/en/peripherals/gripper_servo.md b/docs/en/peripherals/gripper_servo.md index 2120578b6381..57b9ec68bef6 100644 --- a/docs/en/peripherals/gripper_servo.md +++ b/docs/en/peripherals/gripper_servo.md @@ -9,7 +9,7 @@ This section explains how to connect and configure a [gripper](../peripherals/gr The following PWM-connected servos have been tested with PX4: - [R4-EM-R22-161 push-to-close latch electronic lock](https://southco.com/en_any_int/r4-em-r22-161) (SouthCo) -- [FluxGrip FG40 electro-permanent magnetic gripper](http://zubax.com/fg40) (Zubax) +- [FluxGrip FG40 electro-permanent magnetic gripper](https://shop.zubax.com/products/zubax-epm) (Zubax) ## Connecting a PWM-controlled Gripper diff --git a/docs/en/peripherals/vesc.md b/docs/en/peripherals/vesc.md index 867365a603ca..ab052ff61bd0 100644 --- a/docs/en/peripherals/vesc.md +++ b/docs/en/peripherals/vesc.md @@ -54,4 +54,4 @@ See DroneCAN Troubleshooting - (index.md#troubleshooting). ## Further Information - [VESC Project ESCs](https://vesc-project.com/) -- [Benjamin Vedder's blog](http://vedder.se) (project owner) +- [Benjamin Vedder's blog](https://vedder.se/) (project owner) diff --git a/docs/en/releases/1.12.md b/docs/en/releases/1.12.md index d4e717b28d1d..91fb7570c489 100644 --- a/docs/en/releases/1.12.md +++ b/docs/en/releases/1.12.md @@ -51,9 +51,9 @@ The release includes new hardware support for the following boards, peripherals, - Pixhawk FMUv6U (Read more about this spec on the [Pixhawk GitHub Repository](https://github.com/pixhawk/Pixhawk-Standards)) - Pixhawk FMUv6X (Read more about this spec on the [Pixhawk GitHub Repository](https://github.com/pixhawk/Pixhawk-Standards)) -- CUAV X7 / X7Pro ([Read more about this product on the manufacturers site](http://www.cuav.net/en/x7en/)] -- CUAV Nora ([Read more about this product on the manufacturers site](http://www.cuav.net/en/nora/)) -- CUAV CAN GPS ([Read more about this product on the manufacturers site](http://www.cuav.net/en/neo-3-2/)) +- CUAV X7 / X7Pro +- CUAV Nora +- CUAV CAN GPS (Neo-3-2) - SP Racing H7 Extreme ([Read more about this product on the manufacturers site](http://seriouslypro.com/spracingh7extreme)) - Bitcraze Crazyflie v2.1 ([Read more about this product on the manufacturers site](https://www.bitcraze.io/products/crazyflie-2-1/)) - ARK CAN Flow ([Read more about this product on the manufacturers site](https://arkelectron.com/product/ark-flow/)) @@ -81,7 +81,6 @@ These are removed: ### Multicopter - **More intuitive stick feel in Position mode** - - Horizontal stick input mapped to acceleration instead of velocity setpoints - Removes unexpected tilt changes upon reaching travel speed velocity - Intuitive shunting e.g. when landing @@ -89,12 +88,10 @@ These are removed: - Development: [First attempt](https://github.com/PX4/PX4-Autopilot/pull/12072), [Introduction](https://github.com/PX4/PX4-Autopilot/pull/16052), [Improvements](https://github.com/PX4/PX4-Autopilot/pull/16320), [Bugfix zero oscillation](https://github.com/PX4/PX4-Autopilot/pull/16786), [Bugfix position unlock](https://github.com/PX4/PX4-Autopilot/pull/16791), [Bugfix invalid setpoint](https://github.com/PX4/PX4-Autopilot/pull/17078), [Bugfix high velocity pre takeoff](https://github.com/PX4/PX4-Autopilot/pull/17437) - **Hover thrust independent velocity control gains** - - Parameters `MPC_{XY/Z}_VEL_{P/I/D}` were replaced with `MPC_{XY/Z}_VEL_{P/I/D}_ACC`, see: [MPC_XY_VEL_P_ACC](../advanced_config/parameter_reference.md#MPC_XY_VEL_P_ACC), [MPC_XY_VEL_I_ACC](../advanced_config/parameter_reference.md#MPC_XY_VEL_I_ACC), [MPC_XY_VEL_D_ACC](../advanced_config/parameter_reference.md#MPC_XY_VEL_D_ACC), [MPC_Z_VEL_P_ACC](../advanced_config/parameter_reference.md#MPC_Z_VEL_P_ACC), [MPC_Z_VEL_I_ACC](../advanced_config/parameter_reference.md#MPC_Z_VEL_I_ACC), [MPC_Z_VEL_D_ACC](../advanced_config/parameter_reference.md#MPC_Z_VEL_D_ACC) :::warning The gains have a new meaning - - Scale from velocity error in $m/s$ to acceleration output in $m/s^2$ - Existing gains need to roughly be rescaled by a factor of: $gravitational \_ constant / hover\_thrust$ - Automatic parameter transition assumes 50% hover thrust: `~10m/s^2 / 50% = 20 m/s^2`. @@ -139,7 +136,6 @@ Nuttx was upgraded from [8.2+ to NuttX 10.10.0+](https://github.com/apache/incub - [**BACKPORT**] stm32x7:Ethernet Fixed hardfaults, from too big frames - [**BACKPORT**] stm32:Ethernet Fix too big frames - **Boot up stability** V5-V6X ensuring the LSE (RTC) oscillator is started - - [**BACKPORT**] stm32h7:lse fix Kconfig help text - [**BACKPORT**] stm32f7:lse Use Kconfig values directly - [**BACKPORT**] stm32h7:Add DBGMCU @@ -158,7 +154,6 @@ Nuttx was upgraded from [8.2+ to NuttX 10.10.0+](https://github.com/apache/incub ::: - **Driver changes** - - [**BACKPORT**] drivers/serial: fix Rx interrupt enable for cdcacm - [**BACKPORT**] binnfmt:Fix return before close ELF fd diff --git a/docs/en/ros/external_position_estimation.md b/docs/en/ros/external_position_estimation.md index 2d20e9dcd2ac..81c259563a7d 100644 --- a/docs/en/ros/external_position_estimation.md +++ b/docs/en/ros/external_position_estimation.md @@ -2,10 +2,11 @@ Visual Inertial Odometry (VIO) and Motion Capture (MoCap) systems allow vehicles to navigate when a global position source is unavailable or unreliable (e.g. indoors, or when flying under a bridge. etc.). -Both VIO and MoCap determine a vehicle's *pose* (position and attitude) from "visual" information. +Both VIO and MoCap determine a vehicle's _pose_ (position and attitude) from "visual" information. The main difference between them is the frame perspective: -- VIO uses *onboard sensors* to get pose data from the vehicle's perspective (see [egomotion](https://en.wikipedia.org/wiki/Visual_odometry#Egomotion)). -- MoCap uses a system of *off-board cameras* to get vehicle pose data in a 3D space (i.e. it is an external system that tells the vehicle its pose). + +- VIO uses _onboard sensors_ to get pose data from the vehicle's perspective (see [egomotion](https://en.wikipedia.org/wiki/Visual_odometry#Egomotion)). +- MoCap uses a system of _off-board cameras_ to get vehicle pose data in a 3D space (i.e. it is an external system that tells the vehicle its pose). Pose data from either type of system can be used to update a PX4-based autopilot's local position estimate (relative to the local origin) and also can optionally also be fused into the vehicle attitude estimation. Additionally, if the external pose system also provides linear velocity measurements, it can be used to improve the state estimate (fusion of linear velocity measurements is only supported by the EKF2). @@ -19,12 +20,12 @@ The instructions differ depending on whether you are using the EKF2 or LPE estim PX4 uses the following MAVLink messages for getting external position information, and maps them to [uORB topics](../middleware/uorb.md): -MAVLink | uORB ---- | --- -[VISION_POSITION_ESTIMATE](https://mavlink.io/en/messages/common.html#VISION_POSITION_ESTIMATE) | `vehicle_visual_odometry` -[ODOMETRY](https://mavlink.io/en/messages/common.html#ODOMETRY) (`frame_id =` [MAV_FRAME_LOCAL_FRD](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_FRD)) | `vehicle_visual_odometry` -[ATT_POS_MOCAP](https://mavlink.io/en/messages/common.html#ATT_POS_MOCAP) | `vehicle_mocap_odometry` -[ODOMETRY](https://mavlink.io/en/messages/common.html#ODOMETRY) (`frame_id =` [MAV_FRAME_MOCAP_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_MOCAP_NED)) | `vehicle_mocap_odometry` +| MAVLink | uORB | +| -------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------- | +| [VISION_POSITION_ESTIMATE](https://mavlink.io/en/messages/common.html#VISION_POSITION_ESTIMATE) | `vehicle_visual_odometry` | +| [ODOMETRY](https://mavlink.io/en/messages/common.html#ODOMETRY) (`frame_id =` [MAV_FRAME_LOCAL_FRD](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_FRD)) | `vehicle_visual_odometry` | +| [ATT_POS_MOCAP](https://mavlink.io/en/messages/common.html#ATT_POS_MOCAP) | `vehicle_mocap_odometry` | +| [ODOMETRY](https://mavlink.io/en/messages/common.html#ODOMETRY) (`frame_id =` [MAV_FRAME_MOCAP_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_MOCAP_NED)) | `vehicle_mocap_odometry` | EKF2 only subscribes to `vehicle_visual_odometry` topics and can hence only process the first two messages (a MoCap system must generate these messages to work with EKF2). The odometry message is the only message that can send also linear velocities to PX4. @@ -43,46 +44,45 @@ The following MAVLink "vision" messages are not currently supported by PX4: [VISION_SPEED_ESTIMATE](https://mavlink.io/en/messages/common.html#VISION_SPEED_ESTIMATE), [VICON_POSITION_ESTIMATE](https://mavlink.io/en/messages/common.html#VICON_POSITION_ESTIMATE) - ## Reference Frames PX4 uses FRD (X **F**orward, Y **R**ight and Z **D**own) for the local body frame as well for the reference frame. When using the heading of the magnetometer, the PX4 reference frame x axis will be aligned with north, so therefore it is called NED (X **N**orth, Y **E**ast, Z **D**own). The heading of the reference frame of the PX4 estimator and the one of the external pose estimate will not match in most cases. Therefore the reference frame of the external pose estimate is named differently, it is called [MAV_FRAME_LOCAL_FRD](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_FRD). Depending on the source of your reference frame, you will need to apply a custom transformation to the pose estimate before sending the MAVLink Vision/MoCap message. -This is necessary to change the orientation of the parent and child frame of the pose estimate, such that it fits the PX4 convention. Have a look at the MAVROS [*odom* plugin](https://github.com/mavlink/mavros/blob/master/mavros_extras/src/plugins/odom.cpp) for the necessary transformations. +This is necessary to change the orientation of the parent and child frame of the pose estimate, such that it fits the PX4 convention. Have a look at the MAVROS [_odom_ plugin](https://github.com/mavlink/mavros/blob/master/mavros_extras/src/plugins/odom.cpp) for the necessary transformations. :::tip ROS users can find more detailed instructions below in [Reference Frames and ROS](#reference-frames-and-ros). ::: -For example, if using the Optitrack framework the local frame has $x{}$ and $z{}$ on the horizontal plane (*x* front and *z* right) while *y* axis is vertical and pointing up. +For example, if using the Optitrack framework the local frame has $x{}$ and $z{}$ on the horizontal plane (_x_ front and _z_ right) while _y_ axis is vertical and pointing up. A simple trick is swapping axis in order to obtained NED convention. If `x_{mav}`, `y_{mav}` and `z_{mav}` are the coordinates that are sent through MAVLink as position feedback, then we obtain: + ``` x_{mav} = x_{mocap} y_{mav} = z_{mocap} z_{mav} = - y_{mocap} ``` -Regarding the orientation, keep the scalar part *w* of the quaternion the same and swap the vector part *x*, *y* and *z* in the same way. +Regarding the orientation, keep the scalar part _w_ of the quaternion the same and swap the vector part _x_, _y_ and _z_ in the same way. You can apply this trick with every system - if you need to obtain a NED frame, look at your MoCap output and swap axis accordingly. - ## EKF2 Tuning/Configuration Note: this is a quick overview. For more detailed information, check the [Using PX4's Navigation Filter (EKF2)](../advanced_config/tuning_the_ecl_ekf.md) -The following parameters must be set to use external position information with EKF2 (these can be set in *QGroundControl* > **Vehicle Setup > Parameters > EKF2**). +The following parameters must be set to use external position information with EKF2 (these can be set in _QGroundControl_ > **Vehicle Setup > Parameters > EKF2**). -Parameter | Setting for External Position Estimation ---- | --- -[EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL) | Set *horizontal position fusion*, *vertical vision fusion*, *velocity fusion*, and *yaw fusion*, according to your desired fusion model. -[EKF2_HGT_REF](../advanced_config/parameter_reference.md#EKF2_HGT_REF) | Set to *Vision* to use the vision as the reference source for altitude estimation. -[EKF2_EV_DELAY](../advanced_config/parameter_reference.md#EKF2_EV_DELAY) | Set to the difference between the timestamp of the measurement and the "actual" capture time. For more information see [below](#tuning-EKF2_EV_DELAY). -[EKF2_EV_POS_X](../advanced_config/parameter_reference.md#EKF2_EV_POS_X), [EKF2_EV_POS_Y](../advanced_config/parameter_reference.md#EKF2_EV_POS_Y), [EKF2_EV_POS_Z](../advanced_config/parameter_reference.md#EKF2_EV_POS_Z) | Set the position of the vision sensor (or MoCap markers) with respect to the robot's body frame. +| Parameter | Setting for External Position Estimation | +| ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------ | +| [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL) | Set _horizontal position fusion_, _vertical vision fusion_, _velocity fusion_, and _yaw fusion_, according to your desired fusion model. | +| [EKF2_HGT_REF](../advanced_config/parameter_reference.md#EKF2_HGT_REF) | Set to _Vision_ to use the vision as the reference source for altitude estimation. | +| [EKF2_EV_DELAY](../advanced_config/parameter_reference.md#EKF2_EV_DELAY) | Set to the difference between the timestamp of the measurement and the "actual" capture time. For more information see [below](#tuning-EKF2_EV_DELAY). | +| [EKF2_EV_POS_X](../advanced_config/parameter_reference.md#EKF2_EV_POS_X), [EKF2_EV_POS_Y](../advanced_config/parameter_reference.md#EKF2_EV_POS_Y), [EKF2_EV_POS_Z](../advanced_config/parameter_reference.md#EKF2_EV_POS_Z) | Set the position of the vision sensor (or MoCap markers) with respect to the robot's body frame. | You can also disable GNSS, baro and range finder fusion using [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL), [EKF2_BARO_CTRL](../advanced_config/parameter_reference.md#EKF2_BARO_CTRL) and [EKF2_RNG_CTRL](../advanced_config/parameter_reference.md#EKF2_RNG_CTRL), respectively. @@ -91,9 +91,10 @@ Reboot the flight controller in order for parameter changes to take effect. ::: + #### Tuning EKF2_EV_DELAY -[EKF2_EV_DELAY](../advanced_config/parameter_reference.md#EKF2_EV_DELAY) is the *Vision Position Estimator delay relative to IMU measurements*. +[EKF2_EV_DELAY](../advanced_config/parameter_reference.md#EKF2_EV_DELAY) is the _Vision Position Estimator delay relative to IMU measurements_. Or in other words, it is the difference between the vision system timestamp and the "actual" capture time that would have been recorded by the IMU clock (the "base clock" for EKF2). @@ -125,19 +126,18 @@ See [Building the Code](../dev_setup/building_px4.md) for more details. ### Enabling External Pose Input -The following parameters must be set to use external position information with LPE (these can be set in *QGroundControl* > **Vehicle Setup > Parameters > Local Position Estimator**). - -Parameter | Setting for External Position Estimation ---- | --- -[LPE_FUSION](../advanced_config/parameter_reference.md#LPE_FUSION) | Vision integration is enabled if *fuse vision position* is checked (it is enabled by default). -[ATT_EXT_HDG_M](../advanced_config/parameter_reference.md#ATT_EXT_HDG_M) | Set to 1 or 2 to enable external heading integration. Setting it to 1 will cause vision to be used, while 2 enables MoCap heading use. +The following parameters must be set to use external position information with LPE (these can be set in _QGroundControl_ > **Vehicle Setup > Parameters > Local Position Estimator**). +| Parameter | Setting for External Position Estimation | +| ------------------------------------------------------------------------ | -------------------------------------------------------------------------------------------------------------------------------------- | +| [LPE_FUSION](../advanced_config/parameter_reference.md#LPE_FUSION) | Vision integration is enabled if _fuse vision position_ is checked (it is enabled by default). | +| [ATT_EXT_HDG_M](../advanced_config/parameter_reference.md#ATT_EXT_HDG_M) | Set to 1 or 2 to enable external heading integration. Setting it to 1 will cause vision to be used, while 2 enables MoCap heading use. | ### Disabling Barometer Fusion If a highly accurate altitude is already available from VIO or MoCap information, it may be useful to disable the baro correction in LPE to reduce drift on the Z axis. -This can be done by in *QGroundControl* by unchecking the *fuse baro* option in the [LPE_FUSION](../advanced_config/parameter_reference.md#LPE_FUSION) parameter. +This can be done by in _QGroundControl_ by unchecking the _fuse baro_ option in the [LPE_FUSION](../advanced_config/parameter_reference.md#LPE_FUSION) parameter. ### Tuning Noise Parameters @@ -161,7 +161,7 @@ This can then be used when planning and executing indoor missions, or to set a l ## Working with ROS -ROS is not *required* for supplying external pose information, but is highly recommended as it already comes with good integrations with VIO and MoCap systems. +ROS is not _required_ for supplying external pose information, but is highly recommended as it already comes with good integrations with VIO and MoCap systems. PX4 must already have been set up as above. ### Getting Pose Data Into ROS @@ -171,51 +171,51 @@ VIO and MoCap systems have different ways of obtaining pose data, and have their The setup for specific systems is covered [below](#setup_specific_systems). For other systems consult the vendor setup documentation. - + ### Relaying Pose Data to PX4 MAVROS has plugins to relay a visual estimation from a VIO or MoCap system using the following pipelines: -ROS | MAVLink | uORB ---- | --- | --- -/mavros/vision_pose/pose | [VISION_POSITION_ESTIMATE](https://mavlink.io/en/messages/common.html#VISION_POSITION_ESTIMATE) | `vehicle_visual_odometry` -/mavros/odometry/out (`frame_id = odom`, `child_frame_id = base_link`) | [ODOMETRY](https://mavlink.io/en/messages/common.html#ODOMETRY) (`frame_id =` [MAV_FRAME_LOCAL_FRD](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_FRD)) | `vehicle_visual_odometry` -/mavros/mocap/pose | [ATT_POS_MOCAP](https://mavlink.io/en/messages/common.html#ATT_POS_MOCAP) | `vehicle_mocap_odometry` -/mavros/odometry/out (`frame_id = odom`, `child_frame_id = base_link`) | [ODOMETRY](https://mavlink.io/en/messages/common.html#ODOMETRY) (`frame_id =` [MAV_FRAME_LOCAL_FRD](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_FRD)) | `vehicle_mocap_odometry` +| ROS | MAVLink | uORB | +| ---------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------- | +| /mavros/vision_pose/pose | [VISION_POSITION_ESTIMATE](https://mavlink.io/en/messages/common.html#VISION_POSITION_ESTIMATE) | `vehicle_visual_odometry` | +| /mavros/odometry/out (`frame_id = odom`, `child_frame_id = base_link`) | [ODOMETRY](https://mavlink.io/en/messages/common.html#ODOMETRY) (`frame_id =` [MAV_FRAME_LOCAL_FRD](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_FRD)) | `vehicle_visual_odometry` | +| /mavros/mocap/pose | [ATT_POS_MOCAP](https://mavlink.io/en/messages/common.html#ATT_POS_MOCAP) | `vehicle_mocap_odometry` | +| /mavros/odometry/out (`frame_id = odom`, `child_frame_id = base_link`) | [ODOMETRY](https://mavlink.io/en/messages/common.html#ODOMETRY) (`frame_id =` [MAV_FRAME_LOCAL_FRD](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_FRD)) | `vehicle_mocap_odometry` | You can use any of the above pipelines with LPE. If you're working with EKF2, only the "vision" pipelines are supported. -To use MoCap data with EKF2 you will have to [remap](http://wiki.ros.org/roslaunch/XML/remap) the pose topic that you get from MoCap: +To use MoCap data with EKF2 you will have to [remap](https://wiki.ros.org/roslaunch/XML/remap) the pose topic that you get from MoCap: + - MoCap ROS topics of type `geometry_msgs/PoseStamped` or `geometry_msgs/PoseWithCovarianceStamped` must be remapped to `/mavros/vision_pose/pose`. The `geometry_msgs/PoseStamped` topic is most common as MoCap doesn't usually have associated covariances to the data. - If you get data through a `nav_msgs/Odometry` ROS message then you will need to remap it to `/mavros/odometry/out`, making sure to update the `frame_id` and `child_frame_id` accordingly. - The odometry frames `frame_id = odom`, `child_frame_id = base_link` can be changed by updating the file in `mavros/launch/px4_config.yaml`. However, the current version of mavros (`1.3.0`) needs to be able to use the tf tree to find a transform from `frame_id` to the hardcoded frame `odom_ned`. The same applies to the `child_frame_id`, which needs to be connected in the tf tree to the hardcoded frame `base_link_frd`. If you are using mavros `1.2.0` and you didn't update the file `mavros/launch/px4_config.yaml`, then you can safely use the odometry frames `frame_id = odom`, `child_frame_id = base_link` without much worry. - Note that if you are sending odometry data to px4 using `child_frame_id = base_link`, then you need to make sure that the `twist` portion of the `nav_msgs/Odometry` message is **expressed in body frame**, **not in inertial frame!!!!!**. - ### Reference Frames and ROS The local/world and world frames used by ROS and PX4 are different. -Frame | PX4 | ROS ---- | --- | --- -Body | FRD (X **F**orward, Y **R**ight, Z **D**own) | FLU (X **F**orward, Y **L**eft, Z **U**p), usually named `base_link` -World | FRD or NED (X **N**orth, Y **E**ast, Z **D**own) | FLU or ENU (X **E**ast, Y **N**orth, Z **U**p), with the naming being `odom` or `map` +| Frame | PX4 | ROS | +| ----- | ------------------------------------------------ | ------------------------------------------------------------------------------------- | +| Body | FRD (X **F**orward, Y **R**ight, Z **D**own) | FLU (X **F**orward, Y **L**eft, Z **U**p), usually named `base_link` | +| World | FRD or NED (X **N**orth, Y **E**ast, Z **D**own) | FLU or ENU (X **E**ast, Y **N**orth, Z **U**p), with the naming being `odom` or `map` | :::tip -See [REP105: Coordinate Frames for Mobile Platforms](http://www.ros.org/reps/rep-0105.html) for more information about ROS frames. +See [REP105: Coordinate Frames for Mobile Platforms](https://www.ros.org/reps/rep-0105.html) for more information about ROS frames. ::: Both frames are shown in the image below (FRD on the left/FLU on the right). ![Reference frames](../../assets/lpe/ref_frames.png) -With EKF2 when using external heading estimation, magnetic north can either be ignored and or the heading offset to magnetic north can be calculated and compensated. Depending on your choice the yaw angle is given with respect to either magnetic north or local *x*. +With EKF2 when using external heading estimation, magnetic north can either be ignored and or the heading offset to magnetic north can be calculated and compensated. Depending on your choice the yaw angle is given with respect to either magnetic north or local _x_. ::: info -When creating the rigid body in the MoCap software, remember to first align the robot's local *x* axis with the world *x* axis otherwise the yaw estimate will have an offset. This can stop the external pose estimate fusion from working properly. +When creating the rigid body in the MoCap software, remember to first align the robot's local _x_ axis with the world _x_ axis otherwise the yaw estimate will have an offset. This can stop the external pose estimate fusion from working properly. Yaw angle should be zero when body and reference frame align. ::: @@ -234,23 +234,27 @@ You therefore have to add the external pose's body frame to the tf tree. This ca ``` + Make sure that you change the values of yaw, pitch and roll such that it properly attaches the external pose's body frame to the `base_link` or `base_link_frd`. -Have a look at the [tf package](http://wiki.ros.org/tf#static_transform_publisher) for further help on how to specify the transformation between the frames. +Have a look at the [tf package](https://wiki.ros.org/tf#static_transform_publisher) for further help on how to specify the transformation between the frames. You can use rviz to check if you attached the frame right. The name of the `external_pose_child_frame` has to match the child_frame_id of your `nav_msgs/Odometry` message. The same also applies for the reference frame of the external pose. You have to attach the reference frame of the external pose as child to either the `odom` or `odom_frd` frame. Adapt therefore the following code line accordingly. + ``` ``` + If the reference frame has the z axis pointing upwards you can attached it without any rotation (yaw=0, pitch=0, roll=0) to the `odom` frame. The name of `external_pose_parent_frame` has to match the frame_id of the odometry message. ::: info -When using the MAVROS *odom* plugin, it is important that no other node is publishing a transform between the external pose's reference and child frame. -This might break the *tf* tree. +When using the MAVROS _odom_ plugin, it is important that no other node is publishing a transform between the external pose's reference and child frame. +This might break the _tf_ tree. ::: + ## Specific System Setups ### OptiTrack MoCap @@ -259,17 +263,17 @@ The following steps explain how to feed position estimates from an [OptiTrack](h It is assumed that the MoCap system is calibrated. See [this video](https://www.youtube.com/watch?v=cNZaFEghTBU) for a tutorial on the calibration process. -#### Steps on the *Motive* MoCap software +#### Steps on the _Motive_ MoCap software -* Align your robot's forward direction with the [system +x-axis](https://v20.wiki.optitrack.com/index.php?title=Template:Coordinate_System) -* [Define a rigid body in the Motive software](https://www.youtube.com/watch?v=1e6Qqxqe-k0). Give the robot a name that does not contain spaces, e.g. `robot1` instead of `Rigidbody 1` -* [Enable Frame Broadacst and VRPN streaming](https://www.youtube.com/watch?v=yYRNG58zPFo) -* Set the Up axis to be the Z axis (the default is Y) +- Align your robot's forward direction with the [system +x-axis](https://v20.wiki.optitrack.com/index.php?title=Template:Coordinate_System) +- [Define a rigid body in the Motive software](https://www.youtube.com/watch?v=1e6Qqxqe-k0). Give the robot a name that does not contain spaces, e.g. `robot1` instead of `Rigidbody 1` +- [Enable Frame Broadacst and VRPN streaming](https://www.youtube.com/watch?v=yYRNG58zPFo) +- Set the Up axis to be the Z axis (the default is Y) #### Getting pose data into ROS -* Install the `vrpn_client_ros` package -* You can get each rigid body pose on an individual topic by running +- Install the `vrpn_client_ros` package +- You can get each rigid body pose on an individual topic by running ```sh roslaunch vrpn_client_ros sample.launch server:= ``` @@ -291,7 +295,6 @@ Assuming that you have configured EKF2 parameters as described above, PX4 now is You are now set to proceed to the first flight. - ## First Flight After setting up one of the (specific) systems described above you should now be ready to test. @@ -301,19 +304,19 @@ The instructions below show how to do so for MoCap and VIO systems Be sure to perform the following checks before your first flight: -* Set the PX4 parameter `MAV_ODOM_LP` to 1. +- Set the PX4 parameter `MAV_ODOM_LP` to 1. PX4 will then stream back the received external pose as MAVLink [ODOMETRY](https://mavlink.io/en/messages/common.html#ODOMETRY) messages. -* You can check these MAVLink messages with the *QGroundControl* [MAVLink Inspector](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/analyze_view/mavlink_inspector.html) +- You can check these MAVLink messages with the _QGroundControl_ [MAVLink Inspector](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/analyze_view/mavlink_inspector.html) In order to do this, yaw the vehicle until the quaternion of the `ODOMETRY` message is very close to a unit quaternion. (w=1, x=y=z=0) -* At this point the body frame is aligned with the reference frame of the external pose system. +- At this point the body frame is aligned with the reference frame of the external pose system. If you do not manage to get a quaternion close to the unit quaternion without rolling or pitching your vehicle, your frame probably still have a pitch or roll offset. Do not proceed if this is the case and check your coordinate frames again. -* Once aligned you can pick the vehicle up from the ground and you should see the position's z coordinate decrease. +- Once aligned you can pick the vehicle up from the ground and you should see the position's z coordinate decrease. Moving the vehicle in forward direction, should increase the position's x coordinate. While moving the vehicle to the right should increase the y coordinate. In the case you send also linear velocities from the external pose system, you should also check the linear velocities. - Check that the linear velocities are in expressed in the *FRD* body frame reference frame. -* Set the PX4 parameter `MAV_ODOM_LP` back to 0. PX4 will stop streaming this message back. + Check that the linear velocities are in expressed in the _FRD_ body frame reference frame. +- Set the PX4 parameter `MAV_ODOM_LP` back to 0. PX4 will stop streaming this message back. If those steps are consistent, you can try your first flight. diff --git a/docs/en/ros/mavros_installation.md b/docs/en/ros/mavros_installation.md index 6addff50d105..0929b843df92 100644 --- a/docs/en/ros/mavros_installation.md +++ b/docs/en/ros/mavros_installation.md @@ -7,7 +7,7 @@ This documentation reflects the "old approach". This documentation explains how to set up communication between the PX4 Autopilot and a ROS 1 enabled companion computer using MAVROS. -[MAVROS](http://wiki.ros.org/mavros#mavros.2BAC8-Plugins.sys_status) is a ROS 1 package that enables MAVLink extendable communication between computers running ROS 1 for any MAVLink enabled autopilot, ground station, or peripheral. +[MAVROS](https://wiki.ros.org/mavros#mavros.2BAC8-Plugins.sys_status) is a ROS 1 package that enables MAVLink extendable communication between computers running ROS 1 for any MAVLink enabled autopilot, ground station, or peripheral. _MAVROS_ is the "official" supported bridge between ROS 1 and the MAVLink protocol. First we install PX4 and ROS, and then MAVROS. @@ -26,10 +26,9 @@ They cover the _ROS Melodic and Noetic_ releases. ::: tab ROS Noetic (Ubuntu 20.04) -If you're working with [ROS Noetic](http://wiki.ros.org/noetic) on Ubuntu 20.04: +If you're working with [ROS Noetic](https://wiki.ros.org/noetic) on Ubuntu 20.04: 1. Install PX4 without the simulator toolchain: - 1. [Download PX4 Source Code](../dev_setup/building_px4.md): ```sh @@ -52,7 +51,7 @@ If you're working with [ROS Noetic](http://wiki.ros.org/noetic) on Ubuntu 20.04: sudo apt-get install protobuf-compiler libeigen3-dev libopencv-dev -y ``` -1. Follow the [Noetic Installation instructions](http://wiki.ros.org/noetic/Installation/Ubuntu#Installation) (ros-noetic-desktop-full is recommended). +1. Follow the [Noetic Installation instructions](https://wiki.ros.org/noetic/Installation/Ubuntu#Installation) (ros-noetic-desktop-full is recommended). ::: @@ -80,8 +79,8 @@ If you're working with ROS "Melodic on Ubuntu 18.04: Also note: - ROS Melodic is installed with Gazebo (Classic) 9 by default. - Your catkin (ROS build system) workspace is created at **~/catkin_ws/**. - - The script uses instructions from the ROS Wiki "Melodic" [Ubuntu page](http://wiki.ros.org/melodic/Installation/Ubuntu). - ::: + - The script uses instructions from the ROS Wiki "Melodic" [Ubuntu page](https://wiki.ros.org/melodic/Installation/Ubuntu). + ::: :::: @@ -145,7 +144,6 @@ Now you are ready to do the build: ``` 1. Install MAVROS from source using either released or latest version: - - Released/stable ```sh @@ -203,6 +201,6 @@ If you have an example app using the PX4 Autopilot and MAVROS, we can help you g ## See Also -- [mavros ROS Package Summary](http://wiki.ros.org/mavros#mavros.2BAC8-Plugins.sys_status) +- [mavros ROS Package Summary](https://wiki.ros.org/mavros#mavros.2BAC8-Plugins.sys_status) - [mavros source](https://github.com/mavlink/mavros/) -- [ROS Melodic installation instructions](http://wiki.ros.org/melodic/Installation) +- [ROS Melodic installation instructions](https://wiki.ros.org/melodic/Installation) diff --git a/docs/en/ros/mavros_offboard_cpp.md b/docs/en/ros/mavros_offboard_cpp.md index 96bb3fac8da8..6472670ef85c 100644 --- a/docs/en/ros/mavros_offboard_cpp.md +++ b/docs/en/ros/mavros_offboard_cpp.md @@ -123,7 +123,7 @@ int main(int argc, char **argv) ``` The `mavros_msgs` package contains all of the custom messages required to operate services and topics provided by the MAVROS package. -All services and topics as well as their corresponding message types are documented in the [mavros wiki](http://wiki.ros.org/mavros). +All services and topics as well as their corresponding message types are documented in the [mavros wiki](https://wiki.ros.org/mavros). ```cpp mavros_msgs::State current_state; @@ -194,7 +194,7 @@ offb_set_mode.request.custom_mode = "OFFBOARD"; ``` We set the custom mode to `OFFBOARD`. -A list of [supported modes](http://wiki.ros.org/mavros/CustomModes#PX4_native_flight_stack) is available for reference. +A list of [supported modes](https://wiki.ros.org/mavros/CustomModes#PX4_native_flight_stack) is available for reference. ```cpp mavros_msgs::CommandBool arm_cmd; diff --git a/docs/en/ros/mavros_offboard_python.md b/docs/en/ros/mavros_offboard_python.md index 77d917bf71de..df36acace946 100644 --- a/docs/en/ros/mavros_offboard_python.md +++ b/docs/en/ros/mavros_offboard_python.md @@ -155,7 +155,7 @@ if __name__ == "__main__": ## Code explanation The `mavros_msgs` package contains all of the custom messages required to operate services and topics provided by the MAVROS package. -All services and topics as well as their corresponding message types are documented in the [mavros wiki](http://wiki.ros.org/mavros). +All services and topics as well as their corresponding message types are documented in the [mavros wiki](https://wiki.ros.org/mavros). ```py import rospy @@ -237,7 +237,7 @@ for i in range(100): ``` We prepare the message request used to set the custom mode to `OFFBOARD`. -A list of [supported modes](http://wiki.ros.org/mavros/CustomModes#PX4_native_flight_stack) is available for reference. +A list of [supported modes](https://wiki.ros.org/mavros/CustomModes#PX4_native_flight_stack) is available for reference. ```py offb_set_mode = SetModeRequest() diff --git a/docs/en/ros/offboard_control.md b/docs/en/ros/offboard_control.md index 75b4883719ac..3f734001794f 100644 --- a/docs/en/ros/offboard_control.md +++ b/docs/en/ros/offboard_control.md @@ -39,9 +39,7 @@ Usually, there are three ways of setting up offboard communication. 2. One connected to a ground station computer Example radios include: - - - [Lairdtech RM024](http://www.lairdtech.com/products/rm024) - - [Digi International XBee Pro](http://www.digi.com/products/xbee-rf-solutions/modules) + - [Digi International XBee Pro](https://www.digi.com/products/embedded-systems/digi-xbee/rf-modules/sub-1-ghz-rf-modules) [![Mermaid graph: mavlink channel](https://mermaid.ink/img/eyJjb2RlIjoiZ3JhcGggVEQ7XG4gIGduZFtHcm91bmQgU3RhdGlvbl0gLS1NQVZMaW5rLS0-IHJhZDFbR3JvdW5kIFJhZGlvXTtcbiAgcmFkMSAtLVJhZGlvUHJvdG9jb2wtLT4gcmFkMltWZWhpY2xlIFJhZGlvXTtcbiAgcmFkMiAtLU1BVkxpbmstLT4gYVtBdXRvcGlsb3RdOyIsIm1lcm1haWQiOnsidGhlbWUiOiJkZWZhdWx0In0sInVwZGF0ZUVkaXRvciI6ZmFsc2V9)](https://mermaid-js.github.io/mermaid-live-editor/#/edit/eyJjb2RlIjoiZ3JhcGggVEQ7XG4gIGduZFtHcm91bmQgU3RhdGlvbl0gLS1NQVZMaW5rLS0-IHJhZDFbR3JvdW5kIFJhZGlvXTtcbiAgcmFkMSAtLVJhZGlvUHJvdG9jb2wtLT4gcmFkMltWZWhpY2xlIFJhZGlvXTtcbiAgcmFkMiAtLU1BVkxpbmstLT4gYVtBdXRvcGlsb3RdOyIsIm1lcm1haWQiOnsidGhlbWUiOiJkZWZhdWx0In0sInVwZGF0ZUVkaXRvciI6ZmFsc2V9) @@ -54,7 +52,7 @@ graph TD; ### On-board processor -A small computer mounted onto the vehicle, connected to the autopilot through a serial port or Ehthernet port. +A small computer mounted onto the vehicle, connected to the autopilot through a serial port or Ethernet port. There are many possibilities here and it will depend on what kind of additional on-board processing you want to do in addition to sending commands to the autopilot. Some examples are provided in [Companion Computers](../companion_computer/index.md#companion-computer-options). diff --git a/docs/en/ros/raspberrypi_installation.md b/docs/en/ros/raspberrypi_installation.md index 4b4fa9380bfc..f93d7f46923e 100644 --- a/docs/en/ros/raspberrypi_installation.md +++ b/docs/en/ros/raspberrypi_installation.md @@ -3,14 +3,17 @@ This is a guide on how to install ROS-indigo on a Raspberry Pi 2 serving as a companion computer for Pixhawk. ## Prerequisites -* A working Raspberry Pi with monitor, keyboard, or configured SSH connection -* This guide assumes that you have Raspbian "JESSIE" installed on your RPi. If not: [install it](https://www.raspberrypi.org/downloads/raspbian/) or [upgrade](http://raspberrypi.stackexchange.com/questions/27858/upgrade-to-raspbian-jessie) your Raspbian Wheezy to Jessie. + +- A working Raspberry Pi with monitor, keyboard, or configured SSH connection +- This guide assumes that you have Raspbian "JESSIE" installed on your RPi. If not: [install it](https://www.raspberrypi.org/downloads/raspbian/) or [upgrade](https://raspberrypi.stackexchange.com/questions/27858/upgrade-to-raspbian-jessie) your Raspbian Wheezy to Jessie. ## Installation -Follow [this guide](http://wiki.ros.org/ROSberryPi/Installing%20ROS%20Indigo%20on%20Raspberry%20Pi) for the actual installation of ROS Indigo. Note: Install the "ROS-Comm" variant. The Desktop variant is too heavyweight. + +Follow [this guide](https://wiki.ros.org/ROSberryPi/Installing%20ROS%20Indigo%20on%20Raspberry%20Pi) for the actual installation of ROS Indigo. Note: Install the "ROS-Comm" variant. The Desktop variant is too heavyweight. ### Errors when installing packages -If you want to download packages (e.g. `sudo apt-get install ros-indigo-ros-tutorials`), you might get an error saying: "unable to locate package ros-indigo-ros-tutorials". + +If you want to download packages (e.g. `sudo apt-get install ros-indigo-ros-tutorials`), you might get an error saying: "unable to locate package ros-indigo-ros-tutorials". If so, proceed as follows: Go to your catkin workspace (e.g. ~/ros_catkin_ws) and change the name of the packages. diff --git a/docs/en/ros2/index.md b/docs/en/ros2/index.md index 64b8ae76fd03..50043ad978d0 100644 --- a/docs/en/ros2/index.md +++ b/docs/en/ros2/index.md @@ -5,7 +5,7 @@ :::warning Tip The PX4 development team highly recommend that you use/migrate to this version of ROS! -This is the newest version of [ROS](http://www.ros.org/) (Robot Operating System). +This is the newest version of [ROS](https://www.ros.org/) (Robot Operating System). It significantly improves on ROS "1", and in particular allows a much deeper and lower-latency integration with PX4. ::: diff --git a/docs/en/ros2/user_guide.md b/docs/en/ros2/user_guide.md index 2f666b898f67..b338fcb87616 100644 --- a/docs/en/ros2/user_guide.md +++ b/docs/en/ros2/user_guide.md @@ -124,7 +124,6 @@ To install ROS 2 and its dependencies: ::: tab foxy To install ROS 2 "Foxy" on Ubuntu 20.04: - - Follow the official installation guide: [Install ROS 2 Foxy](https://docs.ros.org/en/foxy/Installation/Ubuntu-Install-Debians.html). You can install _either_ the desktop (`ros-foxy-desktop`) _or_ bare-bones versions (`ros-foxy-ros-base`), _and_ the development tools (`ros-dev-tools`). @@ -187,7 +186,6 @@ To start the simulator (and client): :::: tabs ::: tab humble - - Start a PX4 [Gazebo](../sim_gazebo_gz/index.md) simulation using: ```sh @@ -197,7 +195,6 @@ To start the simulator (and client): ::: ::: tab foxy - - Start a PX4 [Gazebo Classic](../sim_gazebo_classic/index.md) simulation using: ```sh @@ -433,7 +430,7 @@ The local/world and body frames used by ROS and PX4 are different. | World | FRD or NED (X **N**orth, Y **E**ast, Z **D**own) | FLU or ENU (X **E**ast, Y **N**orth, Z **U**p) | :::tip -See [REP105: Coordinate Frames for Mobile Platforms](http://www.ros.org/reps/rep-0105.html) for more information about ROS frames. +See [REP105: Coordinate Frames for Mobile Platforms](https://www.ros.org/reps/rep-0105.html) for more information about ROS frames. ::: Both frames are shown in the image below (FRD on the left/FLU on the right). @@ -444,7 +441,6 @@ The FRD (NED) conventions are adopted on **all** PX4 topics unless explicitly sp Therefore, ROS 2 nodes that want to interface with PX4 must take care of the frames conventions. - To rotate a vector from ENU to NED two basic rotations must be performed: - - first a pi/2 rotation around the `Z`-axis (up), - then a pi rotation around the `X`-axis (old East/new North). diff --git a/docs/en/sensor/lidar_lite.md b/docs/en/sensor/lidar_lite.md index ac333250a5f3..56162491fe18 100644 --- a/docs/en/sensor/lidar_lite.md +++ b/docs/en/sensor/lidar_lite.md @@ -35,7 +35,7 @@ This is currently (Q4/2015) under investigation by the manufacturer and potentia The recommended robust setup is a v1 device interfaced via PWM. ::: -The standard wiring instructions for Lidar-Lite 3 (from the [Operation Manual](http://static.garmin.com/pumac/LIDAR_Lite_v3_Operation_Manual_and_Technical_Specifications.pdf)) are shown below. +The standard wiring instructions for Lidar-Lite 3 (from the [Operation Manual](https://static.garmin.com/pumac/LIDAR_Lite_v3_Operation_Manual_and_Technical_Specifications.pdf)) are shown below. Lidar-Lite v2 and v3 are the same, except that the order of pins in the connector is reversed (i.e. it is as though the connector was turned over). ![LidarLite v3 - Standard Wiring from Garmin Specification](../../assets/hardware/sensors/lidar_lite/lidar_lite2_standard_wiring_spec.jpg) @@ -83,4 +83,4 @@ If missing, you would also need to add the driver (`drivers/ll40ls`) to the boar ## Further Information -- [LIDAR_Lite_v3_Operation_Manual_and_Technical_Specifications.pdf](http://static.garmin.com/pumac/LIDAR_Lite_v3_Operation_Manual_and_Technical_Specifications.pdf) (Garmin) +- [LIDAR_Lite_v3_Operation_Manual_and_Technical_Specifications.pdf](https://static.garmin.com/pumac/LIDAR_Lite_v3_Operation_Manual_and_Technical_Specifications.pdf) (Garmin) diff --git a/docs/en/sensor/pmw3901.md b/docs/en/sensor/pmw3901.md index 6dc014b79bfb..d7afc5876f2b 100644 --- a/docs/en/sensor/pmw3901.md +++ b/docs/en/sensor/pmw3901.md @@ -150,7 +150,7 @@ A screenshot showing the I2C pins (SLA, SLC, GND, and VCC) is provided below. ## Hex HereFlow PMW3901 Optical Flow Sensor -The Hex [HereFlow PMW3901 Optical Flow Sensor](http://www.proficnc.com/all-products/185-pixhawk2-suite.html) is a tiny board containing the PMW3901 flow module, VL53L1X distance sensor, and an IMU (used to synchronize the flow data with the gyro data). +The Hex [HereFlow PMW3901 Optical Flow Sensor](https://docs.cubepilot.org/user-guides/flow-senor/here-flow) is a tiny board containing the PMW3901 flow module, VL53L1X distance sensor, and an IMU (used to synchronize the flow data with the gyro data). An onboard microcontroller samples the three sensors and publishes two DroneCAN messages containing all the information needed for the flow and distance sensor calculations. @@ -160,9 +160,7 @@ As for the other optical flow boards, we recommend that you use an [external dis [PX4 configuration](#px4-configuration) and [mounting/orientation](#mounting-orientation) instructions are provided above. - - -### DroneCAN Wiring/Setup +### DroneCAN Wiring/Setup {#dronecan_wiring} The diagram below shows how to connect the sensor to the Pixhawk 4 CAN bus. diff --git a/docs/en/sensor/sfxx_lidar.md b/docs/en/sensor/sfxx_lidar.md index e82a992c124a..57ad1748266a 100644 --- a/docs/en/sensor/sfxx_lidar.md +++ b/docs/en/sensor/sfxx_lidar.md @@ -19,13 +19,13 @@ The following models are supported by PX4, and can be connected to either the I2 The following models are supported by PX4 but are no longer available from the manufacturer. -| Model | Range | Bus | | -| -------------------------------------------------------------------------------------------------- | ----- | ------------- | --------------------------------------------------------------- | -| [SF02](http://documents.lightware.co.za/SF02%20-%20Laser%20Rangefinder%20Manual%20-%20Rev%208.pdf) | 50 | Serial | | -| [SF10/A](http://documents.lightware.co.za/SF10%20-%20Laser%20Altimeter%20Manual%20-%20Rev%206.pdf) | 25 | Serial or I2C | | -| [SF10/B](http://documents.lightware.co.za/SF10%20-%20Laser%20Altimeter%20Manual%20-%20Rev%206.pdf) | 50 | Serial or I2C | | -| SF10/C | 100m | Serial or I2C | | -| LW20/B | 50 | I2C bus | Waterproofed (IP67) with servo for sense-and-avoid applications | +| Model | Range | Bus | | +| --------------------------------------------------------------------------------------------------- | ----- | ------------- | --------------------------------------------------------------- | +| [SF02](https://documents.lightware.co.za/SF02%20-%20Laser%20Rangefinder%20Manual%20-%20Rev%208.pdf) | 50 | Serial | | +| [SF10/A](https://documents.lightware.co.za/SF10%20-%20Laser%20Altimeter%20Manual%20-%20Rev%206.pdf) | 25 | Serial or I2C | | +| [SF10/B](https://documents.lightware.co.za/SF10%20-%20Laser%20Altimeter%20Manual%20-%20Rev%206.pdf) | 50 | Serial or I2C | | +| SF10/C | 100m | Serial or I2C | | +| LW20/B | 50 | I2C bus | Waterproofed (IP67) with servo for sense-and-avoid applications | ::: diff --git a/docs/en/sim_flightgear/index.md b/docs/en/sim_flightgear/index.md index be005b56a8d1..040ea8a9182c 100644 --- a/docs/en/sim_flightgear/index.md +++ b/docs/en/sim_flightgear/index.md @@ -7,8 +7,8 @@ It may or may not work with current versions of PX4. See [Toolchain Installation](../dev_setup/dev_env.md) for information about the environments and tools supported by the core development team. ::: -[FlightGear](https://www.flightgear.org/) is a flight simulator with powerful [FDM engines](http://wiki.flightgear.org/Flight_Dynamics_Model). -This allows FlightGear to simulate rotorcrafts under various meteorological conditions (which is why the bridge was originally developed by [ThunderFly s.r.o.](https://www.thunderfly.cz/)). +[FlightGear](https://wiki.flightgear.org/Flight_Dynamics_Model) is a flight simulator with powerful [FDM engines](https://wiki.flightgear.org/Flight_Dynamics_Model). +This allows FlightGear to simulate rotorcraft under various meteorological conditions (which is why the bridge was originally developed by [ThunderFly s.r.o.](https://www.thunderfly.cz/)). This page describes FlightGear's single-vehicle use in SITL. For information about multi-vehicle use see: [Multi-Vehicle Simulation with FlightGear](../sim_flightgear/multi_vehicle.md). @@ -189,7 +189,7 @@ Takeoff location in SITL FlightGear can be set using additional variables. Setting the variable will override the default takeoff location. The variables which can be set are as follows: `--airport`, `--runway`, and `--offset-distance`. -Other options can be found on [FlightGear wiki](http://wiki.flightgear.org/Command_line_options#Initial_Position_and_Orientation) +Other options can be found on [FlightGear wiki](https://wiki.flightgear.org/Command_line_options#Initial_Position_and_Orientation) For example: @@ -197,7 +197,7 @@ For example: FG_ARGS_EX="--airport=PHNL" make px4_sitl_nolockstep flightgear_rascal ``` -The example above starts the simulation on the [Honolulu international airport](http://wiki.flightgear.org/Suggested_airports) +The example above starts the simulation on the [Honolulu international airport](https://wiki.flightgear.org/Suggested_airports) ### Using a Joystick diff --git a/docs/en/sim_flightgear/vehicles.md b/docs/en/sim_flightgear/vehicles.md index 5b8f9969594a..119d5512912b 100644 --- a/docs/en/sim_flightgear/vehicles.md +++ b/docs/en/sim_flightgear/vehicles.md @@ -25,7 +25,7 @@ The most suitable one for UAV development is currently the [Rascal RC plane](htt ![Rascal plane in FlightGear](../../assets/simulation/flightgear/vehicles/rascal110.jpg) -The variants differ mainly by the [FDM](http://wiki.flightgear.org/Flight_Dynamics_Model) model. +The variants differ mainly by the [FDM](https://wiki.flightgear.org/Flight_Dynamics_Model) model. All variants have a common feature selection table that can be activated by pressing the `=` key on the computer keyboard. There is a pop-up table that could be used for advanced features activation. @@ -119,7 +119,7 @@ The file content meaning is as follows: - `FgModel` - a precise case sensitive name of the FlightGear model corresponding to "XXXX-set.xml" in the model directory (where XXXX is the model name). - `Url` is optional and it is not currently used. It is intended for future use to auto-download the models from web -- `Controls` - the most important part of the process of adding a vehicle. This section contains the mapping between the PX4 mixer file and [FlightGear property tree](http://wiki.flightgear.org/Property_tree). +- `Controls` - the most important part of the process of adding a vehicle. This section contains the mapping between the PX4 mixer file and [FlightGear property tree](https://wiki.flightgear.org/Property_tree). - The first number in a list selects a PX4 mixer output. - Path string is a FlightGear variable location in the property tree. - The last number in a list is a multiplier, allowing inversion or scaling of mixer input. diff --git a/docs/en/sim_gazebo_classic/index.md b/docs/en/sim_gazebo_classic/index.md index 1a92d3defc32..2f6bde0bb67e 100644 --- a/docs/en/sim_gazebo_classic/index.md +++ b/docs/en/sim_gazebo_classic/index.md @@ -46,8 +46,6 @@ Note that `aptitude` is needed because it can resolve dependency conflicts (by r ::: tip You could also modify the installation script to install Gazebo Classic on Ubuntu 22.04 before it is run for the first time. - -Additional installation instructions can be found on [gazebosim.org](http://gazebosim.org/tutorials?cat=guided_b&tut=guided_b1). ::: ## Running the Simulation @@ -120,7 +118,7 @@ INFO [simulator] Waiting for simulator to connect on TCP port 4560 Gazebo multi-robot simulator, version 9.0.0 Copyright (C) 2012 Open Source Robotics Foundation. Released under the Apache 2 License. -http://gazebosim.org +https://gazebosim.org/home ... INFO [ecl/EKF] 5188000: commencing GPS fusion ``` diff --git a/docs/en/sim_gazebo_classic/multi_vehicle_simulation.md b/docs/en/sim_gazebo_classic/multi_vehicle_simulation.md index 0e90407120f6..28c8bff362f6 100644 --- a/docs/en/sim_gazebo_classic/multi_vehicle_simulation.md +++ b/docs/en/sim_gazebo_classic/multi_vehicle_simulation.md @@ -102,7 +102,7 @@ You can then control the vehicles with _QGroundControl_ and MAVROS in a similar ### Required -- Current [PX4 ROS/Gazebo development environment](../ros/mavros_installation.md) (which includes the [MAVROS package](http://wiki.ros.org/mavros)). +- Current [PX4 ROS/Gazebo development environment](../ros/mavros_installation.md) (which includes the [MAVROS package](https://wiki.ros.org/mavros)). - a clone of latest [PX4/PX4-Autopilot](https://github.com/PX4/PX4-Autopilot) ### Build and Test @@ -182,7 +182,6 @@ The launch file `multi_uav_mavros_sitl.launch`does the following, ``` - for each vehicle, - - creates urdf model from xacro, loads gazebo classic model and runs PX4 SITL app instance ```xml @@ -225,7 +224,6 @@ To add a third iris to this simulation there are two main components to consider - select a different port for `mavlink_udp_port` arg for communication with Gazebo Classic - selects ports for MAVROS communication by modifying both port numbers in the `fcu_url` arg - create a startup file, and change the file as follows: - - make a copy of an existing iris rcS startup file (`iris_1` or `iris_2`) and rename it `iris_3` - `MAV_SYS_ID` value to `3` - `SITL_UDP_PRT` value to match that of the `mavlink_udp_port` launch file arg @@ -264,7 +262,6 @@ This method is similar to using the xacro except that the SITL/Gazebo Classic po To add a new vehicle, you need to make sure the model can be found (in order to spawn it in Gazebo Classic), and PX4 needs to have an appropriate corresponding startup script. 1. You can choose to do either of: - - modify the **single_vehicle_spawn_sdf.launch** file to point to the location of your model by changing the line below to point to your model: ```sh @@ -286,5 +283,5 @@ To add a new vehicle, you need to make sure the model can be found (in order to ## Additional Resources - See [Simulation](../simulation/index.md) for a description of the UDP port configuration. -- See [URDF in Gazebo](http://wiki.ros.org/urdf/Tutorials/Using%20a%20URDF%20in%20Gazebo) for more information about spawning the model with xacro. +- See [URDF in Gazebo](https://wiki.ros.org/urdf/Tutorials/Using%20a%20URDF%20in%20Gazebo) for more information about spawning the model with xacro. - See [RotorS](https://github.com/ethz-asl/rotors_simulator/tree/master/rotors_description/urdf) for more xacro models. diff --git a/docs/en/sim_gazebo_classic/octomap.md b/docs/en/sim_gazebo_classic/octomap.md index ac7c48fe9de0..1efb7cd4fffb 100644 --- a/docs/en/sim_gazebo_classic/octomap.md +++ b/docs/en/sim_gazebo_classic/octomap.md @@ -1,6 +1,6 @@ # OctoMap 3D Models with ROS/Gazebo Classic -The [OctoMap library](http://octomap.github.io/) is an open source library for generating volumetric 3D environment models from sensor data. +The [OctoMap library](https://octomap.github.io/) is an open source library for generating volumetric 3D environment models from sensor data. This model data can then be used by a drone for navigation and obstacle avoidance. This guide covers how to use _OctoMap_ with the [Gazebo Classic](../sim_gazebo_classic/index.md) [Rotors Simulator](https://github.com/ethz-asl/rotors_simulator/wiki/RotorS-Simulator) and ROS. diff --git a/docs/en/sim_jsbsim/index.md b/docs/en/sim_jsbsim/index.md index 16b65182a9f4..c5d23520071f 100644 --- a/docs/en/sim_jsbsim/index.md +++ b/docs/en/sim_jsbsim/index.md @@ -7,7 +7,7 @@ It may or may not work with current versions of PX4. See [Toolchain Installation](../dev_setup/dev_env.md) for information about the environments and tools supported by the core development team. ::: -[JSBSim](http://jsbsim.sourceforge.net/index.html) is a open source flight simulator ("flight dynamics model (FDM)") that runs on Microsoft Windows, Apple Macintosh, Linux, IRIX, Cygwin (Unix on Windows), etc. +[JSBSim](https://jsbsim.sourceforge.net/index.html) is a open source flight simulator ("flight dynamics model (FDM)") that runs on Microsoft Windows, Apple Macintosh, Linux, IRIX, Cygwin (Unix on Windows), etc. Its features include: fully configurable aerodynamics and a propulsion system that can model complex flight dynamics of an aircraft. Rotational earth effects are also modeled into the dynamics. diff --git a/docs/en/telemetry/ark_microhard_serial.md b/docs/en/telemetry/ark_microhard_serial.md index 9682304104f4..e07acbd8daf1 100644 --- a/docs/en/telemetry/ark_microhard_serial.md +++ b/docs/en/telemetry/ark_microhard_serial.md @@ -1,6 +1,6 @@ # ARK Electron Microhard Serial Telemetry Radios -_ARK Electron Microhard Serial Telemetry Radios_ integrate the [Microhard Pico Serial](http://microhardcorp.com/P900.php) P900 RF module. +_ARK Electron Microhard Serial Telemetry Radios_ integrate the [Microhard Pico Serial](https://microhardcorp.com/P900.php) P900 RF module. This can be used to enable MAVLink communication between a radio on a vehicle and a GCS. Microhard Pico Serial radios are (up to) 1 Watt output radios that support point to point, point to multi-point, and mesh modes. diff --git a/docs/en/telemetry/crsf_telemetry.md b/docs/en/telemetry/crsf_telemetry.md index 98f1e4507eaa..cbcd770d7ff7 100644 --- a/docs/en/telemetry/crsf_telemetry.md +++ b/docs/en/telemetry/crsf_telemetry.md @@ -92,7 +92,6 @@ The steps are: ``` 1. In the PX4 board config tool: - - Disable the default `rc_input` module 1. Navigate to the `drivers` submenu, then scroll down to highlight `rc_input`. 1. Use the enter key to remove the `*` from `rc_input` checkbox. @@ -163,7 +162,7 @@ Transmitter modules: Receivers: -- [TBS Crossfire Nano RX](http://team-blacksheep.com/products/prod:crossfire_nano_rx) - designed for small quadcopters. +- [TBS Crossfire Nano RX](https://www.team-blacksheep.com/products/prod:crossfire_nano_rx) - designed for small quadcopters. ## ExpressLRS Radio Systems @@ -176,7 +175,7 @@ Transmitter modules: Receivers: -- [ExpressLRS Matek Diversity RX](http://www.mateksys.com/?portfolio=elrs-r24). +- [ExpressLRS Matek Diversity RX](https://www.mateksys.com/?portfolio=elrs-r24). ::: info This is used in the [Reptile Dragon 2 Build Log](../frames_plane/reptile_dragon_2.md). diff --git a/docs/en/telemetry/esp8266_wifi_module.md b/docs/en/telemetry/esp8266_wifi_module.md index af84bf78d266..cad34d720b8c 100644 --- a/docs/en/telemetry/esp8266_wifi_module.md +++ b/docs/en/telemetry/esp8266_wifi_module.md @@ -28,7 +28,7 @@ Modules that accept 5.0V supply: A plug and play ESP8266 module. The Kahuna comes with a cable to connect directly to the Pixhawk-standard `TELEM1` or `TELEM2` ports. - It is pre-flashed with the latest firmware, and has a u.fl connector for an external antenna. + It is pre-flashed with the latest firmware, and has a `u.fl` connector for an external antenna. At most you may need to set the baud rate parameter, which for `TELEM1` is `SER_TEL1_BAUD = 57600 (57600 8N1)`. The [User Guide](https://docs.google.com/document/d/1VyOsp9_q6dIAdYdWuDFcWoqqrNy_vbFMANubZA3Uz5g/edit?pli=1&tab=t.0) include WiFi setup and other relevant information. @@ -115,13 +115,9 @@ If you have any problem connecting, see [QGC Usage Problems](https://docs.qgroun ESP8266 modules from different manufacturers may not have appropriate ESP8266 firmware pre-installed. The instructions below explain how to update radios with the correct version. -### Pre Built Binaries - -[MavLink ESP8266 Firmware V 1.2.2](http://www.grubba.com/mavesp8266/firmware-1.2.2.bin) - ### Build From Sources -The [firmware repository](https://github.com/dogmaphobic/mavesp8266) contains instructions and all the tools needed for building and flashing the ESP8266 firmware. +The [firmware repository](https://github.com/BeyondRobotix/mavesp8266) contains instructions and all the tools needed for building and flashing the ESP8266 firmware. ### Updating the Firmware OTA @@ -136,7 +132,7 @@ This is the easiest way to update firmware! ### Flashing the ESP8266 Firmware Before flashing, make sure you boot the ESP8266 in _Flash Mode_ as described below. -If you cloned the [MavESP8266](https://github.com/dogmaphobic/mavesp8266) repository, you can build and flash the firmware using the provided [PlatformIO](http://platformio.org) tools and environment. +If you cloned the [MavESP8266](https://github.com/BeyondRobotix/mavesp8266) repository, you can build and flash the firmware using the provided [PlatformIO](https://platformio.org/) tools and environment. If you downloaded the pre-built firmware above, download the [esptool](https://github.com/espressif/esptool) utility and use the command line below: ```sh diff --git a/docs/en/telemetry/holybro_microhard_p900_radio.md b/docs/en/telemetry/holybro_microhard_p900_radio.md index c6254d501607..19b9e9de0f9b 100644 --- a/docs/en/telemetry/holybro_microhard_p900_radio.md +++ b/docs/en/telemetry/holybro_microhard_p900_radio.md @@ -1,6 +1,6 @@ # Holybro Microhard P900 Radio -The [Holybro Microhard P900 Radio](https://holybro.com/products/microhard-radio) integrates the [Microhard Pico Serial](http://microhardcorp.com/P900.php) P900 RF module, which is capable of delivering high-performance wireless serial communications in robust and secure mesh, point-to-point or point-to-multipoint topologies. +The [Holybro Microhard P900 Radio](https://holybro.com/products/microhard-radio) integrates the [Microhard Pico Serial](https://microhardcorp.com/P900.php) P900 RF module, which is capable of delivering high-performance wireless serial communications in robust and secure mesh, point-to-point or point-to-multipoint topologies. It enables MAVLink communication between a radio on a vehicle and a GCS. This radio operate within the 902-928 MHz ISM frequency band, using frequency hopping spread spectrum (FHSS) technology, providing reliable wireless asynchronous data transfer between most equipment types which employ a serial interface. diff --git a/docs/en/telemetry/microhard_serial.md b/docs/en/telemetry/microhard_serial.md index 61ec2edffb47..ead3b5dcc383 100644 --- a/docs/en/telemetry/microhard_serial.md +++ b/docs/en/telemetry/microhard_serial.md @@ -1,6 +1,6 @@ # Microhard Serial Telemetry Radios -[Microhard Pico Serial Radios](http://microhardcorp.com/P900.php) integrate the [Microhard Pico Serial](http://microhardcorp.com/P900.php) P900 RF module. +[Microhard Pico Serial Radios](https://microhardcorp.com/P900.php) integrate the _Microhard Pico Serial_ P900 RF module. This is a relatively small size and low cost radio that supports modes including point to point, point to multi-point, and mesh modes. It has configurable power output and can also be configured to use forward error correction. diff --git a/docs/en/telemetry/rfd900_telemetry.md b/docs/en/telemetry/rfd900_telemetry.md index 6df0d695c632..988b2afea55f 100644 --- a/docs/en/telemetry/rfd900_telemetry.md +++ b/docs/en/telemetry/rfd900_telemetry.md @@ -1,6 +1,6 @@ # RFD900 Long-Range Telemetry -[jDrones](http://store.jDrones.com) and [RFDesign](http://rfdesign.com.au/) offer _long-range_ [SiK](../telemetry/sik_radio.md)-compatible telemetry radios. +[jDrones](http://store.jDrones.com) and [RFDesign](https://rfdesign.com.au/) offer _long-range_ [SiK](../telemetry/sik_radio.md)-compatible telemetry radios. The radios provide reliable connectivity at greater than 5km ranges with normal antennas (and have been reported to achieve much greater ranges). ![jDrones Long Range Telemetry](../../assets/hardware/telemetry/jdrones_long_range_uav_telemetry_rf900set02_2.jpg) @@ -10,7 +10,8 @@ _jDrones_ have productized _RFDesign_ modems (added a casing with power manageme The first such modem was the _RFD900_, but both _RFDesign_ and _jDrones_ have since iterated to new versions. ::: -The _jDrones_ radios have a JST-GH connector, and come with cables for: _JST-GH to JST-GH_ and _JST-GH to DF-13_. They can therefore be used in a "plug-n-play" way with most [Pixhawk Series](../flight_controller/pixhawk_series.md) controllers (you might have to change/use an appropriate connector for some "non-standard" boards). +The _jDrones_ radios have a JST-GH connector, and come with cables for: _JST-GH to JST-GH_ and _JST-GH to DF-13_. +They can therefore be used in a "plug-n-play" way with most [Pixhawk Series](../flight_controller/pixhawk_series.md) controllers (you might have to change/use an appropriate connector for some "non-standard" boards). There are a number of versions available: diff --git a/docs/en/test_and_ci/docker.md b/docs/en/test_and_ci/docker.md index ac66c9025504..62816ccc872b 100644 --- a/docs/en/test_and_ci/docker.md +++ b/docs/en/test_and_ci/docker.md @@ -35,15 +35,13 @@ sudo usermod -aG docker $USER # Log in/out again before using docker! ``` - +## Container Hierarchy {#px4_containers} -## Container Hierarchy - -The available containers are on [Github here](https://github.com/PX4/PX4-containers/tree/master?tab=readme-ov-file#container-hierarchy). +The available containers are on [GitHub here](https://github.com/PX4/PX4-containers/tree/master?tab=readme-ov-file#container-hierarchy). These allow testing of various build targets and configurations (the included tools can be inferred from their names). The containers are hierarchical, such that containers have the functionality of their parents. -For example, the partial hierarchy below shows that the docker container with nuttx build tools (`px4-dev-nuttx-focal`) does not include ROS 2, while the simulation containers do: +For example, the partial hierarchy below shows that the docker container with NuttX build tools (`px4-dev-nuttx-focal`) does not include ROS 2, while the simulation containers do: ```plain - px4io/px4-dev-base-focal @@ -58,7 +56,7 @@ For example, the partial hierarchy below shows that the docker container with nu The most recent version can be accessed using the `latest` tag: `px4io/px4-dev-nuttx-focal:latest` (available tags are listed for each container on _hub.docker.com_. -For example, the `px4io/px4-dev-nuttx-focal` tags can be found [here](https://hub.docker.com/r/px4io/px4-dev-nuttx-focal/tags?page=1&ordering=last_updated)). +For example, the `px4io/px4-dev-nuttx-focal` tags can be found on [hub.docker.com here](https://hub.docker.com/r/px4io/px4-dev-nuttx-focal/tags?page=1&ordering=last_updated)). :::tip Typically you should use a recent container, but not necessarily the `latest` (as this changes too often). @@ -97,9 +95,7 @@ Or to start a bash session using the NuttX toolchain: The script is easy because you don't need to know anything much about _Docker_ or think about what container to use. However it is not particularly robust! The manual approach discussed in the [section below](#manual_start) is more flexible and should be used if you have any problems with the script. ::: - - -### Calling Docker Manually +### Calling Docker Manually {#manual_start} The syntax of a typical command is shown below. This runs a Docker container that has support for X forwarding (makes the simulation GUI available from inside the container). @@ -164,7 +160,8 @@ make px4_sitl_default gazebo-classic ### Re-enter the Container -The `docker run` command can only be used to create a new container. To get back into this container (which will retain your changes) simply do: +The `docker run` command can only be used to create a new container. +To get back into this container (which will retain your changes) simply do: ```sh # start the container @@ -193,9 +190,14 @@ docker rm 45eeb98f1dd9 ### QGroundControl -When running a simulation instance e.g. SITL inside the docker container and controlling it via _QGroundControl_ from the host, the communication link has to be set up manually. The autoconnect feature of _QGroundControl_ does not work here. +When running a simulation instance e.g. SITL inside the docker container and controlling it via _QGroundControl_ from the host, the communication link has to be set up manually. +The autoconnect feature of _QGroundControl_ does not work here. -In _QGroundControl_, navigate to [Settings](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/settings_view/settings_view.html) and select Comm Links. Create a new link that uses the UDP protocol. The port depends on the used [configuration](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d-posix/rcS) e.g. port 14570 for the SITL config. The IP address is the one of your docker container, usually 172.17.0.1/16 when using the default network. The IP address of the docker container can be found with the following command (assuming the container name is `mycontainer`): +In _QGroundControl_, navigate to [Settings](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/settings_view/settings_view.html) and select Comm Links. +Create a new link that uses the UDP protocol. +The port depends on the used [configuration](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d-posix/rcS) e.g. port 14570 for the SITL config. +The IP address is the one of your docker container, usually 172.17.0.1/16 when using the default network. +The IP address of the docker container can be found with the following command (assuming the container name is `mycontainer`): ```sh $ docker inspect -f '{ {range .NetworkSettings.Networks}}{ {.IPAddress}}{ {end}}' mycontainer @@ -209,9 +211,11 @@ Spaces between double curly braces above should be not be present (they are need #### Permission Errors -The container creates files as needed with a default user - typically "root". This can lead to permission errors where the user on the host computer is not able to access files created by the container. +The container creates files as needed with a default user - typically "root". +This can lead to permission errors where the user on the host computer is not able to access files created by the container. -The example above uses the line `--env=LOCAL_USER_ID="$(id -u)"` to create a user in the container with the same UID as the user on the host. This ensures that all files created within the container will be accessible on the host. +The example above uses the line `--env=LOCAL_USER_ID="$(id -u)"` to create a user in the container with the same UID as the user on the host. +This ensures that all files created within the container will be accessible on the host. #### Graphics Driver Issues @@ -221,17 +225,15 @@ It's possible that running Gazebo Classic will result in a similar error message libGL error: failed to load driver: swrast ``` -In that case the native graphics driver for your host system must be installed. Download the right driver and install it inside the container. For Nvidia drivers the following command should be used (otherwise the installer will see the loaded modules from the host and refuse to proceed): +In that case the native graphics driver for your host system must be installed. +Download the right driver and install it inside the container. +For Nvidia drivers the following command should be used (otherwise the installer will see the loaded modules from the host and refuse to proceed): ```sh ./NVIDIA-DRIVER.run -a -N --ui=none --no-kernel-module ``` -More information on this can be found [here](http://gernotklingler.com/blog/howto-get-hardware-accelerated-opengl-support-docker/). - - - -## Virtual Machine Support +## Virtual Machine Support {#virtual_machine} Any recent Linux distribution should work. diff --git a/docs/en/test_and_ci/integration_testing_mavsdk.md b/docs/en/test_and_ci/integration_testing_mavsdk.md index 524d07f37367..1e2bea35d4cf 100644 --- a/docs/en/test_and_ci/integration_testing_mavsdk.md +++ b/docs/en/test_and_ci/integration_testing_mavsdk.md @@ -162,4 +162,4 @@ About to run 39 test cases for 3 selected models (1 iteration): Terms used: - "model": This is the selected Gazebo model, e.g. `iris`. -- "test case": This is a [catch2 test case](https://github.com/catchorg/Catch2/blob/master/docs/test-cases-and-sections.md). +- "test case": This is a [catch2 test case](https://github.com/catchorg/Catch2/blob/devel/docs/test-cases-and-sections.md). diff --git a/docs/en/test_and_ci/integration_testing_ros1_mavros.md b/docs/en/test_and_ci/integration_testing_ros1_mavros.md index d2b8dfa92bb4..591413058a03 100644 --- a/docs/en/test_and_ci/integration_testing_ros1_mavros.md +++ b/docs/en/test_and_ci/integration_testing_ros1_mavros.md @@ -58,7 +58,7 @@ The **.test** files launch the corresponding Python tests defined in `integratio This section explains how to write a new python test using ROS 1/MAVROS, test it, and add it to the PX4 test suite. We recommend you review the existing tests as examples/inspiration ([integrationtests/python_src/px4_it/mavros/](https://github.com/PX4/PX4-Autopilot/tree/main/integrationtests/python_src/px4_it/mavros)). -The official ROS documentation also contains information on how to use [unittest](http://wiki.ros.org/unittest) (on which this test suite is based). +The official ROS documentation also contains information on how to use [unittest](https://wiki.ros.org/unittest) (on which this test suite is based). To write a new test: @@ -116,33 +116,30 @@ To write a new test: ``` 1. Run the new test only + - Start the simulator: - - Start the simulator: + ```sh + cd + source Tools/simulation/gazebo/setup_gazebo.bash + roslaunch launch/mavros_posix_sitl.launch + ``` - ```sh - cd - source Tools/simulation/gazebo/setup_gazebo.bash - roslaunch launch/mavros_posix_sitl.launch - ``` + - Run test (in a new shell): - - Run test (in a new shell): - - ```sh - cd - source Tools/simulation/gazebo/setup_gazebo.bash - rosrun px4 mavros_new_test.py - ``` + ```sh + cd + source Tools/simulation/gazebo/setup_gazebo.bash + rosrun px4 mavros_new_test.py + ``` 1. Add new test node to a launch file - - - In `test/` create a new `.test` ROS launch file. - - Call the test file using one of the base scripts _rostest_px4_run.sh_ or _rostest_avoidance_run.sh_ + - In `test/` create a new `.test` ROS launch file. + - Call the test file using one of the base scripts _rostest_px4_run.sh_ or _rostest_avoidance_run.sh_ 1. (Optional) Create a new target in the Makefile - - - Open the Makefile - - Search the _Testing_ section - - Add a new target name and call the test + - Open the Makefile + - Search the _Testing_ section + - Add a new target name and call the test For example: diff --git a/docs/en/tutorials/motion-capture.md b/docs/en/tutorials/motion-capture.md index 512e84bcdee4..a64292172648 100644 --- a/docs/en/tutorials/motion-capture.md +++ b/docs/en/tutorials/motion-capture.md @@ -44,7 +44,7 @@ See [Switching State Estimators](../advanced/switching_state_estimators.md) for ### EKF2 The ROS topic for motion cap `mocap_pose_estimate` for mocap systems and `vision_pose_estimate` for vision. -Check [mavros_extras](http://wiki.ros.org/mavros_extras) for further info. +Check [mavros_extras](https://wiki.ros.org/mavros_extras) for further info. ## Testing