Docs are now in user guide and main (#19977)

* Fix links to docs in source to point to docs on main not master

* More docs and scripts that need to point to main
This commit is contained in:
Hamish Willee 2022-08-01 11:39:39 +10:00 committed by GitHub
parent c566fb414b
commit 30e2490d5b
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
34 changed files with 45 additions and 45 deletions

View File

@ -20,7 +20,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/master/en/getting_started/flight_reporting.html)).
- Download the flight log file from the vehicle ([tutorial](https://docs.px4.io/main/en/getting_started/flight_reporting.html)).
- Upload the log to the [PX4 Flight Review](http://logs.px4.io/)
- Share the link to the log (Copy and paste the URL of the log)

View File

@ -8,7 +8,7 @@ First [fork and clone](https://help.github.com/articles/fork-a-repo) the project
### Create a feature branch
*Always* branch off master for new features.
*Always* branch off main for new features.
```
git checkout -b mydescriptivebranchname
@ -16,7 +16,7 @@ git checkout -b mydescriptivebranchname
### Edit and build the code
The [developer guide](http://dev.px4.io/) explains how to set up the development environment on Mac OS, Linux or Windows. Please take note of our [coding style](https://dev.px4.io/master/en/contribute/code.html) when editing files.
The [developer guide](https://docs.px4.io/main/en/development/development.html) explains how to set up the development environment on Mac OS, Linux or Windows. Please take note of our [coding style](https://docs.px4.io/main/en/contribute/code.html) when editing files.
### Commit your changes

18
Jenkinsfile vendored
View File

@ -204,15 +204,15 @@ pipeline {
unstash 'msg_documentation'
unstash 'uorb_graph'
withCredentials([usernamePassword(credentialsId: 'px4buildbot_github_personal_token', passwordVariable: 'GIT_PASS', usernameVariable: 'GIT_USER')]) {
sh('git clone https://${GIT_USER}:${GIT_PASS}@github.com/PX4/px4_user_guide.git')
sh('cp airframes.md px4_user_guide/en/airframes/airframe_reference.md')
sh('cp parameters.md px4_user_guide/en/advanced_config/parameter_reference.md')
sh('cp -R modules/*.md px4_user_guide/en/modules/')
sh('cp -R graph_*.json px4_user_guide/.vuepress/public/en/middleware/')
sh('cp -R msg_docs/*.md px4_user_guide/en/msg_docs/')
sh('cd px4_user_guide; git status; git add .; git commit -a -m "Update PX4 Firmware metadata `date`" || true')
sh('cd px4_user_guide; git push origin master || true')
sh('rm -rf px4_user_guide')
sh('git clone https://${GIT_USER}:${GIT_PASS}@github.com/PX4/PX4-user_guide.git')
sh('cp airframes.md PX4-user_guide/en/airframes/airframe_reference.md')
sh('cp parameters.md PX4-user_guide/en/advanced_config/parameter_reference.md')
sh('cp -R modules/*.md PX4-user_guide/en/modules/')
sh('cp -R graph_*.json PX4-user_guide/.vuepress/public/en/middleware/')
sh('cp -R msg_docs/*.md PX4-user_guide/en/msg_docs/')
sh('cd PX4-user_guide; git status; git add .; git commit -a -m "Update PX4 Firmware metadata `date`" || true')
sh('cd PX4-user_guide; git push origin main || true')
sh('rm -rf PX4-user_guide')
}
}
when {

View File

@ -10,8 +10,8 @@ This repository holds the [PX4](http://px4.io) flight control solution for drone
PX4 is highly portable, OS-independent and supports Linux, NuttX and MacOS out of the box.
* Official Website: http://px4.io (License: BSD 3-clause, [LICENSE](https://github.com/PX4/PX4-Autopilot/blob/master/LICENSE))
* [Supported airframes](https://docs.px4.io/main/en/airframes/airframe_reference.html) ([portfolio](http://px4.io/#airframes)):
* Official Website: http://px4.io (License: BSD 3-clause, [LICENSE](https://github.com/PX4/PX4-Autopilot/blob/main/LICENSE))
* [Supported airframes](https://docs.px4.io/main/en/airframes/airframe_reference.html) ([portfolio](https://px4.io/ecosystem/commercial-systems/)):
* [Multicopters](https://docs.px4.io/main/en/frames_multicopter/)
* [Fixed wing](https://docs.px4.io/main/en/frames_plane/)
* [VTOL](https://docs.px4.io/main/en/frames_vtol/)

View File

@ -2,7 +2,7 @@
#
# @name Phantom FPV Flying Wing
#
# @url https://docs.px4.io/master/en/frames_plane/wing_wing_z84.html
# @url https://docs.px4.io/main/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/master/en/frames_plane/wing_wing_z84.html
# @url https://docs.px4.io/main/en/frames_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/master/en/frames_multicopter/spedix_s250_pixracer.html
# @url https://docs.px4.io/main/en/frames_multicopter/spedix_s250_pixracer.html
#
# @type Quadrotor asymmetric
# @class Copter

View File

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

View File

@ -330,7 +330,7 @@ def get_mixers(yaml_config, output_functions, verbose):
option = select_param + '==' + str(type_index)
mixer_config = {
'option': option,
'help-url': 'https://docs.px4.io/master/en/config/actuators.html',
'help-url': 'https://docs.px4.io/main/en/config/actuators.html',
}
for optional in ['type', 'title']:
if optional in current_type:

View File

@ -8,7 +8,7 @@ class MarkdownTablesOutput():
result = """# Airframes Reference
:::note
**This list is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/master/Tools/px4airframes/markdownout.py) from the source code** using the build command: `make airframe_metadata`.
**This list is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/px4airframes/markdownout.py) from the source code** using the build command: `make airframe_metadata`.
:::
This page lists all supported airframes and types including the motor assignment and numbering.

View File

@ -69,7 +69,7 @@ The generated files will be written to the `modules` directory.
result = ''
for module in module_list:
result += "## %s\n" % module.name()
result += "Source: [%s](https://github.com/PX4/PX4-Autopilot/tree/master/src/%s)\n\n" % (module.scope(), module.scope())
result += "Source: [%s](https://github.com/PX4/PX4-Autopilot/tree/main/src/%s)\n\n" % (module.scope(), module.scope())
doc = module.documentation()
if len(doc) > 0:
result += "%s\n" % doc

View File

@ -12,7 +12,7 @@ class ModuleDocumentation(object):
"""
# If you add categories or subcategories, they also need to be added to the
# TOC in https://github.com/PX4/Devguide/blob/master/en/SUMMARY.md
# TOC in https://github.com/PX4/PX4-user_guide/blob/main/en/SUMMARY.md
valid_categories = ['driver', 'estimator', 'controller', 'system',
'communication', 'command', 'template', 'simulation', 'autotune']
valid_subcategories = ['', 'distance_sensor', 'imu', 'airspeed_sensor',

View File

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

View File

@ -694,7 +694,7 @@ class OutputJSON(object):
node['type'] = 'topic'
node['color'] = topic_colors[topic]
# url is opened when double-clicking on the node
node['url'] = 'https://github.com/PX4/PX4-Autopilot/blob/master/msg/'+topic_filename(topic)+'.msg'
node['url'] = 'https://github.com/PX4/PX4-Autopilot/blob/main/msg/'+topic_filename(topic)+'.msg'
nodes.append(node)
data['nodes'] = nodes

View File

@ -310,7 +310,7 @@ if(EXISTS ${BOARD_DEFCONFIG})
endif()
if (NO_HELP)
add_definitions(-DCONSTRAINED_FLASH_NO_HELP="https://docs.px4.io/master/en/modules/modules_main.html")
add_definitions(-DCONSTRAINED_FLASH_NO_HELP="https://docs.px4.io/main/en/modules/modules_main.html")
endif()
if(CONSTRAINED_MEMORY)

View File

@ -38,7 +38,7 @@ if __name__ == "__main__":
print("{:} -> {:}".format(msg_filename, output_file))
#Format msg url
msg_url="[source file](https://github.com/PX4/PX4-Autopilot/blob/master/msg/%s)" % msg_file
msg_url="[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/%s)" % msg_file
msg_description = ""
summary_description = ""
@ -90,7 +90,7 @@ if __name__ == "__main__":
readme_text="""# uORB Message Reference
:::note
This list is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/master/msg/tools/generate_msg_docs.py) from the source code.
This list is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main/msg/tools/generate_msg_docs.py) from the source code.
:::
This topic lists the UORB messages available in PX4 (some of which may be may be shared by the [PX4-ROS 2 Bridge](../ros/ros2_comm.md)).

View File

@ -33,7 +33,7 @@
if("${CMAKE_CXX_COMPILER_ID}" MATCHES "GNU")
if(CMAKE_CXX_COMPILER_VERSION VERSION_LESS_EQUAL 7)
message(FATAL_ERROR "GCC 7 or older no longer supported. https://docs.px4.io/master/en/dev_setup/dev_env.html")
message(FATAL_ERROR "GCC 7 or older no longer supported. https://docs.px4.io/main/en/dev_setup/dev_env.html")
endif()
endif()

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/master/en/sensor/leddar_one.html
Setup/usage information: https://docs.px4.io/main/en/sensor/leddar_one.html
### Examples

View File

@ -417,7 +417,7 @@ void LightwareLaser::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/master/en/sensor/sfxx_lidar.html
Setup/usage information: https://docs.px4.io/main/en/sensor/sfxx_lidar.html
)DESCR_STR");
PRINT_MODULE_USAGE_NAME("lightware_laser_i2c", "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/master/en/sensor/sfxx_lidar.html
Setup/usage information: https://docs.px4.io/main/en/sensor/sfxx_lidar.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/master/en/sensor/lidar_lite.html
Setup/usage information: https://docs.px4.io/main/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/master/en/sensor/lidar_lite.html
Setup/usage information: https://docs.px4.io/main/en/sensor/lidar_lite.html
)DESCR_STR");
PRINT_MODULE_USAGE_NAME("ll40ls", "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/master/en/sensor/rangefinders.html#teraranger-rangefinders
Setup/usage information: https://docs.px4.io/main/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/master/en/sensor/tfmini.html
Setup/usage information: https://docs.px4.io/main/en/sensor/tfmini.html
### Examples

View File

@ -428,7 +428,7 @@ Serial bus driver for the ThoneFlow-3901U optical flow sensor.
Most boards are configured to enable/start the driver on a specified UART using the SENS_TFLOW_CFG parameter.
Setup/usage information: https://docs.px4.io/master/en/sensor/pmw3901.html#thone-thoneflow-3901u
Setup/usage information: https://docs.px4.io/main/en/sensor/pmw3901.html#thone-thoneflow-3901u
### Examples

View File

@ -79,7 +79,7 @@ if validate:
print(" v1.9.0-beta1")
print(" v1.9.0-1.0.0")
print(" v1.9.0-1.0.0-alpha2")
print("See also https://dev.px4.io/master/en/setup/building_px4.html#firmware_version")
print("See also https://docs.px4.io/main/en/dev_setup/building_px4.html#building-for-nuttx")
print("")
sys.exit(1)

View File

@ -48,7 +48,7 @@ bool PreFlightCheck::airframeCheck(orb_advert_t *mavlink_log_pub, const vehicle_
// We no longer support VTOL on fmu-v2, so we need to warn existing users.
if (status.is_vtol) {
mavlink_log_critical(mavlink_log_pub,
"VTOL is not supported with fmu-v2, see docs.px4.io/master/en/config/firmware.html#bootloader");
"VTOL is not supported with fmu-v2, see docs.px4.io/main/en/config/firmware.html#bootloader");
success = false;
}

View File

@ -2249,7 +2249,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/master/en/advanced_config/tuning_the_ecl_ekf.html) page.
The documentation can be found on the [ECL/EKF Overview & Tuning](https://docs.px4.io/main/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

@ -539,7 +539,7 @@ static void usage()
Mount/gimbal 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://docs.px4.io/master/en/advanced/gimbal_control.html) page.
Documentation how to use it is on the [gimbal_control](https://docs.px4.io/main/en/advanced/gimbal_control.html) page.
### Examples
Test the output by setting a angles (all omitted axes are set to 0):

View File

@ -1228,7 +1228,7 @@ MavlinkReceiver::handle_message_set_actuator_control_target(mavlink_message_t *m
#if defined(ENABLE_LOCKSTEP_SCHEDULER)
PX4_ERR("SET_ACTUATOR_CONTROL_TARGET not supported with lockstep enabled");
PX4_ERR("Please disable lockstep for actuator offboard control:");
PX4_ERR("https://dev.px4.io/master/en/simulation/#disable-lockstep-simulation");
PX4_ERR("https://docs.px4.io/main/en/simulation/#disable-lockstep-simulation");
return;
#endif

View File

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

View File

@ -1171,7 +1171,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/master/en/debug/system_wide_replay.html)
The replay procedure is documented on the [System-wide Replay](https://docs.px4.io/main/en/debug/system_wide_replay.html)
page.
)DESCR_STR");

View File

@ -244,7 +244,7 @@ Tunes are used to provide audible notification and warnings (e.g. when the syste
The tool requires that a driver is running that can handle the tune_control uorb topic.
Information about the tune format and predefined system tunes can be found here:
https://github.com/PX4/Firmware/blob/master/src/lib/tunes/tune_definition.desc
https://github.com/PX4/PX4-Autopilot/blob/main/src/lib/tunes/tune_definition.desc
### Examples

View File

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