mirror of
https://github.com/CopterExpress/clover.git
synced 2026-06-01 23:49:32 +00:00
Compare commits
14 Commits
clover-doc
...
hitl
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
add7f0d55f | ||
|
|
c1d6ed27aa | ||
|
|
614784e949 | ||
|
|
9376c017b4 | ||
|
|
b5d300e218 | ||
|
|
efb44484b0 | ||
|
|
0a2ad3d64f | ||
|
|
ffe2d3d5e4 | ||
|
|
81f4795aec | ||
|
|
596ed3dcf2 | ||
|
|
63c71fc331 | ||
|
|
0efb249d9b | ||
|
|
47c6e5aa9b | ||
|
|
687a4f50fd |
23
.github/workflows/docs-docker.yaml
vendored
23
.github/workflows/docs-docker.yaml
vendored
@@ -1,23 +0,0 @@
|
||||
name: Build docs Docker image
|
||||
|
||||
on:
|
||||
workflow_dispatch:
|
||||
push:
|
||||
branches: [ '*' ]
|
||||
|
||||
jobs:
|
||||
docs-docker:
|
||||
runs-on: ubuntu-22.04
|
||||
steps:
|
||||
- uses: actions/checkout@v2
|
||||
|
||||
- name: Build Docker image
|
||||
run: docker build -t clover-docs:latest docs
|
||||
|
||||
- name: Test Docker image
|
||||
run: docker run -t --rm -v `pwd`:/clover clover-docs:latest
|
||||
|
||||
- name: Show results
|
||||
run: |
|
||||
ls -lh _book
|
||||
ls -lh *.pdf
|
||||
@@ -1,5 +1,5 @@
|
||||
<launch>
|
||||
<arg name="fcu_conn" default="usb"/> <!-- options: usb, uart, tcp, udp, sitl -->
|
||||
<arg name="fcu_conn" default="usb"/> <!-- options: usb, uart, tcp, udp, sitl, hitl -->
|
||||
<arg name="fcu_ip" default="127.0.0.1"/>
|
||||
<arg name="fcu_sys_id" default="1"/>
|
||||
<arg name="gcs_bridge" default="tcp"/>
|
||||
@@ -23,6 +23,9 @@
|
||||
<!-- sitl since PX4 1.9.0 -->
|
||||
<param name="fcu_url" value="udp://@$(arg fcu_ip):14580" if="$(eval fcu_conn == 'sitl')"/>
|
||||
|
||||
<!-- hitl connection (to gazebo_mavlink_interface plugin) -->
|
||||
<param name="fcu_url" value="udp://$(arg fcu_ip):14540@" if="$(eval fcu_conn == 'hitl')"/>
|
||||
|
||||
<!-- set target_system_id -->
|
||||
<param name="target_system_id" value="$(arg fcu_sys_id)" />
|
||||
|
||||
|
||||
@@ -37,6 +37,8 @@
|
||||
<depend>rosbridge_server</depend>
|
||||
<depend>web_video_server</depend>
|
||||
<depend>tf2_web_republisher</depend>
|
||||
<depend>libxml2</depend>
|
||||
<depend>libxslt</depend>
|
||||
<depend condition="$ROS_PYTHON_VERSION == 2">python-lxml</depend>
|
||||
<depend condition="$ROS_PYTHON_VERSION == 3">python3-lxml</depend>
|
||||
<depend>dynamic_reconfigure</depend>
|
||||
|
||||
@@ -154,7 +154,7 @@ private:
|
||||
|
||||
img.convertTo(curr_, CV_32F);
|
||||
|
||||
if (prev_.empty()) {
|
||||
if (prev_.empty() || (msg->header.stamp - prev_stamp_).toSec() > 0.1) { // outdated previous frame
|
||||
prev_ = curr_.clone();
|
||||
prev_stamp_ = msg->header.stamp;
|
||||
cv::createHanningWindow(hann_, curr_.size(), CV_32F);
|
||||
|
||||
@@ -625,6 +625,10 @@ def check_rangefinder():
|
||||
|
||||
@check('Boot duration')
|
||||
def check_boot_duration():
|
||||
if not os.path.exists('/etc/clover_version'):
|
||||
info('skip check')
|
||||
return # Don't check not on Clover's image
|
||||
|
||||
output = subprocess.check_output('systemd-analyze').decode()
|
||||
r = re.compile(r'([\d\.]+)s\s*$', flags=re.MULTILINE)
|
||||
duration = float(r.search(output).groups()[0])
|
||||
|
||||
@@ -10,8 +10,9 @@
|
||||
<arg name="gps" default="true"/>
|
||||
<!-- Use physics parameters from CAD programs -->
|
||||
<arg name="use_clover_physics" default="false"/>
|
||||
<arg name="hitl" default="false"/>
|
||||
|
||||
<arg name="cmd" default="$(find xacro)/xacro $(find clover_description)/urdf/clover/clover4.xacro main_camera:=$(arg main_camera) rangefinder:=$(arg rangefinder) led:=$(arg led) gps:=$(arg gps) maintain_camera_rate:=$(arg maintain_camera_rate) use_clover_physics:=$(arg use_clover_physics)"/>
|
||||
<arg name="cmd" default="$(find xacro)/xacro $(find clover_description)/urdf/clover/clover4.xacro main_camera:=$(arg main_camera) rangefinder:=$(arg rangefinder) led:=$(arg led) gps:=$(arg gps) maintain_camera_rate:=$(arg maintain_camera_rate) use_clover_physics:=$(arg use_clover_physics) hitl:=$(arg hitl)"/>
|
||||
<param command="$(arg cmd)" name="drone_description"/>
|
||||
<!-- Note: -package_to_model replaces all mentions of "package://" with "model://" in urdf URIs -->
|
||||
<node name="$(anon spawn)" output="screen" pkg="gazebo_ros" type="spawn_model" args="-urdf -param drone_description -model clover -z 0.3"/>
|
||||
|
||||
@@ -7,6 +7,7 @@
|
||||
<xacro:arg name="gps" default="true"/>
|
||||
<xacro:arg name="maintain_camera_rate" default="false"/>
|
||||
<xacro:arg name="use_clover_physics" default="false"/>
|
||||
<xacro:arg name="hitl" default="false"/>
|
||||
|
||||
<xacro:include filename="clover4_base.xacro" />
|
||||
<xacro:include filename="../sensors/rpi_cam.urdf.xacro"/>
|
||||
|
||||
@@ -53,14 +53,14 @@
|
||||
<mavlink_addr>INADDR_ANY</mavlink_addr>
|
||||
<mavlink_tcp_port>4560</mavlink_tcp_port>
|
||||
<mavlink_udp_port>14560</mavlink_udp_port>
|
||||
<serialEnabled>false</serialEnabled>
|
||||
<serialEnabled>$(arg hitl)</serialEnabled>
|
||||
<serialDevice>/dev/ttyACM0</serialDevice>
|
||||
<baudRate>921600</baudRate>
|
||||
<qgc_addr>INADDR_ANY</qgc_addr>
|
||||
<qgc_udp_port>14550</qgc_udp_port>
|
||||
<sdk_addr>INADDR_ANY</sdk_addr>
|
||||
<sdk_udp_port>14540</sdk_udp_port>
|
||||
<hil_mode>false</hil_mode>
|
||||
<hil_mode>$(arg hitl)</hil_mode>
|
||||
<hil_state_level>0</hil_state_level>
|
||||
<send_vision_estimation>0</send_vision_estimation>
|
||||
<send_odometry>1</send_odometry>
|
||||
|
||||
@@ -10,7 +10,7 @@ The simulation may be configured by a set of arguments:
|
||||
|
||||
* `mav_id` (*integer*, default: *0*) - MAVLink identifier of the vehicle. **Note**: Multi-vehicle simulation is possible, but requires extensive changes to launch files;
|
||||
* `est` (*string*, default: *lpe*, possible values: *lpe*, *ekf2*) - PX4 estimator selection. Note that this may be overriden in the startup scripts for your craft;
|
||||
* `vehicle` (*string*, default: *clover*) - PX4 vehicle name. Depending on this parameter, different PX4 presets will be loaded. **Note**: The default value, *clover*, requires you to use [Clover-specific PX4 branch](https://github.com/CopterExpress/Firmware/tree/v1.10.1-clever);
|
||||
* `vehicle` (*string*, default: *clover*) - PX4 vehicle name. Depending on this parameter, different PX4 presets will be loaded.
|
||||
* `main_camera` (*boolean*, default: *true*) - controls whether the drone will have a vision position estimation camera;
|
||||
* `rangefinder` (*boolean*, default: *true*) - controls whether the drone will have a laser rangefinder;
|
||||
* `led` (*boolean*, default: *true*) - controls whether the drone will have a programmable LED strip;
|
||||
|
||||
@@ -1,5 +1,6 @@
|
||||
<launch>
|
||||
<arg name="type" default="gazebo"/> <!-- gazebo, jmavsim, none (only clover packages) -->
|
||||
<arg name="mode" default="sitl"/> <!-- sitl or hitl -->
|
||||
<arg name="mav_id" default="0"/>
|
||||
<arg name="est" default="ekf2"/> <!-- PX4 estimator: lpe, ekf2 -->
|
||||
<arg name="vehicle" default="clover"/> <!-- PX4 vehicle configuration: clover, clover_vpe -->
|
||||
@@ -21,7 +22,7 @@
|
||||
</include>
|
||||
|
||||
<!-- PX4 instance -->
|
||||
<node name="sitl_$(arg mav_id)" pkg="px4" type="px4" output="screen" required="true" args="$(find px4)/ROMFS/px4fmu_common -s etc/init.d-posix/rcS -i $(arg mav_id)" unless="$(eval type == 'none')">
|
||||
<node name="sitl_$(arg mav_id)" pkg="px4" type="px4" output="screen" required="true" args="$(find px4)/ROMFS/px4fmu_common -s etc/init.d-posix/rcS -i $(arg mav_id)" unless="$(eval type == 'none' or mode == 'hitl')">
|
||||
<env name="PX4_SIM_MODEL" value="$(arg vehicle)"/>
|
||||
<env name="PX4_ESTIMATOR" value="$(arg est)"/>
|
||||
</node>
|
||||
@@ -34,6 +35,7 @@
|
||||
<arg name="led" value="$(arg led)"/>
|
||||
<arg name="gps" value="$(arg gps)"/>
|
||||
<arg name="use_clover_physics" value="$(arg use_clover_physics)"/>
|
||||
<arg name="hitl" value="$(eval mode == 'hitl')"/>
|
||||
</include>
|
||||
|
||||
<node name="jmavsim" pkg="px4" required="true" type="jmavsim_run.sh" output="screen" if="$(eval type == 'jmavsim')">
|
||||
@@ -45,7 +47,7 @@
|
||||
<!-- Clover services -->
|
||||
<include file="$(find clover)/launch/clover.launch">
|
||||
<arg name="simulator" value="true"/>
|
||||
<arg name="fcu_conn" value="sitl"/>
|
||||
<arg name="fcu_conn" value="$(arg mode)"/>
|
||||
<arg name="fcu_ip" value="127.0.0.1"/>
|
||||
<arg name="gcs_bridge" value=""/>
|
||||
<arg name="web_video_server" default="false" if="$(eval type == 'jmavsim')"/>
|
||||
|
||||
@@ -1,36 +0,0 @@
|
||||
# Build: sudo docker build -t clover-docs:latest .
|
||||
|
||||
# Run: docker run -it --rm -v ~/clover:/clover clover-docs:latest
|
||||
|
||||
# Save image: sudo docker save clover-docs:latest | gzip > clover-docs.tar.gz
|
||||
|
||||
FROM ubuntu:22.04
|
||||
|
||||
ENV DEBIAN_FRONTEND=noninteractive
|
||||
|
||||
RUN apt-get update && apt-get install -y curl git
|
||||
|
||||
RUN curl https://raw.githubusercontent.com/creationix/nvm/master/install.sh | bash
|
||||
RUN . $HOME/.nvm/nvm.sh && nvm install 10.15 && nvm use 10.15 && npm --version
|
||||
|
||||
RUN echo ttf-mscorefonts-installer msttcorefonts/accepted-mscorefonts-eula select true | debconf-set-selections \
|
||||
&& apt-get update \
|
||||
&& apt-get install -y calibre msttcorefonts ghostscript
|
||||
|
||||
RUN . $HOME/.nvm/nvm.sh && curl https://raw.githubusercontent.com/CopterExpress/clover/master/builder/assets/install_gitbook.sh | bash
|
||||
|
||||
# RUN . $HOME/.nvm/nvm.sh && npm install markdownlint-cli@0.28.1 -g && PUPPETEER_SKIP_DOWNLOAD=1 npm install svgexport -g
|
||||
RUN . $HOME/.nvm/nvm.sh && npm install markdownlint-cli@0.28.1 -g && npm install svgexport -g --unsafe-perm
|
||||
|
||||
RUN . $HOME/.nvm/nvm.sh && node -v && gitbook -V && markdownlint -V
|
||||
|
||||
RUN curl https://raw.githubusercontent.com/CopterExpress/clover/master/book.json > book.json
|
||||
|
||||
RUN . $HOME/.nvm/nvm.sh && gitbook install
|
||||
|
||||
CMD . $HOME/.nvm/nvm.sh && export QTWEBENGINE_DISABLE_SANDBOX=1 && cp -r node_modules /clover && cd /clover && gitbook build \
|
||||
&& gitbook pdf ./ _book/clover.pdf && \
|
||||
gs -sDEVICE=pdfwrite -dCompatibilityLevel=1.4 -dPDFSETTINGS=/default -dNOPAUSE -dQUIET -dBATCH -dDetectDuplicateImages -dCompressFonts=true -r150 -sOutputFile=_book/clover_ru_compressed.pdf _book/clover_ru.pdf && \
|
||||
gs -sDEVICE=pdfwrite -dCompatibilityLevel=1.4 -dPDFSETTINGS=/default -dNOPAUSE -dQUIET -dBATCH -dDetectDuplicateImages -dCompressFonts=true -r150 -sOutputFile=_book/clover_en_compressed.pdf _book/clover_en.pdf && \
|
||||
rm _book/clover_ru.pdf && mv _book/clover_ru_compressed.pdf _book/clover_ru.pdf && \
|
||||
rm _book/clover_en.pdf && mv _book/clover_en_compressed.pdf _book/clover_en.pdf
|
||||
@@ -1,7 +1,5 @@
|
||||
# Working with the camera
|
||||
|
||||
> **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/camera.md) for older images.
|
||||
|
||||
Make sure the camera is enabled in the `~/catkin_ws/src/clover/clover/launch/clover.launch` file:
|
||||
|
||||
```xml
|
||||
|
||||
@@ -20,15 +20,14 @@ USB connection is the preferred way to connect to the flight controller.
|
||||
|
||||
## UART connection
|
||||
|
||||
> **Note** In the image version **0.20** `clever` package and service was renamed to `clover`. See [previous version of the article](https://github.com/CopterExpress/clover/blob/v0.19/docs/en/connection.md) for older images.
|
||||
|
||||
<!-- TODO: Connection scheme -->
|
||||
|
||||
UART connection is another way for the Raspberry Pi and FCU to communicate.
|
||||
|
||||
1. Connect Raspberry Pi to your FCU using a UART cable.
|
||||
2. [Connect to the Raspberry Pi over SSH](ssh.md).
|
||||
3. Change the connection type in `~/catkin_ws/src/clover/clover/launch/clover.launch` to UART:
|
||||
1. Connect the TELEM 2 port on the flight controller using a UART cable to the Raspberry Pi pins following this instruction: the black cable (*GND*) to Ground, the green cable (*UART_RX*) to *GPIO14*, the yellow cable (*UART_TX*) to *GPIO15*. Do not connect the red cable (*5V*).
|
||||
2. Set the PX4 parameters: `MAV_1_CONFIG` to TELEM 2, `SER_TEL2_BAUND` to 921600 8N1. In PX4 of version prior to v1.10.0 the parameter `SYS_COMPANION` should be set to 921600.
|
||||
3. [Connect to the Raspberry Pi over SSH](ssh.md).
|
||||
4. Change the connection type in `~/catkin_ws/src/clover/clover/launch/clover.launch` to UART:
|
||||
|
||||
```xml
|
||||
<arg name="fcu_conn" default="uart"/>
|
||||
@@ -40,15 +39,4 @@ UART connection is another way for the Raspberry Pi and FCU to communicate.
|
||||
sudo systemctl restart clover
|
||||
```
|
||||
|
||||
> **Hint** Set the `SYS_COMPANION` PX4 parameter to 921600 to enable UART on the FCU.
|
||||
|
||||
## SITL connection
|
||||
|
||||
In order to connect to a local or a remote [SITL](sitl.md) instance set the `fcu_conn` parameter to `udp` and `fcu_ip` to the IP address of the SITL instance (`127.0.0.1` if you are running the instance locally):
|
||||
|
||||
```xml
|
||||
<arg name="fcu_conn" default="udp"/>
|
||||
<arg name="fcu_ip" default="127.0.0.1"/>
|
||||
```
|
||||
|
||||
**Next**: [Using QGroundControl over Wi-Fi](gcs_bridge.md)
|
||||
|
||||
@@ -40,6 +40,8 @@ Messages published in the topics may be viewed with the `rostopic` utility, e.g.
|
||||
|
||||
`/mavros/setpoint_position/local` — set target position and yaw of the drone \(in the ENU coordinate system\).
|
||||
|
||||
`/mavros/setpoint_position/global` – set target position in global coordinates (latitude, longitude, altitude) and yaw of the drone.
|
||||
|
||||
`/mavros/setpoint_position/cmd_vel` — set target linear velocity of the drone.
|
||||
|
||||
`/mavros/setpoint_attitude/attitude` and `/mavros/setpoint_attitude/att_throttle` — set target attitude and throttle level.
|
||||
@@ -52,4 +54,4 @@ Messages published in the topics may be viewed with the `rostopic` utility, e.g.
|
||||
|
||||
`/mavros/setpoint_raw/attitude` — sends [SET\_ATTITUDE\_TARGET](https://mavlink.io/en/messages/common.html#SET_ATTITUDE_TARGET) message. Allows setting the target attitude /angular velocity and throttle level. The values to be set are selected using the `type_mask` field
|
||||
|
||||
`/mavros/setpoint_raw/global` — sends [SET\_POSITION\_TARGET\_GLOBAL\_INT](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_GLOBAL_INT). Allows setting the target attitude in global coordinates \(latitude, longitude, altitude\) and flight speed. **Not supported in PX4** \([issue](https://github.com/PX4/Firmware/issues/7552)\).
|
||||
`/mavros/setpoint_raw/global` — sends [SET\_POSITION\_TARGET\_GLOBAL\_INT](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_GLOBAL_INT). Allows setting the target attitude in global coordinates \(latitude, longitude, altitude\) and flight speed.
|
||||
|
||||
@@ -2,7 +2,7 @@
|
||||
|
||||
Setting up the simulation environment from scratch requires some effort, but results in the most performant setup, with less chance of driver issues.
|
||||
|
||||
> **Hint** See up-to-date commands set for installation Clover simulation software in the script, that builds the virtual machine image with the simulator: [`install_software.sh`](https://github.com/CopterExpress/clover_vm/blob/master/scripts/install_software.sh).
|
||||
<!-- > **Hint** See up-to-date commands set for installation Clover simulation software in the script, that builds the virtual machine image with the simulator: [`install_software.sh`](https://github.com/CopterExpress/clover_vm/blob/master/scripts/install_software.sh). -->
|
||||
|
||||
Prerequisites: **Ubuntu 20.04**.
|
||||
|
||||
@@ -66,7 +66,7 @@ PX4 will be built along with the other packages in our workspace. You may clone
|
||||
Clone PX4 sources and make the required symlinks:
|
||||
|
||||
```bash
|
||||
git clone --recursive --depth 1 --branch v1.12.0 https://github.com/PX4/PX4-Autopilot.git ~/PX4-Autopilot
|
||||
git clone --recursive --depth 1 --branch v1.12.3 https://github.com/PX4/PX4-Autopilot.git ~/PX4-Autopilot
|
||||
ln -s ~/PX4-Autopilot ~/catkin_ws/src/
|
||||
ln -s ~/PX4-Autopilot/Tools/sitl_gazebo ~/catkin_ws/src/
|
||||
ln -s ~/PX4-Autopilot/mavlink ~/catkin_ws/src/
|
||||
|
||||
@@ -1,7 +1,5 @@
|
||||
# Работа с камерой
|
||||
|
||||
> **Note** В версии образа **0.20** пакет и сервис `clever` был переименован в `clover`. Для более ранних версий см. документацию для версии [**0.19**](https://github.com/CopterExpress/clover/blob/v0.19/docs/ru/camera.md).
|
||||
|
||||
<!-- TODO: физическое подключение -->
|
||||
|
||||
Для работы с основной камерой необходимо убедиться что она включена в файле `~/catkin_ws/src/clover/clover/launch/clover.launch`:
|
||||
|
||||
@@ -20,15 +20,14 @@
|
||||
|
||||
## Подключение по UART
|
||||
|
||||
> **Note** В версии образа **0.20** пакет и сервис `clever` был переименован в `clover`. Для более ранних версий см. документацию для версии [**0.19**](https://github.com/CopterExpress/clover/blob/v0.19/docs/ru/connection.md).
|
||||
|
||||
<!-- TODO схема подключения -->
|
||||
|
||||
Дополнительным способом подключения является подключение подключение по интерфейсу UART.
|
||||
|
||||
1. Подключите Raspberry Pi к полетному контроллеру по UART.
|
||||
2. [Подключитесь в Raspberry Pi по SSH](ssh.md).
|
||||
3. Поменяйте в launch-файле Клевера (`~/catkin_ws/src/clover/clover/launch/clover.launch`) тип подключения на UART:
|
||||
1. Подключите Raspberry Pi к полетному контроллеру по UART. Для этого соедините кабелем порт TELEM 2 на полетном контроллере к пинам на Raspberry Pi следующем образом: черный провод (GND) к Ground, зеленый (*UART_RX*) к *GPIO14*, желтый (*UART_TX*) к *GPIO15*. Красный провод (*5V*) подключать не нужно.
|
||||
2. Измените значения параметров PX4: `MAV_1_CONFIG` на TELEM 2, `SER_TEL2_BAUND` на 921600 8N1. В PX4 до версии v1.10.0 необходима установка параметра `SYS_COMPANION` в значение 921600.
|
||||
3. [Подключитесь в Raspberry Pi по SSH](ssh.md).
|
||||
4. Поменяйте в launch-файле Клевера (`~/catkin_ws/src/clover/clover/launch/clover.launch`) тип подключения на UART:
|
||||
|
||||
```xml
|
||||
<arg name="fcu_conn" default="uart"/>
|
||||
@@ -40,15 +39,4 @@
|
||||
sudo systemctl restart clover
|
||||
```
|
||||
|
||||
> **Hint** Для корректной работы подключения Raspberry Pi и полетного контроллера по UART необходимо установить значение параметра `SYS_COMPANION` на 921600.
|
||||
|
||||
## Подключение к SITL
|
||||
|
||||
Для того, чтобы подсоединиться к локально/удаленно запущенному [SITL](sitl.md), необходимо установить аргумент `fcu_conn` в `udp`, и `fcu_ip` в IP-адрес машины, где запущен SITL (`127.0.0.1` для локального):
|
||||
|
||||
```xml
|
||||
<arg name="fcu_conn" default="udp"/>
|
||||
<arg name="fcu_ip" default="127.0.0.1"/>
|
||||
```
|
||||
|
||||
**Далее**: [Подключение QGroundControl по Wi-Fi](gcs_bridge.md).
|
||||
|
||||
@@ -40,6 +40,8 @@ MAVROS подписывается на определенные ROS-топики
|
||||
|
||||
`/mavros/setpoint_position/local` — установить целевую позицию и рысканье \(yaw\) беспилотника \(в системе координат ENU\).
|
||||
|
||||
`/mavros/setpoint_position/global` – установить целевую позицию в глобальных координатах (ширина, долгота и высота) и рысканье беспилотника.
|
||||
|
||||
`/mavros/setpoint_velocity/cmd_vel` — установить целевую линейную скорость беспилотника.
|
||||
|
||||
`/mavros/setpoint_attitude/attitude` и `/mavros/setpoint_attitude/att_throttle` — установить целевую ориентацию \(Attitude\) и уровень газа.
|
||||
@@ -52,4 +54,4 @@ MAVROS подписывается на определенные ROS-топики
|
||||
|
||||
`/mavros/setpoint_raw/attitude` — отправка пакета [SET\_ATTITUDE\_TARGET](https://mavlink.io/en/messages/common.html#SET_ATTITUDE_TARGET). Позволяет установить целевую ориентацию / угловые скорости и уровень газа. Выбор устанавливаемых величин осуществляется с помощью поля `type_mask`
|
||||
|
||||
`/mavros/setpoint_raw/global` — отправка пакета [SET\_POSITION\_TARGET\_GLOBAL\_INT](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_GLOBAL_INT). Позволяет установить целевую позицию в глобальных координатах \(ширина, долгота, высота\), а также скорости полета. **Не поддерживается в PX4** \([issue](https://github.com/PX4/Firmware/issues/7552)\).
|
||||
`/mavros/setpoint_raw/global` — отправка пакета [SET\_POSITION\_TARGET\_GLOBAL\_INT](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_GLOBAL_INT). Позволяет установить целевую позицию в глобальных координатах \(ширина, долгота, высота\), а также скорости полета.
|
||||
|
||||
@@ -2,7 +2,7 @@
|
||||
|
||||
Настройка среды для симуляции с нуля требует некоторых усилий, однако это приведет к улучшению производительности и к уменьшению вероятности появления проблем с драйверами.
|
||||
|
||||
> **Hint** Смотрите актуальный набор команд установки необходимого ПО для запуска симулятора Клевера в скрипте сборки виртуальной машины с симулятором: [`install_software.sh`](https://github.com/CopterExpress/clover_vm/blob/master/scripts/install_software.sh).
|
||||
<!-- > **Hint** Смотрите актуальный набор команд установки необходимого ПО для запуска симулятора Клевера в скрипте сборки виртуальной машины с симулятором: [`install_software.sh`](https://github.com/CopterExpress/clover_vm/blob/master/scripts/install_software.sh). -->
|
||||
|
||||
Требования для сборки: **Ubuntu 20.04**.
|
||||
|
||||
@@ -66,7 +66,7 @@ sudo /usr/bin/python3 -m pip install -r ~/catkin_ws/src/clover/clover/requiremen
|
||||
Склонируйте исходный код PX4 и создайте необходимые симлинки:
|
||||
|
||||
```bash
|
||||
git clone --recursive --depth 1 --branch v1.12.0 https://github.com/PX4/PX4-Autopilot.git ~/PX4-Autopilot
|
||||
git clone --recursive --depth 1 --branch v1.12.3 https://github.com/PX4/PX4-Autopilot.git ~/PX4-Autopilot
|
||||
ln -s ~/PX4-Autopilot ~/catkin_ws/src/
|
||||
ln -s ~/PX4-Autopilot/Tools/sitl_gazebo ~/catkin_ws/src/
|
||||
ln -s ~/PX4-Autopilot/mavlink ~/catkin_ws/src/
|
||||
|
||||
Reference in New Issue
Block a user