mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-16 15:27:35 +08:00
88d623bedb
* Add vitepress tree * Update existing workflows so they dont trigger on changes in the docs path * Add nojekyll, package.json, LICENCE etc * Add crowdin docs upload/download scripts * Add docs flaw checker workflows * Used docs prefix for docs workflows * Crowdin obvious fixes * ci: docs move to self hosted runner runs on a beefy server for faster builds Signed-off-by: Ramon Roche <mrpollo@gmail.com> * ci: don't run build action for docs or ci changes Signed-off-by: Ramon Roche <mrpollo@gmail.com> * ci: update runners Signed-off-by: Ramon Roche <mrpollo@gmail.com> * Add docs/en * Add docs assets and scripts * Fix up editlinks to point to PX4 sources * Download just the translations that are supported * Add translation sources for zh, uk, ko * Update latest tranlsation and uorb graphs * update vitepress to latest --------- Signed-off-by: Ramon Roche <mrpollo@gmail.com> Co-authored-by: Ramon Roche <mrpollo@gmail.com>
144 lines
14 KiB
Markdown
144 lines
14 KiB
Markdown
# Drive Modes (Differential Rover)
|
|
|
|
Flight modes (or more accurately "Drive modes" for ground vehicles) provide autopilot support to make it easier to manually drive the vehicle or to execute autonomous missions.
|
|
|
|
This section outlines all supported drive modes for differential rovers.
|
|
|
|
For information on mapping RC control switches to specific modes see: [Basic Configuration > Flight Modes](../config/flight_mode.md).
|
|
|
|
:::warning
|
|
Selecting any other mode than those listed below will either stop the rover or can lead to undefined behaviour.
|
|
:::
|
|
|
|
## Manual Modes
|
|
|
|
Manual modes require stick inputs from the user to drive the vehicle.
|
|
|
|

