Compare commits

...

45 Commits
v0.25 ... v0.23

Author SHA1 Message Date
Oleg Kalachev
26c2387f5c Merge branch 'master' into recent-px4 2022-02-10 15:41:45 +03:00
Oleg Kalachev
4fbc4f63ee docs: remove unused asset 2022-02-03 07:33:56 +03:00
Oleg Kalachev
c48a945258 Merge branch 'master' into recent-px4 2022-02-03 05:05:22 +03:00
Oleg Kalachev
39763c4a40 Merge branch 'master' into recent-px4 2022-02-03 04:37:31 +03:00
Oleg Kalachev
6c43d5c230 docs: rework parameters article, make summary parameters table 2022-02-01 15:20:20 +03:00
Oleg Kalachev
265898912f clover.launch: add force_init argument
PX4 1.12.3 doesn’t init by flow without mag
force_init runs vpe_publisher to force init using vpe
2022-02-01 14:08:33 +03:00
Oleg Kalachev
d31bd75d7d docs: remove obsolete notes and simplify titles in autonomous flight article 2022-02-01 13:57:20 +03:00
Oleg Kalachev
e15ef587d7 docs: add note about possible unintended switching out of LAND mode 2022-02-01 13:47:30 +03:00
Oleg Kalachev
79903db95d Merge branch 'master' into recent-px4 2022-02-01 11:40:30 +03:00
Oleg Kalachev
14a9c0eb46 Merge branch 'master' into recent-px4 2022-02-01 11:38:17 +03:00
Oleg Kalachev
673dbb1feb docs: rename px4_parameters.md article to parameters.md 2022-02-01 11:36:52 +03:00
Oleg Kalachev
4446b22db4 Merge branch 'master' into recent-px4 2022-02-01 11:19:50 +03:00
Oleg Kalachev
281f515ba7 Merge branch 'master' into recent-px4 2022-02-01 11:05:41 +03:00
Oleg Kalachev
273e3191f1 docs: update PX4 docs links 2022-02-01 11:01:41 +03:00
Oleg Kalachev
ae08c62bf4 Merge branch 'master' into recent-px4 2022-02-01 10:54:55 +03:00
Oleg Kalachev
9f9b1d3115 docs: rephrase firmware flashing section to continue recommending COEX firmware 2022-02-01 10:54:35 +03:00
Oleg Kalachev
f3fb3e4cee Merge branch 'master' into recent-px4 2022-02-01 08:31:09 +03:00
Oleg Kalachev
80c853735d docs: reduce size of some images 2022-02-01 08:23:38 +03:00
Oleg Kalachev
9bd3c616da docs: reduce qgc-params.png file size 2022-02-01 08:19:15 +03:00
Oleg Kalachev
75209ea2f9 selfcheck.py: bring back info about non-Clover firmware 2022-02-01 07:56:47 +03:00
Oleg Kalachev
d0a0e5d50d selfcheck.py: add checking map=>body transform 2022-02-01 07:00:01 +03:00
Oleg Kalachev
afe8abcd96 Merge branch 'master' into recent-px4 2022-01-28 08:08:51 +03:00
Oleg Kalachev
3b06a33cad genmap.py: use -p flag in example 2022-01-27 04:00:26 +03:00
Oleg Kalachev
47e39d5331 vpe_publisher: rename parameter publish_zero to force_init 2022-01-26 07:24:04 +03:00
Oleg Kalachev
e86b4da0ed ci: cancel previous docs builds to avoid publishing old site 2022-01-25 19:12:17 +03:00
Oleg Kalachev
6bcd670190 Merge branch 'master' into recent-px4 2022-01-21 23:22:58 +03:00
Oleg Kalachev
b628825420 Merge branch 'master' into recent-px4 2022-01-20 19:57:20 +03:00
Oleg Kalachev
b3ac99fbef Merge branch 'master' into recent-px4 2021-12-17 07:40:18 +03:00
Oleg Kalachev
ae9a5154ab Merge branch 'master' into recent-px4 2021-12-16 13:44:15 +03:00
Oleg Kalachev
1878e467ac Merge branch 'master' into recent-px4 2021-12-16 13:35:23 +03:00
Oleg Kalachev
75b63ad77d Merge branch 'master' into recent-px4 2021-11-25 23:41:36 +03:00
Oleg Kalachev
140535b0b4 Merge branch 'master' into recent-px4 2021-11-25 23:36:30 +03:00
Oleg Kalachev
2a8c85144e Merge branch 'master' into recent-px4 2021-11-25 22:55:46 +03:00
Oleg Kalachev
65bc74b5ec docs: some updates to optical flow article 2021-11-19 10:16:10 +03:00
Oleg Kalachev
ac4f16f973 selfcheck.py: fix and simplify firmware version parsing, remove Clover firmware warning 2021-11-19 10:14:41 +03:00
Oleg Kalachev
baf8b736d4 selfcheck.py: make not finding vcgencmd not a failure 2021-11-19 09:47:45 +03:00
Oleg Kalachev
bb318ce93f selfcheck.py: add gzclient and gzserver to cpu eaters whitelist 2021-11-19 09:47:07 +03:00
Oleg Kalachev
d7b6968fee selfcheck.py: remove timestamps from selfcheck reports 2021-11-19 09:46:46 +03:00
Oleg Kalachev
08f6aa7aee docs: update 2021-11-18 14:43:21 +03:00
Oleg Kalachev
d5e729c66c docs: update firmware flashing section 2021-11-16 09:09:50 +03:00
Oleg Kalachev
27c83d062c docs: use enumerated list for consistency 2021-11-16 07:40:27 +03:00
Oleg Kalachev
04bc9fb017 docs: some updates in setup section 2021-11-16 07:32:02 +03:00
Oleg Kalachev
b2928dd536 docs: info on no mags found error 2021-11-16 07:31:01 +03:00
Oleg Kalachev
2a4163cbeb docs: update PX4 docs links 2021-11-16 07:30:33 +03:00
Oleg Kalachev
d1edc95ab5 docs: minor fix 2021-11-16 07:28:31 +03:00
12 changed files with 181 additions and 123 deletions

