Fix up doc links to point to master branch

This commit is contained in:
Hamish Willee 2020-04-20 11:22:33 +10:00 committed by Beat Küng
parent 75054f11df
commit 8236b8da81
19 changed files with 27 additions and 27 deletions

View File

@ -19,7 +19,7 @@ A clear and concise description of what you expected to happen.
**Log Files and Screenshots**
*Always* provide a link to the flight log file:
- Download the flight log file from the vehicle ([tutorial](https://docs.px4.io/en/getting_started/flight_reporting.html)).
- Download the flight log file from the vehicle ([tutorial](https://docs.px4.io/master/en/getting_started/flight_reporting.html)).
- Share the link to a log showing the problem on [PX4 Flight Review](http://logs.px4.io/).
Add screenshots to help explain your problem.

View File

@ -9,31 +9,31 @@
This repository holds the [PX4](http://px4.io) flight control solution for drones, with the main applications located in the [src/modules](https://github.com/PX4/Firmware/tree/master/src/modules) directory. It also contains the PX4 Drone Middleware Platform, which provides drivers and middleware to run drones.
* Official Website: http://px4.io (License: BSD 3-clause, [LICENSE](https://github.com/PX4/Firmware/blob/master/LICENSE))
* [Supported airframes](https://docs.px4.io/en/airframes/airframe_reference.html) ([portfolio](http://px4.io/#airframes)):
* [Multicopters](https://docs.px4.io/en/airframes/airframe_reference.html#copter)
* [Fixed wing](https://docs.px4.io/en/airframes/airframe_reference.html#plane)
* [VTOL](https://docs.px4.io/en/airframes/airframe_reference.html#vtol)
* [Supported airframes](https://docs.px4.io/master/en/airframes/airframe_reference.html) ([portfolio](http://px4.io/#airframes)):
* [Multicopters](https://docs.px4.io/master/en/airframes/airframe_reference.html#copter)
* [Fixed wing](https://docs.px4.io/master/en/airframes/airframe_reference.html#plane)
* [VTOL](https://docs.px4.io/master/en/airframes/airframe_reference.html#vtol)
* many more experimental types (Rovers, Blimps, Boats, Submarines, Autogyros, etc)
* Releases: [Downloads](https://github.com/PX4/Firmware/releases)
## PX4 Users
The [PX4 User Guide](https://docs.px4.io/en/) explains how to assemble [supported vehicles](https://docs.px4.io/en/airframes/airframe_reference.html) and fly drones with PX4.
See the [forum and chat](https://docs.px4.io/en/#support) if you need help!
The [PX4 User Guide](https://docs.px4.io/master/en/) explains how to assemble [supported vehicles](https://docs.px4.io/master/en/airframes/airframe_reference.html) and fly drones with PX4.
See the [forum and chat](https://docs.px4.io/master/en/#support) if you need help!
## PX4 Developers
This [Developer Guide](https://dev.px4.io/) is for software developers who want to modify the flight stack and middleware (e.g. to add new flight modes), hardware integrators who want to support new flight controller boards and peripherals, and anyone who wants to get PX4 working on a new (unsupported) airframe/vehicle.
Developers should read the [Guide for Contributions](https://dev.px4.io/en/contribute/).
See the [forum and chat](https://dev.px4.io/en/#support) if you need help!
Developers should read the [Guide for Contributions](https://dev.px4.io/master/en/contribute/).
See the [forum and chat](https://dev.px4.io/master/en/#support) if you need help!
### Weekly Dev Call
The PX4 Dev Team syncs up on a [weekly dev call](https://dev.px4.io/en/contribute/#dev_call).
The PX4 Dev Team syncs up on a [weekly dev call](https://dev.px4.io/master/en/contribute/#dev_call).
> **Note** The dev call is open to all interested developers (not just the core dev team). This is a great opportunity to meet the team and contribute to the ongoing development of the platform. It includes a QA session for newcomers. All regular calls are listed in the [Dronecode calendar](https://www.dronecode.org/calendar/).

View File

@ -2,7 +2,7 @@
#
# @name Phantom FPV Flying Wing
#
# @url https://docs.px4.io/en/frames_plane/wing_wing_z84.html
# @url https://docs.px4.io/master/en/frames_plane/wing_wing_z84.html
#
# @type Flying Wing
# @class Plane

View File

@ -2,7 +2,7 @@
#
# @name Wing Wing (aka Z-84) Flying Wing
#
# @url https://docs.px4.io/en/framebuild_plane/wing_wing_z84.html
# @url https://docs.px4.io/master/en/framebuild_plane/wing_wing_z84.html
#
# @type Flying Wing
# @class Plane

View File

@ -1,7 +1,7 @@
#!/bin/sh
#
# @name Spedix S250AQ
# @url https://docs.px4.io/en/framebuild_multicopter/spedix_s250_pixracer.html
# @url https://docs.px4.io/master/en/framebuild_multicopter/spedix_s250_pixracer.html
#
# @type Quadrotor asymmetric
# @class Copter

View File

@ -2,7 +2,7 @@
#
# @name HolyBro QAV250
#
# @url https://docs.px4.io/en/frames_multicopter/holybro_qav250_pixhawk4_mini.html
# @url https://docs.px4.io/master/en/frames_multicopter/holybro_qav250_pixhawk4_mini.html
#
# @type Quadrotor x
# @class Copter

View File

@ -322,7 +322,7 @@ class uploader(object):
except NotImplementedError:
raise RuntimeError("Programing not supported for this version of silicon!\n"
"See https://docs.px4.io/en/flight_controller/silicon_errata.html")
"See https://docs.px4.io/master/en/flight_controller/silicon_errata.html")
except RuntimeError:
# timeout, no response yet
return False

View File

@ -103,7 +103,7 @@ Serial bus driver for the LeddarOne LiDAR.
Most boards are configured to enable/start the driver on a specified UART using the SENS_LEDDAR1_CFG parameter.
Setup/usage information: https://docs.px4.io/en/sensor/leddar_one.html
Setup/usage information: https://docs.px4.io/master/en/sensor/leddar_one.html
### Examples

View File

@ -57,7 +57,7 @@ I2C bus driver for LidarLite rangefinders.
The sensor/driver must be enabled using the parameter SENS_EN_LL40LS.
Setup/usage information: https://docs.px4.io/en/sensor/lidar_lite.html
Setup/usage information: https://docs.px4.io/master/en/sensor/lidar_lite.html
)DESCR_STR");
PRINT_MODULE_USAGE_NAME("ll40ls", "driver");

View File

@ -147,7 +147,7 @@ PWM driver for LidarLite rangefinders.
The sensor/driver must be enabled using the parameter SENS_EN_LL40LS.
Setup/usage information: https://docs.px4.io/en/sensor/lidar_lite.html
Setup/usage information: https://docs.px4.io/master/en/sensor/lidar_lite.html
)DESCR_STR");
PRINT_MODULE_USAGE_NAME("ll40ls", "driver");

View File

@ -104,7 +104,7 @@ Serial bus driver for the LightWare SF02/F, SF10/a, SF10/b, SF10/c, SF11/c Laser
Most boards are configured to enable/start the driver on a specified UART using the SENS_SF0X_CFG parameter.
Setup/usage information: https://docs.px4.io/en/sensor/sfxx_lidar.html
Setup/usage information: https://docs.px4.io/master/en/sensor/sfxx_lidar.html
### Examples

View File

@ -289,7 +289,7 @@ void SF1XX::print_usage()
I2C bus driver for Lightware SFxx series LIDAR rangefinders: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20.
Setup/usage information: https://docs.px4.io/en/sensor/sfxx_lidar.html
Setup/usage information: https://docs.px4.io/master/en/sensor/sfxx_lidar.html
)DESCR_STR");
PRINT_MODULE_USAGE_NAME("sf1xx", "driver");

View File

@ -47,7 +47,7 @@ I2C bus driver for TeraRanger rangefinders.
The sensor/driver must be enabled using the parameter SENS_EN_TRANGER.
Setup/usage information: https://docs.px4.io/en/sensor/rangefinders.html#teraranger-rangefinders
Setup/usage information: https://docs.px4.io/master/en/sensor/rangefinders.html#teraranger-rangefinders
)DESCR_STR");
PRINT_MODULE_USAGE_NAME("teraranger", "driver");
PRINT_MODULE_USAGE_SUBCATEGORY("distance_sensor");

View File

@ -115,7 +115,7 @@ Serial bus driver for the Benewake TFmini LiDAR.
Most boards are configured to enable/start the driver on a specified UART using the SENS_TFMINI_CFG parameter.
Setup/usage information: https://docs.px4.io/en/sensor/tfmini.html
Setup/usage information: https://docs.px4.io/master/en/sensor/tfmini.html
### Examples

View File

@ -2448,7 +2448,7 @@ int Ekf2::print_usage(const char *reason)
### Description
Attitude and position estimator using an Extended Kalman Filter. It is used for Multirotors and Fixed-Wing.
The documentation can be found on the [ECL/EKF Overview & Tuning](https://docs.px4.io/en/advanced_config/tuning_the_ecl_ekf.html) page.
The documentation can be found on the [ECL/EKF Overview & Tuning](https://docs.px4.io/master/en/advanced_config/tuning_the_ecl_ekf.html) page.
ekf2 can be started in replay mode (`-r`): in this mode it does not access the system time, but only uses the
timestamps from the sensor topics.

View File

@ -1 +1 @@
For see a complete documentation, please follow this [link](https://dev.px4.io/en/middleware/micrortps.html)
For see a complete documentation, please follow this [link](https://dev.px4.io/master/en/middleware/micrortps.html)

View File

@ -1055,7 +1055,7 @@ The module is typically used together with uORB publisher rules, to specify whic
The replay module will just publish all messages that are found in the log. It also applies the parameters from
the log.
The replay procedure is documented on the [System-wide Replay](https://dev.px4.io/en/debug/system_wide_replay.html)
The replay procedure is documented on the [System-wide Replay](https://dev.px4.io/master/en/debug/system_wide_replay.html)
page.
)DESCR_STR");

View File

@ -601,7 +601,7 @@ static void usage()
Mount (Gimbal) control driver. It maps several different input methods (eg. RC or MAVLink) to a configured
output (eg. AUX channels or MAVLink).
Documentation how to use it is on the [gimbal_control](https://dev.px4.io/en/advanced/gimbal_control.html) page.
Documentation how to use it is on the [gimbal_control](https://dev.px4.io/master/en/advanced/gimbal_control.html) page.
### Implementation
Each method is implemented in its own class, and there is a common base class for inputs and outputs.

View File

@ -250,7 +250,7 @@ int ver_main(int argc, char *argv[])
printf("\nWARNING WARNING WARNING!\n"
"Revision %c has a silicon errata:\n"
"%s"
"\nhttps://docs.px4.io/en/flight_controller/silicon_errata.html\n\n", rev, errata);
"\nhttps://docs.px4.io/master/en/flight_controller/silicon_errata.html\n\n", rev, errata);
}
}