|
|
|
|
The sticks provide the same "high level" control effects over direction and rate of movement in all manual modes:
|
|
|
|
- `Left stick up/down`: Drive the rover forwards/backwards (controlling speed)
|
|
- `Right stick left/right`: Rotate the rover to the left/right (controlling yaw rate).
|
|
|
|
The manual modes provide progressively increasing levels of autopilot support for maintaining a course, speed, and rate of turn, compensating for external factors such as slopes or uneven terrain.
|
|
|
|
| Mode | 특징 |
|
|
| ------------------------------ | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
|
|
| [Manual](#manual-mode) | No autopilot support. User is responsible for keeping the rover on the desired course and maintaining speed and rate of turn. |
|
|
| [Acro](#acro-mode) | + Maintains the yaw rate (This makes it slightly better at holding a straight line in uneven terrain). <br>+ Allows maximum yaw rate to be limited. |
|
|
| [Stabilized](#stabilized-mode) | + Maintans the yaw (This makes it significantly better at holding a straight line). |
|
|
| [Position](#position-mode) | + Maintains the course (Best mode for driving a straight line).<br>+ Maintains speed against disturbances, e.g. when driving up a hill.<br>+ Allows maximum speed to be limited. |
|
|
|
|
:::details
|
|
Overview mode mapping to control effect
|
|
|
|
| Mode | Forwards/backwards speed | Yaw rate | Required measurements |
|
|
| ------------------------------ | ---------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------- |
|
|
| [Manual](#manual-mode) | Directly map stick input to motor commands. | Directly map stick input to motor commands. | None. |
|
|
| [Acro](#acro-mode) | Directly map stick input to motor commands. | Stick input creates a yaw rate setpoint for the control system to regulate. | Yaw rate. |
|
|
| [Stabilized](#stabilized-mode) | Directly map stick input to motor commands. | Stick input creates a yaw rate setpoint for the control system to regulate. If this setpoint is zero (stick is centered) the control system will maintain the current yaw (heading) of the rover. | Yaw rate and yaw. |
|
|
| [Position](#position-mode) | Stick input creates a speed setpoint for the control system to regulate. | Stick input creates a yaw rate setpoint for the control system to regulate. If this setpoint is zero (stick is centered) the control system will keep the rover driving in a straight line. | Yaw rate, yaw, speed and global position (GPS). |
|
|
|
|
:::
|
|
|
|
### 수동 모드
|
|
|
|
In this mode the stick inputs are directly mapped to motor commands. The rover does not attempt to maintain a specific orientation or compensate for external factors like slopes or uneven terrain!
|
|
The user is responsible for making the necessary adjustments to the stick inputs to keep the rover on the desired course.
|
|
|
|
| Stick | Effect |
|
|
| ---------------------- | --------------------------------------------------- |
|
|
| Left stick up/down | Drive the rover forwards/backwards. |
|
|
| Right stick left/right | Yaw the rover to the left/right. |
|
|
|
|
For the configuration/tuning of this mode see [Manual mode](../config_rover/differential.md#manual-mode).
|
|
|
|
### Acro Mode
|
|
|
|
:::info
|
|
This mode requires a yaw rate measurement.
|
|
:::
|
|
|
|
In this mode the vehicle regulates its yaw rate to a setpoint (but does not stabilize heading or regulate speed).
|
|
|
|
| Stick | Effect |
|
|
| ---------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
|
|
| Left stick up/down | Drive the rover forwards/backwards. |
|
|
| Right stick left/right | Create a yaw rate setpoint for the control system to regulate. If this input is zero the control system will attempt to maintain a zero yaw rate (minimal disturbance rejection) |
|
|
|
|
For the configuration/tuning of this mode see [Acro mode](../config_rover/differential.md#acro-mode).
|
|
|
|
### Stabilized Mode
|
|
|
|
:::info
|
|
This mode requires a yaw rate and yaw estimate.
|
|
:::
|
|
|
|
In this mode the vehicle regulates its yaw rate to a setpoint and will maintain its heading if this setpoint is zero (but does not regulate speed).
|
|
Compared to [Acro mode](#acro-mode), this mode is much better at driving in a straight line as it can more effectively reject disturbances.
|
|
|
|
| Stick | Effect |
|
|
| ---------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
|
|
| Left stick up/down | Drive the rover forwards/backwards. |
|
|
| Right stick left/right | Create a yaw rate setpoint for the control system to regulate. If this input is zero the control system will maintain the current yaw. |
|
|
|
|
For the configuration/tuning of this mode see [Stabilized mode](../config_rover/differential.md#stabilized-mode).
|
|
|
|
### Position Mode
|
|
|
|
:::info
|
|
This mode requires a yaw rate, yaw, speed and global position estimate.
|
|
:::
|
|
|
|
This is the manual mode with the most autopilot support.
|
|
The vehicle regulates its yaw rate and speed to a setpoint.
|
|
If the yaw rate setpoint is zero, the controller will remember the GNSS coordinates and yaw (heading) of the vehicle and use those to construct a line that the rover will then follow (course control).
|
|
This offers the highest amount of disturbance rejection, which leads to the best straight line driving behavior.
|
|
|
|
| Stick | Effect |
|
|
| ---------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ |
|
|
| Left stick up/down | Create a speed setpoint for the control system to regulate. |
|
|
| Right stick left/right | Create a yaw rate setpoint for the control system to regulate. If this input is zero the control system will maintain the course of the rover. |
|
|
|
|
For the configuration/tuning of this mode see [Position mode](../config_rover/differential.md#position-mode).
|
|
|
|
## Auto Modes
|
|
|
|
In auto modes the autopilot takes over control of the vehicle to run missions, return to launch, or perform other autonomous navigation tasks.
|
|
For the configuration/tuning of these modes see [Auto Modes](../config_rover/differential.md#auto-modes).
|
|
|
|
### Mission Mode
|
|
|
|
_Mission mode_ is an automatic mode in which the vehicle executes a predefined autonomous [mission plan](../flying/missions.md) that has been uploaded to the flight controller.
|
|
The mission is typically created and uploaded with a Ground Control Station (GCS) application, such as [QGroundControl](https://docs.qgroundcontrol.com/master/en/).
|
|
|
|
#### Mission commands
|
|
|
|
The following commands can be used in missions at time of writing (`main`/planned for `PX4 v1.16+`):
|
|
|
|
| QGC mission item | 통신 | 설명 |
|
|
| ------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------ | ------------------------------------------------------------------------------------------------ |
|
|
| Mission start | [MAV_CMD_MISSION_START](MAV_CMD_MISSION_START) | Starts the mission. |
|
|
| Waypoint | [MAV_CMD_NAV_WAYPOINT](MAV_CMD_NAV_WAYPOINT) | Navigate to waypoint. |
|
|
| Return to launch | [MAV\_CMD\_NAV\_RETURN\_TO\_LAUNCH][MAV_CMD_NAV_RETURN_TO_LAUNCH] | Return to the launch location. |
|
|
| Delay until | [MAV_CMD_NAV_DELAY](MAV_CMD_NAV_DELAY) | The rover will stop for a specified amount of time. |
|
|
| Change speed | [MAV\_CMD\_DO\_CHANGE\_SPEED][MAV_CMD_DO_CHANGE_SPEED] | Change the speed setpoint |
|
|
| Set launch location | [MAV_CMD_DO_SET_HOME](MAV_CMD_DO_SET_HOME) | Changes launch location to specified coordinates. |
|
|
| Jump to item (all) | [MAV\_CMD\_DO\_JUMP][MAV_CMD_DO_JUMP] (and other jump commands) | Jump to specified mission item. |
|
|
| Loiter (all) | [MAV\_CMD\_NAV\_LOITER\_TIME][MAV_CMD_NAV_LOITER_TIME] (and other loiter commands) | Stop the rover for given time. Other commands stop indefinitely. |
|
|
|
|
[MAV_CMD_MISSION_START]: https://mavlink.io/en/messages/common.html#MAV_CMD_MISSION_START
|
|
[MAV_CMD_NAV_WAYPOINT]: https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_WAYPOINT
|
|
[MAV_CMD_NAV_RETURN_TO_LAUNCH]: https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_RETURN_TO_LAUNCH
|
|
[MAV_CMD_NAV_DELAY]: https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_DELAY
|
|
[MAV_CMD_DO_CHANGE_SPEED]: https://mavlink.io/en/messages/common.html#MAV_CMD_DO_CHANGE_SPEED
|
|
[MAV_CMD_DO_SET_HOME]: https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_HOME
|
|
[MAV_CMD_NAV_LOITER_TIME]: https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_LOITER_TIME
|
|
[MAV_CMD_DO_JUMP]: https://mavlink.io/en/messages/common.html#MAV_CMD_DO_JUMP
|
|
|
|
### Return Mode
|
|
|
|
This mode uses the [pure pursuit guidance logic](../config_rover/differential.md#pure-pursuit-guidance-logic) with the launch position as goal.
|
|
Return mode can be activated through the respective [mission command](#mission-commands) or through the ground station UI.
|