View File

@@ -8,8 +8,11 @@
<!-- For additional help go to https://clover.coex.tech/aruco --> <!-- For additional help go to https://clover.coex.tech/aruco -->
<arg name="force_init" default="false"/>
<arg name="disable" default="false"/> <!-- only force init -->
<!-- aruco_detect: detect aruco markers, estimate poses --> <!-- aruco_detect: detect aruco markers, estimate poses -->
<node name="aruco_detect" pkg="nodelet" if="$(arg aruco_detect)" type="nodelet" args="load aruco_pose/aruco_detect main_camera_nodelet_manager" output="screen" clear_params="true" respawn="true"> <node name="aruco_detect" pkg="nodelet" if="$(eval aruco_detect and not disable)" type="nodelet" args="load aruco_pose/aruco_detect main_camera_nodelet_manager" output="screen" clear_params="true" respawn="true">
<remap from="image_raw" to="main_camera/image_raw"/> <remap from="image_raw" to="main_camera/image_raw"/>
<remap from="camera_info" to="main_camera/camera_info"/> <remap from="camera_info" to="main_camera/camera_info"/>
<remap from="map_markers" to="aruco_map/markers"/> <remap from="map_markers" to="aruco_map/markers"/>
@@ -26,7 +29,7 @@
</node> </node>
<!-- aruco_map: estimate aruco map pose --> <!-- aruco_map: estimate aruco map pose -->
<node name="aruco_map" pkg="nodelet" type="nodelet" if="$(arg aruco_map)" args="load aruco_pose/aruco_map main_camera_nodelet_manager" output="screen" clear_params="true" respawn="true"> <node name="aruco_map" pkg="nodelet" type="nodelet" if="$(eval aruco_map and not disable)" args="load aruco_pose/aruco_map main_camera_nodelet_manager" output="screen" clear_params="true" respawn="true">
<remap from="image_raw" to="main_camera/image_raw"/> <remap from="image_raw" to="main_camera/image_raw"/>
<remap from="camera_info" to="main_camera/camera_info"/> <remap from="camera_info" to="main_camera/camera_info"/>
<remap from="markers" to="aruco_detect/markers"/> <remap from="markers" to="aruco_detect/markers"/>
@@ -41,11 +44,11 @@
</node> </node>
<!-- vpe publisher from aruco markers --> <!-- vpe publisher from aruco markers -->
<node name="vpe_publisher" pkg="clover" type="vpe_publisher" if="$(arg aruco_vpe)" output="screen" clear_params="true"> <node name="vpe_publisher" pkg="clover" type="vpe_publisher" if="$(eval aruco_vpe or force_init)" output="screen" clear_params="true">
<remap from="~pose_cov" to="aruco_map/pose"/> <remap from="~pose_cov" to="aruco_map/pose" if="$(arg aruco_vpe)"/>
<remap from="~vpe" to="mavros/vision_pose/pose"/> <remap from="~vpe" to="mavros/vision_pose/pose"/>
<param name="frame_id" value="aruco_map_detected"/> <param name="frame_id" value="aruco_map_detected" if="$(arg aruco_vpe)"/>
<param name="publish_zero" value="true"/> <param name="force_init" value="$(arg force_init)"/>
<param name="offset_frame_id" value="aruco_map"/> <param name="offset_frame_id" value="aruco_map"/>
</node> </node>
</launch> </launch>

View File

@@ -12,6 +12,7 @@
<arg name="led" default="true"/> <arg name="led" default="true"/>
<arg name="blocks" default="false"/> <arg name="blocks" default="false"/>
<arg name="rc" default="false"/> <arg name="rc" default="false"/>
<arg name="force_init" value="true"/> <!-- force estimator to init by publishing zero pose -->
<arg name="simulator" default="false"/> <!-- flag that we are operating on a simulated drone --> <arg name="simulator" default="false"/> <!-- flag that we are operating on a simulated drone -->
@@ -33,7 +34,10 @@
</node> </node>
<!-- aruco markers --> <!-- aruco markers -->
<include file="$(find clover)/launch/aruco.launch" if="$(arg aruco)"/> <include file="$(find clover)/launch/aruco.launch" if="$(eval aruco or force_init)">
<arg name="force_init" value="$(arg force_init)"/>
<arg name="disable" value="$(eval not aruco)"/>
</include>
<!-- optical flow --> <!-- optical flow -->
<node pkg="nodelet" type="nodelet" name="optical_flow" args="load clover/optical_flow main_camera_nodelet_manager" if="$(arg optical_flow)" clear_params="true" output="screen" respawn="true"> <node pkg="nodelet" type="nodelet" name="optical_flow" args="load clover/optical_flow main_camera_nodelet_manager" if="$(arg optical_flow)" clear_params="true" output="screen" respawn="true">

View File

@@ -195,24 +195,27 @@ def check_fcu():
failure('no connection to the FCU (check wiring)') failure('no connection to the FCU (check wiring)')
return return
clover_tag = re.compile(r'-cl[oe]ver\.\d+$')
clover_fw = False
# Make sure the console is available to us # Make sure the console is available to us
mavlink_exec('\n') mavlink_exec('\n')
version_str = mavlink_exec('ver all') version_str = mavlink_exec('ver all')
if version_str == '': if version_str == '':
info('no version data available from SITL') info('no version data available from SITL')
r = re.compile(r'^FW (git tag|version): (v?\d\.\d\.\d.*)$') for line in version_str.split('\n'):
is_clover_firmware = False if line.startswith('FW version: '):
for ver_line in version_str.split('\n'): info(line[len('FW version: '):])
match = r.search(ver_line) elif line.startswith('FW git tag: '): # only Clover's firmware
if match is not None: tag = line[len('FW git tag: '):]
field, version = match.groups() clover_fw = clover_tag.search(tag)
info('firmware %s: %s' % (field, version)) info(tag)
if 'clover' in version or 'clever' in version: elif line.startswith('HW arch: '):
is_clover_firmware = True info(line[len('HW arch: '):])
if not is_clover_firmware: if not clover_fw:
failure('not running Clover PX4 firmware, https://clover.coex.tech/firmware') info('not Clover PX4 firmware, check https://clover.coex.tech/firmware')
est = get_param('SYS_MC_EST_GROUP') est = get_param('SYS_MC_EST_GROUP')
if est == 1: if est == 1:

View File

@@ -141,11 +141,11 @@ int main(int argc, char **argv) {
vpe_pub = nh_priv.advertise<PoseStamped>("vpe", 1); vpe_pub = nh_priv.advertise<PoseStamped>("vpe", 1);
//vpe_cov_pub = nh_priv_.advertise<PoseStamped>("pose_cov_pub", 1); //vpe_cov_pub = nh_priv_.advertise<PoseStamped>("pose_cov_pub", 1);
if (nh_priv.param("publish_zero", false)) { if (nh_priv.param("force_init", false) || nh_priv.param("publish_zero", false)) { // publish_zero is old name
// publish zero to initialize the local position // publish zero to initialize the local position
zero_timer = nh.createTimer(ros::Duration(0.1), &publishZero); zero_timer = nh.createTimer(ros::Duration(0.1), &publishZero);
publish_zero_timout = ros::Duration(nh_priv.param("publish_zero_timout", 5.0)); publish_zero_timout = ros::Duration(nh_priv.param("force_init_timeout", 5.0));
publish_zero_duration = ros::Duration(nh_priv.param("publish_zero_duration", 5.0)); publish_zero_duration = ros::Duration(nh_priv.param("force_init_duration", 5.0));
local_position_sub = nh.subscribe("mavros/local_position/pose", 1, &localPositionCallback); local_position_sub = nh.subscribe("mavros/local_position/pose", 1, &localPositionCallback);
} }

Binary file not shown.

Before

Width:  |  Height:  |  Size: 244 KiB

View File

@@ -1,20 +1,64 @@
# PX4 Parameters # PX4 Parameters
Main article: https://dev.px4.io/en/advanced/parameter_reference.html Full documentation on PX4 parameters: https://docs.px4.io/master/en/advanced_config/parameter_reference.html.
> **Note** This is a description some of the most important PX4 parameters as of version 1.8.0. The full list is available at the link above. For changing PX4 parameters, use QGroundControl software, [connect to Clover over Wi-Fi](gcs_bridge.md) or USB. Go to *Vehicle Setup* panel (click on the QGroundControl logo in the top-left corner) and choose *Parameters* menu.
To change PX4 parameters, you can use the QGroundControl application [by connecting to Clover via Wi-Fi](gcs_bridge.md): ## Recommended values
![PX4 parameters in QGroundControl](../assets/qgc-params.png) ### Common parameters
## Main parameters |Parameter|Value|Comment|
|-|-|-|
|`SENS_FLOW_ROT`|0 (*No rotation*)|If using *PX4Flow* hardware, keep the default value|
|`SENS_FLOW_MINHGT`|0.01|For [VL53L1X](laser.md) rangefinder|
|`SENS_FLOW_MAXHGT`|4.0|For [VL53L1X](laser.md) rangefinder|
|`SENS_FLOW_MAXR`|10.0||
|`SYS_HAS_MAG`|0|If impossible to run the magnetometer (*No mags found* error)|
The most important parameters are listed in this paragraph. ### Estimator subsystem parameters
`SYS_MC_EST_GROUP` select the estimator module. In case of using LPE ([COEX patched firmware](firmware.md)):
This is a group of modules that calculates the current state of the copter using readings from the sensors. The copter state includes: |Parameter|Value|Comment|
|-|-|-|
|`LPE_FUSION`|86|Checkboxes: *flow* + *vis* + *land Detector* + *gyro comp*. If flying over horizontal floor *pub agl as lpos down* checkbox is allowed.<br>Details: [Optical Flow](optical_flow.md), [ArUco markers](aruco_map.md), [GPS](gps.md).|
|`LPE_VIS_DELAY`|0.0||
|`LPE_VIS_Z`|0.1||
|`LPE_FLW_SCALE`|1.0||
|`LPE_FLW_R`|0.2||
|`LPE_FLW_RR`|0.0||
|`LPE_FLW_QMIN`|10||
|`ATT_W_EXT_HDG`|0.5|Enabling usage of external yaw angle (when navigating using [markers map](aruco_map.md))|
|`ATT_EXT_HDG_M`|1 (*Vision*)||
|`ATT_W_MAG`|0|Disabling usage of the magnetometer (when navigating indoor)|
In case of using EKF2 (official firmware):
<!-- markdownlint-disable MD044 -->
|Parameter|Value|Comment|
|-|-|-|
|`EKF2_AID_MASK`|27|Checkboxes: (optionally) *gps* + *flow* + *vision position* + *vision yaw*.<br>Details: [Optical Flow](optical_flow.md), [ArUco markers](aruco_map.md), [GPS](gps.md).|
|`EKF2_OF_DELAY`|0||
|`EKF2_OF_QMIN`|10||
|`EKF2_OF_N_MIN`|0.05||
|`EKF2_OF_N_MAX`|0.2||
|`EKF2_HGT_MODE`|2 (*Range sensor*)|If the [rangefinder](laser.md) is present and flying over horizontal floor|
|`EKF2_EVA_NOISE`|0.1||
|`EKF2_EVP_NOISE`|0.1||
|`EKF2_EV_DELAY`|0||
|`EKF2_MAG_TYPE`|5 (*None*)|Disabling usage of the magnetometer (when navigating indoor)|
<!-- markdownlint-enable MD031 -->
> **Info** See also: list of default parameters of the [Clover simulator](simulation.md): https://github.com/CopterExpress/clover/blob/master/clover_simulation/airframes/4500_clover.
## Additional information
The `SYS_MC_EST_GROUP` parameter defines the estimator subsystem to use.
Estimator subsystem is a group of modules that calculates the current state of the copter using readings from the sensors. The copter state includes:
* Angle rate of the copter pitch_rate, roll_rate, yaw_rate; * Angle rate of the copter pitch_rate, roll_rate, yaw_rate;
* Copter orientation (in the local coordinate system) pitch, roll, yaw (one of presentations); * Copter orientation (in the local coordinate system) pitch, roll, yaw (one of presentations);
@@ -57,9 +101,7 @@ These parameters adjust the flight of the copter by position (POSCTL, OFFBOARD,
## LPE + Q attitude estimator ## LPE + Q attitude estimator
These parameters configure the behavior of the `lpe` and `q` modules, which compute the state (orientation, position) of the copter. These parameters apply **only** if the `SYS_MC_EST_GROUP` parameter is set to `1` (local_position_estimator, attitude_estimator_q) These parameters configure the behavior of the `lpe` and `q` modules, which compute the state (orientation, position) of the copter. These parameters apply **only** if the `SYS_MC_EST_GROUP` parameter is set to `1` (local_position_estimator, attitude_estimator_q).
TODO
## Commander ## Commander
@@ -68,5 +110,3 @@ Prearm checks, switching the modes and states of the copter.
## Sensors ## Sensors
Enabling, disabling and configuring various sensors. Enabling, disabling and configuring various sensors.
TODO

View File

@@ -27,28 +27,29 @@ Main article: https://docs.qgroundcontrol.com/en/SetupView/Firmware.html
> **Note** Do not connect your flight controller prior to flashing. > **Note** Do not connect your flight controller prior to flashing.
We recommend using the modified version of PX4 by CopterExpress for the Clover drone, especially for autonomous flights. Download the latest stable version **<a class="latest-firmware v4" href="https://github.com/CopterExpress/Firmware/releases">from our GitHub</a>**. We recommend using the modified version of [PX4 with COEX patches](firmware.md) for the Clover drone, especially for autonomous flights. Download the latest stable version **<a class="latest-firmware v4" href="https://github.com/CopterExpress/Firmware/releases">from our GitHub</a>**.
> **Info** For Pixhawk-based quadcopters there is a separate firmware version. See details in "[Pixhawk / Pixracer firmware flashing](firmware.md)" article. To use all the most recent PX4 functions you also can use the latest official firmware version (experimentally).
Flash the flight controller with this firmware: Flash the flight controller with this firmware:
<img src="../assets/qgc-firmware.png" alt="QGroundControl firmware upload" class="zoom"> <img src="../assets/qgc-firmware.png" alt="QGroundControl firmware upload" class="zoom">
1. Launch QGroundControl software. 1. Disconnect the flight controller from computer (if connected).
2. Open the *Vehicle Setup* tab. 2. Launch QGroundControl software.
3. Select the *Firmware* menu. 3. Go to *Vehicle Setup* panel (click on the QGroundControl logo in the top-left corner) and select *Firmware* menu.
4. Connect your flight controller to your PC over USB. 4. Connect your flight controller to your PC over USB.
5. Wait for the flight controller to connect to QGroundControl. 5. Select *PX4 Flight Stack* in the right bar appeared.
6. Select *PX4 Flight Stack* in the right bar.
To use the recommended Copter Express firmware: <img src="../assets/qgc-firmware.png" alt="QGroundControl firmware upload" class="zoom">
* Check *Advanced Settings* checkbox. 6. To use **COEX patched firmware**:
* Select *Custom firmware file...* from the dropdown list.
* Press *OK* and select the file that you've downloaded.
To use the latest official stable firmware just press *OK*. * Check *Advanced Settings* checkbox.
* Select *Custom firmware file...* from the dropdown list.
* Press *OK* and select the file that you've downloaded.
To use the latest **official stable firmware** just press *OK*.
Wait for QGroundControl to finish flashing the flight controller. Wait for QGroundControl to finish flashing the flight controller.
@@ -82,7 +83,7 @@ This is how the main QGroundControl settings window will look like:
### Setting parameters ### Setting parameters
Open the *Vehicle Setup* tab and select the *Parameters* menu. You can use the *Search* field to find parameters by name. Open the *Vehicle Setup* tab and select the *Parameters* menu. You can use the *Search* field to find parameters by name. Recommended parameters values are given in the further documentation and also in the [parameters summary article](parameters.md).
<img src="../assets/qgc-parameters.png" alt="QGroundControl parameters" class="zoom"> <img src="../assets/qgc-parameters.png" alt="QGroundControl parameters" class="zoom">

View File

@@ -1,11 +1,4 @@
Autonomous flight (OFFBOARD) # Autonomous flight
===
> **Note** In the image version **0.20** `clever` package was renamed to `clover`. See [previous version of the article](https://github.com/CopterExpress/clover/blob/v0.19/docs/en/simple_offboard.md) for older images.
<!-- -->
> **Hint** We recommend using our [custom PX4 firmware for Clover](firmware.md#modified-firmware-for-clover) for autonomous flights.
The `simple_offboard` module of the `clover` package is intended for simplified programming of the autonomous drone flight (`OFFBOARD` [flight mode](modes.md)). It allows setting the desired flight tasks, and automatically transforms [coordinates between frames](frames.md). The `simple_offboard` module of the `clover` package is intended for simplified programming of the autonomous drone flight (`OFFBOARD` [flight mode](modes.md)). It allows setting the desired flight tasks, and automatically transforms [coordinates between frames](frames.md).
@@ -13,8 +6,7 @@ The `simple_offboard` module of the `clover` package is intended for simplified
Main services are [`get_telemetry`](#gettelemetry) (receive telemetry data), [`navigate`](#navigate) (fly to a given point along a straight line), [`navigate_global`](#navigateglobal) (fly to a point specified as latitude and longitude along a straight line), [`land`](#land) (switch to landing mode). Main services are [`get_telemetry`](#gettelemetry) (receive telemetry data), [`navigate`](#navigate) (fly to a given point along a straight line), [`navigate_global`](#navigateglobal) (fly to a point specified as latitude and longitude along a straight line), [`land`](#land) (switch to landing mode).
Python examples ## Python usage
---
You need to create proxies for services before calling them. Use the following template for your programs: You need to create proxies for services before calling them. Use the following template for your programs:
@@ -37,8 +29,7 @@ land = rospy.ServiceProxy('land', Trigger)
Unused proxy functions may be removed from the code. Unused proxy functions may be removed from the code.
API description ## API description
---
> **Note** Omitted numeric parameters are set to 0. > **Note** Omitted numeric parameters are set to 0.
@@ -312,14 +303,9 @@ Landing the drone (command line):
rosservice call /land "{}" rosservice call /land "{}"
``` ```
<!-- > **Caution** In recent PX4 versions, the vehicle will be switched out of LAND mode to manual mode, if the remote control sticks are moved significantly.
### release
Stop publishing setpoints to the drone (release control). Required to continue monitoring by means of [MAVROS](mavros.md). ## Additional materials
-->
Additional materials
------------------------
* [ArUco-based position estimation and navigation](aruco.md). * [ArUco-based position estimation and navigation](aruco.md).
* [Program samples and snippets](snippets.md). * [Program samples and snippets](snippets.md).

View File

@@ -14,6 +14,8 @@
4. Последовательно устанавливайте квадрокоптер в каждую из указанных ориентаций до появления желтой рамки. 4. Последовательно устанавливайте квадрокоптер в каждую из указанных ориентаций до появления желтой рамки.
5. Вращайте квадрокоптер по направлению стрелки до появления зеленой рамки. 5. Вращайте квадрокоптер по направлению стрелки до появления зеленой рамки.
> **Warning** Последние версии прошивки PX4 не поддерживают внутренний компас на полетном контроллере COEX Pix. При появлении ошибки *No mags found* перейдите во вкладку *Parameters*, установите параметры `SYS_HAS_MAG` в `0`, `EKF2_MAG_TYPE` в `None` и перезагрузите полетный контроллер (*Tools* => *Reboot Vehicle*).
Дополнительная информация: https://docs.px4.io/master/en/config/compass.html. Дополнительная информация: https://docs.px4.io/master/en/config/compass.html.
## Гироскоп ## Гироскоп

View File

@@ -1,20 +1,64 @@
# Параметры PX4 # Параметры PX4
Основная статья: https://dev.px4.io/en/advanced/parameter_reference.html Полная документация по параметрам PX4: https://docs.px4.io/master/en/advanced_config/parameter_reference.html.
> **Note** Это описание некоторых, наиболее важных параметров PX4 по состоянию на версию 1.8.0. Полный список см. по ссылке выше. Для изменения параметров PX4 используйте программу QGroundControl, [подключившись к Клеверу по Wi-Fi](gcs_bridge.md) или USB. Перейдите в панель *Vehicle Setup* (кликнув на логотип QGroundControl в левом верхнем углу и выберите меню *Parameters*.
Для изменения параметров PX4 можно воспользоваться программой QGroundControl, [подключившись к Клеверу по Wi-Fi](gcs_bridge.md): ## Рекомендованные значения
![Параметры PX4 в QGroundControl](../assets/qgc-params.png) ### Общие параметры
## Основные параметры |Параметр|Значение|Примечание|
|-|-|-|
|`SENS_FLOW_ROT`|0 (*No rotation*)|В случае использования "железного" [PX4Flow](px4flow.md), оставьте значение по умолчанию|
|`SENS_FLOW_MINHGT`|0.01|Для [дальномера VL53L1X](laser.md)|
|`SENS_FLOW_MAXHGT`|4.0|Для [дальномера VL53L1X](laser.md)|
|`SENS_FLOW_MAXR`|10.0||
|`SYS_HAS_MAG`|0|При невозможности запуска магнитометра (ошибка *No mags found*)|
Наиболее важные параметры вынесены в этот параграф. ### Настройки подсистемы Estimator
`SYS_MC_EST_GROUP`  выбор модуля estimator'а. В случае использования LPE ([прошивка COEX](firmware.md)):
Это группа модулей, которая вычисляет текущее состояние (state) коптера, используя показания с датчиков. В состояние коптера входит: |Параметр|Значение|Примечание|
|-|-|-|
|`LPE_FUSION`|86|Чекбоксы: *flow* + *vis* + *land Detector* + *gyro comp*. При полете над ровным полом возможно включение *pub agl as lpos down*. <br>Подробнее: [Optical Flow](optical_flow.md), [ArUco-маркеры](aruco_map.md), [GPS](gps.md).|
|`LPE_VIS_DELAY`|0.0||
|`LPE_VIS_Z`|0.1||
|`LPE_FLW_SCALE`|1.0||
|`LPE_FLW_R`|0.2||
|`LPE_FLW_RR`|0.0||
|`LPE_FLW_QMIN`|10||
|`ATT_W_EXT_HDG`|0.5|Включение использования внешнего угла по рысканью (при навигации по [карте маркеров](aruco_map.md))|
|`ATT_EXT_HDG_M`|1 (*Vision*)||
|`ATT_W_MAG`|0|Выключение магнитометра (при навигации внутри помещения)|
В случае использования EKF2 (официальная прошивка):
<!-- markdownlint-disable MD044 -->
|Параметр|Значение|Примечание|
|-|-|-|
|`EKF2_AID_MASK`|27|Чекбоксы: (опционально) *gps* + *flow* + *vision position* + *vision yaw*.<br>Подробнее: [Optical Flow](optical_flow.md), [ArUco-маркеры](aruco_map.md), [GPS](gps.md).|
|`EKF2_OF_DELAY`|0||
|`EKF2_OF_QMIN`|10||
|`EKF2_OF_N_MIN`|0.05||
|`EKF2_OF_N_MAX`|0.2||
|`EKF2_HGT_MODE`|2 (*Range sensor*)|При наличии [дальномера](laser.md) и полете над ровным полом|
|`EKF2_EVA_NOISE`|0.1||
|`EKF2_EVP_NOISE`|0.1||
|`EKF2_EV_DELAY`|0||
|`EKF2_MAG_TYPE`|5 (*None*)|Выключение магнитометра (при навигации внутри помещения)|
<!-- markdownlint-enable MD031 -->
> **Info** См. также: список параметров по умолчанию в [симуляторе](simulation.md): https://github.com/CopterExpress/clover/blob/master/clover_simulation/airframes/4500_clover.
## Дополнительная информация
Параметр `SYS_MC_EST_GROUP` отвечает за выбор Estimator'а.
Estimator это подсистема, которая вычисляет текущее состояние (state) коптера, используя показания с датчиков. В состояние коптера входит:
* угловая скорость коптера pitch_rate, roll_rate, yaw_rate; * угловая скорость коптера pitch_rate, roll_rate, yaw_rate;
* ориентация коптера (в локальной системе координат) pitch (тангаж), roll (крен), yaw (рысканье) (одно из представлений); * ориентация коптера (в локальной системе координат) pitch (тангаж), roll (крен), yaw (рысканье) (одно из представлений);
@@ -57,9 +101,7 @@
## LPE + Q attitude estimator ## LPE + Q attitude estimator
Данные параметры настраивают поведение модулей `lpe` и `q`, которые вычисляют состояние (ориентацию, позицию) коптера. Эти параметры применяются **только** если параметр `SYS_MC_EST_GROUP` установлен в значение `1` (local_position_estimator, attitude_estimator_q) Данные параметры настраивают поведение модулей `lpe` и `q`, которые вычисляют состояние (ориентацию, позицию) коптера. Эти параметры применяются **только** если параметр `SYS_MC_EST_GROUP` установлен в значение `1` (local_position_estimator, attitude_estimator_q).
TODO
## Commander ## Commander
@@ -68,5 +110,3 @@ TODO
## Sensors ## Sensors
Включение, выключение и настройка различных датчиков. Включение, выключение и настройка различных датчиков.
TODO

View File

@@ -16,39 +16,32 @@
<img src="../assets/pix-sd.png" alt="Pixracer и MicroSD-карта" class="zoom center" width=400> <img src="../assets/pix-sd.png" alt="Pixracer и MicroSD-карта" class="zoom center" width=400>
* Установите карту в компьютер (используйте адаптер при необходимости). 1. Установите карту в компьютер (используйте адаптер при необходимости).
* Отформатируйте карту в файловую систему FAT32. Для этого кликните на значок SD-карты в "Проводнике" и нажмите "Форматирование" в Windows. Используйте "Дисковую утилиту" в macOS. 2. Отформатируйте карту в файловую систему FAT32. Для этого кликните на значок SD-карты в "Проводнике" и нажмите "Форматирование" в Windows. Используйте "Дисковую утилиту" в macOS.
* Выполните "Безопасное извлечение" карты, извлеките карту. 3. Выполните "Безопасное извлечение" карты, извлеките карту.
* Установите карту в полетный контроллер. 4. Установите карту в полетный контроллер.
## Загрузка прошивки в полетный контроллер ## Загрузка прошивки в полетный контроллер
Основная статья: https://docs.qgroundcontrol.com/en/SetupView/Firmware.html. Наиболее оттестированной, в особенности для осуществления автономных полетов, является [версия прошивки с патчами COEX](firmware.md). Скачайте актуальную версию прошивки на GitHub — **<a class="latest-firmware v4" href="https://github.com/CopterExpress/Firmware/releases">скачать</a>**.
> **Note** Перед осуществлением перепрошивки Pixracer не должен быть подключен к компьютеру по USB. Для использования всех наиболее актуальных функций PX4 вы также можете использовать последнюю официальную версию прошивки (в экспериментальном режиме).
Для Клевера, в особенности для осуществления автономных полетов, рекомендуется использовать версию прошивки PX4 от Copter Express. Скачайте актуальную версию прошивки на GitHub — **<a class="latest-firmware v4" href="https://github.com/CopterExpress/Firmware/releases">скачать</a>**. 1. Отключите полетный контроллер от компьютера (если он подключен).
2. Запустите программу QGroundControl.
3. Перейдите в панель *Vehicle Setup* (кликнув на логотип QGroundControl в левом верхнем углу) и выберите меню *Firmware*.
4. Подключите полетный контроллер к компьютеру по USB.
5. Выберите в появившемся меню справа *PX4 Flight Stack*.
> **Info** Для квадрокоптеров с Pixhawk (Клевер 2) существует отдельная версия прошивки. Подробности смотрите в статье "[Прошивка полетного контроллера](firmware.md)". <img src="../assets/qgc-firmware.png" alt="QGroundControl firmware upload" class="zoom">
Загрузите прошивку в полетный контролер: 6. Для загрузки **прошивки COEX**:
<img src="../assets/qgc-firmware.png" alt="QGroundControl firmware upload" class="zoom"> * Выберите *Advanced settings*.
* В выпадающем меню выберите *Custom firmware file...*
* Нажмите *OK* и выберите скаченный файл прошивки.
1. Запустите программу QGroundControl. Для загрузки последней версии **стандартной прошивки** сразу нажмите *OK*.
2. Зайдите во вкладку *Vehicle Setup*.
3. Выберите меню *Firmware*.
4. Подключите Pixracer к компьютеру по USB.
5. Дождитесь подключения Pixracer к QGroundControl.
6. Выберите в меню справа *PX4 Flight Stack*.
Для загрузки прошивки от Copter Express (рекомендуется):
* Выберите *Advanced settings*.
* В выпадающем меню выберите *Custom firmware file...*
* Нажмите *OK* и выберите скаченный файл прошивки.
Для загрузки последней версии стандартной прошивки сразу нажмите *OK*.
Дождитесь, пока QGroundControl загрузит прошивку и выполнит перезагрузку полетного контроллера. Дождитесь, пока QGroundControl загрузит прошивку и выполнит перезагрузку полетного контроллера.
@@ -82,7 +75,7 @@
### Параметры ### Параметры
Для настройки параметров полетного контроллера войдите во вкладку *Vehicle Setup* и выберите меню *Parameters*. Вы можете использовать поле *Search* для поиска параметров по имени. Для настройки параметров полетного контроллера войдите во вкладку *Vehicle Setup* и выберите меню *Parameters*. Вы можете использовать поле *Search* для поиска параметров по имени. Рекомендуемые параметры для Клевера приведены в дальнейшей документации а также в соответствующей [сводной статье](parameters.md).
<img src="../assets/qgc-parameters.png" alt="QGroundControl parameters" class="zoom"> <img src="../assets/qgc-parameters.png" alt="QGroundControl parameters" class="zoom">

View File

@@ -1,11 +1,4 @@
Автономный полет (OFFBOARD) # Автономный полет
===
> **Note** В версии образа **0.20** пакет `clever` был переименован в `clover`. Для более ранних версий см. документацию для версии [**0.19**](https://github.com/CopterExpress/clover/blob/v0.19/docs/ru/simple_offboard.md).
<!-- -->
> **Hint** Для автономных полетов рекомендуется использование [специальной сборки PX4 для Клевера](firmware.md#прошивка-для-клевера).
Модуль `simple_offboard` пакета `clover` предназначен для упрощенного программирования автономного полета дрона ([режим](modes.md) `OFFBOARD`). Он позволяет устанавливать желаемые полетные задачи и автоматически трансформирует [систему координат](frames.md). Модуль `simple_offboard` пакета `clover` предназначен для упрощенного программирования автономного полета дрона ([режим](modes.md) `OFFBOARD`). Он позволяет устанавливать желаемые полетные задачи и автоматически трансформирует [систему координат](frames.md).
@@ -13,8 +6,7 @@
Основные сервисы [`get_telemetry`](#gettelemetry) (получение телеметрии), [`navigate`](#navigate) (полет в заданную точку по прямой), [`navigate_global`](#navigateglobal) (полет в глобальную точку по прямой), [`land`](#land) (переход в режим посадки). Основные сервисы [`get_telemetry`](#gettelemetry) (получение телеметрии), [`navigate`](#navigate) (полет в заданную точку по прямой), [`navigate_global`](#navigateglobal) (полет в глобальную точку по прямой), [`land`](#land) (переход в режим посадки).
Использование из языка Python ## Использование из языка Python
---
Для использования сервисов, необходимо создать объекты-прокси к ним. Используйте этот шаблон для вашей программы: Для использования сервисов, необходимо создать объекты-прокси к ним. Используйте этот шаблон для вашей программы:
@@ -37,8 +29,7 @@ land = rospy.ServiceProxy('land', Trigger)
Неиспользуемые функции-прокси можно удалить из кода. Неиспользуемые функции-прокси можно удалить из кода.
Описание API ## Описание API
---
> **Note** Незаполненные числовые параметры устанавливаются в значение 0. > **Note** Незаполненные числовые параметры устанавливаются в значение 0.
@@ -312,14 +303,9 @@ if res.success:
rosservice call /land "{}" rosservice call /land "{}"
``` ```
<!-- > **Caution** В более новых версиях PX4 коптер выйдет из режима LAND в ручной режим, если сильно перемещать стики.
### release
Перестать публиковать setpoint'ы коптеру (отпустить управление). Необходим для продолжения контроля средствами [MAVROS](mavros.md). ## Дополнительные материалы
-->
Дополнительные материалы
------------------------
* [Полеты в поле ArUco-маркеров](aruco.md). * [Полеты в поле ArUco-маркеров](aruco.md).
* [Примеры программ и сниппеты](snippets.md). * [Примеры программ и сниппеты](snippets.md).