Compare commits

..

11 Commits

Author SHA1 Message Date
Oleg Kalachev
45356b19a9 docs: add note about flying relative to a marker in the map 2019-09-15 17:53:15 +03:00
Alexey Rogachevskiy
e1a11bd70a aruco_pose: Allow rgb8 map images 2019-09-11 23:10:36 +03:00
Alexey Rogachevskiy
035384cd6f builder: Make tests run again 2019-09-11 21:56:10 +03:00
Oleg Kalachev
16a2ecef2e gitbook: fix 2019-09-11 20:59:20 +03:00
Tenessinum
727fde82a8 docs: change size of iframes in Big Challenges article (#177) 2019-09-10 17:28:11 +03:00
Oleg Kalachev
fc1df980ff docs: fix link to the latest firmware 2019-09-10 16:25:39 +03:00
Alexey Rogachevskiy
2e7bcde38e docs: Revise simple_offboard translation (en) 2019-09-10 14:23:06 +03:00
Alexey Rogachevskiy
5a8ce0cf0c docs/en: Remove non-English words 2019-09-09 22:41:18 +03:00
Oleg Kalachev
e78c57a734 Change Clever documentation domain name 2019-09-09 16:22:48 +03:00
Oleg Kalachev
9581cc6496 Create CNAME 2019-09-09 16:13:19 +03:00
Oleg Kalachev
eddec45259 gitbook: make redirect pages blank 2019-09-08 00:45:30 +03:00
29 changed files with 97 additions and 83 deletions

View File

@@ -73,8 +73,8 @@ jobs:
github-token: ${GITHUB_OAUTH_TOKEN}
keep-history: true
target-branch: master
repo: CopterExpress/clever-gitbook
fqdn: clever.copterexpress.com
repo: CopterExpress/clever.coex.tech
fqdn: clever.coex.tech
verbose: true
on:
branch: master

View File

@@ -6,7 +6,7 @@ CLEVER (Russian: *"Клевер"*, meaning *"Clover"*) is an educational program
Copter Express has implemented a large number of different autonomous drone projects using exactly the same platform: [automated pizza delivery](https://www.youtube.com/watch?v=hmkAoZOtF58) in Samara and Kazan, coffee delivery in Skolkovo Innovation Center, [autonomous quadcopter with charging station](https://www.youtube.com/watch?v=RjX6nUqw1mI) for site monitoring and security, winning drones on [Robocross-2016](https://www.youtube.com/watch?v=dGbDaz_VmYU) and [Robocross-2017](https://youtu.be/AQnd2CRczbQ) competitions and many others.
**The main documentation is available [on Gitbook](https://clever.copterexpress.com/).**
**The main documentation is available [on Gitbook](https://clever.coex.tech/).**
Use it to learn how to assemble, configure, pilot and program autonomous CLEVER drone.
@@ -26,7 +26,7 @@ Image includes:
* Periphery drivers (`pigpiod`, `rpi_ws281x`, etc)
* CLEVER software bundle for autonomous drone control
API description (in Russian) for autonomous flights is available [on GitBook](https://clever.copterexpress.com/simple_offboard.html).
API description (in Russian) for autonomous flights is available [on GitBook](https://clever.coex.tech/simple_offboard.html).
## Manual installation

View File

@@ -140,7 +140,7 @@ def test_map_image(node):
img = rospy.wait_for_message('aruco_map/image', Image, timeout=5)
assert img.width == 2000
assert img.height == 2000
assert img.encoding == 'mono8'
assert img.encoding in ('mono8', 'rgb8')
def test_map_markers(node):
markers = rospy.wait_for_message('aruco_map/markers', MarkerArray, timeout=5)

View File

@@ -17,7 +17,7 @@ class TestArucoPose(unittest.TestCase):
img = rospy.wait_for_message('aruco_map/image', Image, timeout=5)
self.assertEqual(img.width, 2000)
self.assertEqual(img.height, 2000)
self.assertEqual(img.encoding, 'mono8')
self.assertIn(img.encoding, ('mono8', 'rgb8'))
def test_map_visualization(self):
vis = rospy.wait_for_message('aruco_map/visualization', VisMarkerArray, timeout=5)

View File

@@ -58,4 +58,4 @@ def test_map_image(node):
img = rospy.wait_for_message('aruco_map/image', Image, timeout=5)
assert img.width == 2000
assert img.height == 2000
assert img.encoding == 'mono8'
assert img.encoding in ('mono8', 'rgb8')

View File

@@ -24,10 +24,11 @@
},
"bulk-redirect": {
"basepath": "",
"redirectsFile": "redirects.json"
"redirectsFile": "redirects.json",
"blank": true
},
"sitemap": {
"hostname": "https://clever.copterexpress.com"
"hostname": "https://clever.coex.tech"
},
"toolbar": {
"buttons":

View File

@@ -183,6 +183,7 @@ echo_stamp "Install GeographicLib datasets (needed for mavros)" \
&& wget -qO- https://raw.githubusercontent.com/mavlink/mavros/master/mavros/scripts/install_geographiclib_datasets.sh | bash
echo_stamp "Running tests"
cd /home/pi/catkin_ws
catkin_make run_tests && catkin_test_results
echo_stamp "Change permissions for catkin_ws"

View File

@@ -3,7 +3,7 @@
<arg name="aruco_map" default="false"/>
<arg name="aruco_vpe" default="false"/>
<!-- For additional help go to https://clever.copterexpress.com/aruco.html -->
<!-- For additional help go to https://clever.coex.tech/aruco -->
<!-- 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 nodelet_manager" output="screen" clear_params="true">

View File

@@ -3,7 +3,7 @@
<arg name="led_effect" default="true"/>
<arg name="led_notify" default="true"/>
<!-- For additional help go to https://clever.copterexpress.com/led.html -->
<!-- For additional help go to https://clever.coex.tech/led -->
<!-- ws281x led strip driver -->
<node pkg="ws281x" name="led" type="ws281x_node" clear_params="true" output="screen" if="$(arg ws281x)">

View File

@@ -2,7 +2,7 @@
<!-- Camera position and orientation are represented by base_link -> main_camera_optical transform -->
<!-- static_transform_publisher arguments: x y z yaw pitch roll frame_id child_frame_id -->
<!-- article about camera setup: https://clever.copterexpress.com/camera_frame.html -->
<!-- article about camera setup: https://clever.coex.tech/camera_frame -->
<!-- camera is oriented downward, camera cable goes backward [option 1] -->
<node pkg="tf2_ros" type="static_transform_publisher" name="main_camera_frame" args="0.05 0 -0.07 -1.5707963 0 3.1415926 base_link main_camera_optical"/>

View File

@@ -7,7 +7,7 @@
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>
<license>MIT</license>
<url type="website">https://clever.copterexpress.com/</url>
<url type="website">https://clever.coex.tech/</url>
<author email="okalachev@gmail.com">Oleg Kalachev</author>
<author email="urpylka@gmail.com">Artem Smirnov</author>

View File

@@ -209,7 +209,7 @@ def check_fcu():
is_clever_firmware = True
if not is_clever_firmware:
failure('not running Clever PX4 firmware, check http://clever.copterexpress.com/firmware.html')
failure('not running Clever PX4 firmware, https://clever.coex.tech/firmware')
est = get_param('SYS_MC_EST_GROUP')
if est == 1:
@@ -244,7 +244,7 @@ def check_fcu():
battery = rospy.wait_for_message('mavros/battery', BatteryState, timeout=3)
cell = battery.cell_voltage[0]
if cell > 4.3 or cell < 3.0:
failure('Incorrect cell voltage: %.2f V, see https://clever.copterexpress.com/power.html', cell)
failure('Incorrect cell voltage: %.2f V, https://clever.coex.tech/power', cell)
elif cell < 3.7:
failure('Critically low cell voltage: %.2f V, recharge battery', cell)
except rospy.ROSException:

View File

@@ -479,7 +479,7 @@ inline void checkState()
throw std::runtime_error("State timeout, check mavros settings");
if (!state.connected)
throw std::runtime_error("No connection to FCU, https://clever.copterexpress.com/connection.html");
throw std::runtime_error("No connection to FCU, https://clever.coex.tech/connection");
}
#define ENSURE_FINITE(var) { if (!std::isfinite(var)) throw std::runtime_error(#var " argument cannot be NaN or Inf"); }

View File

@@ -1,7 +1,7 @@
<h1>CLEVER Drone Kit Tools</h1>
<ul>
<li><a href="docs">View documentation</a> (snapshot of <a href="http://clever.copterexpress.com">clever.copterexpress.com</a>)</li>
<li><a href="docs">View documentation</a> (snapshot of <a href="https://clever.coex.tech">clever.coex.tech</a>)</li>
<li><a href="" id="wvs">View image topics</a> (<code>web_video_server</code>)</li>
<li><a href="" id="butterfly">Open web terminal</a> (<code>Butterfly</code>)</li>
<li><a href="viz.html">View 3D visualization</a> (<code>ros3djs</code>)</li>

View File

@@ -37,7 +37,7 @@ gitbook.events.bind('page.change', function() {
// show link to latest raspberry image
gitbook.events.bind('page.change', function() {
var el = document.querySelector('a.latest-image');
if (el.length) return;
if (!el) return;
// get latest release from GitHub
fetch('https://api.github.com/repos/CopterExpress/clever/releases').then(function(res) {

View File

@@ -120,6 +120,13 @@ time.sleep(5)
navigate(2, 2, 2, speed=1, frame_id='aruco_map')
```
Starting from the [image](image.md) version 0.18, the drone also can fly relative to a marker in the map, even if it doesn't see it:
```python
# Fly to 1 meter above the marker 5
navigate(frame_id='aruco_5', x=0, y=0, z=1)
```
## Additional settings
If the drone's position is not stable when VPE is used, try increasing the *P* term in the velocity PID regulator: increase the `MPC_XY_VEL_P` and `MPC_Z_VEL_P` parameters.

View File

@@ -269,7 +269,7 @@ and replace map.txt with your map name.
Ctrl+x; y; Enter
```
- Перезагрузите модуль Клевер:
- Restart the `clever` service:
```bash
sudo systemctl restart clever

View File

@@ -31,7 +31,7 @@ Before you test it you need to install on your laptop:
- Install Nodejs from [here](https://nodejs.org/en/download/). For [Ubuntu installation](https://tecadmin.net/install-latest-nodejs-npm-on-ubuntu/)
- Install Yarn package manager from [here](https://yarnpkg.com/lang/en/docs/install/). [Usual problem](https://github.com/yarnpkg/yarn/issues/3189) while installing and using yarn with Ubuntu.
- Have an experience in manual control on the drone in case of any weird behavior happen.
- Worked before with COEX drones, if this is your first time to work with COEX drones check [this](https://clever.copterexpress.com/en/).
- Worked before with COEX drones, if this is your first time to work with COEX drones check [this](https://clever.coex.tech/en/).
and you are ready to build and use the required codes.
@@ -52,7 +52,7 @@ git clone https://github.com/hany606/tfjs-posenet.git
### In the Raspberry Pi of the drone (Main controller)
- Access the Raspberry Pi
- [Switch to Client mode](https://clever.copterexpress.com/en/network.html) and ensure that the network has internet connection.
- [Switch to Client mode](network.md) and ensure that the network has internet connection.
Notice: I have already made a bash script based on that tutorial, it is in COEX-Internship19/helpers/ called .to_client.bash
To run it:
@@ -145,7 +145,7 @@ Animation is created by [this](https://justsketchme.web.app/)
## References
- [Human pose estimation guide](https://blog.nanonets.com/human-pose-estimation-2d-guide/)
- [Clever drones tutorials](https://clever.copterexpress.com/en/)
- [Clever drones tutorials](https://clever.coex.tech/en/)
- [Posenet GitHub repo](https://github.com/tensorflow/tfjs-models/tree/master/posenet)
- [Posenet meduim article](https://medium.com/tensorflow/real-time-human-pose-estimation-in-the-browser-with-tensorflow-js-7dd0bc881cd5)
- [Tensorflow.js demos](https://www.tensorflow.org/js/demos)

View File

@@ -27,7 +27,7 @@ Main article: https://docs.qgroundcontrol.com/en/SetupView/Firmware.html
> **Note** Do not connect your flight controller prior to flashing.
We recommend using the modified version of PX4 by CopterExpress for the Clever drone, especially for autonomous flights. Download the latest stable version **<a class="latest-firmware v4" href="https://github.com/CopterExpress/clever/releases">from our GitHub</a>**.
We recommend using the modified version of PX4 by CopterExpress for the Clever 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>**.
Flash the flight controller with this firmware:

View File

@@ -5,27 +5,25 @@ Simple OFFBOARD
<!-- -->
> **Hint** For autonomous flights it is recommanded to use [special firmware PX4 for Clever](firmware.md#прошивка-для-клевера).
> **Hint** For autonomous flights it is recommanded to use [special PX4 firmware for Clever](firmware.md#modified-firmware-for-clever).
The `simple_offboard` module of the `clever` package is intended for simplified programming of the autonomous drone ([mode](modes.md) `OFFBOARD`). It allows setting the desired flight tasks, and automatically transforms [the system of coordinates](frames.md).
The `simple_offboard` module of the `clever` 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).
`simple_offboard` is a high level way of interacting with the flight controller. For a more low level work, see [mavros](mavros.md).
`simple_offboard` is a high level system for interacting with the flight controller. For a more low level system, see [mavros](mavros.md).
Main services are `get_telemetry` (receiving all telemetry), `navigate` (flying to a given point along a straight line), `navigate_global` (flying to a global point along a straight line), `land` (switching to the 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).
The use of Python language
Python samples
---
To use the services, create proxies to them. Use the following template for you programs:
You need to create proxies for services before calling them. Use the following template for your programs:
```python
import rospy
from clever import srv
from std_srvs.srv import Trigger
rospy.init_node('flight') # flight name of your ROS node
# Creating proxies to all services:
rospy.init_node('flight') # 'flight' is name of your ROS node
get_telemetry = rospy.ServiceProxy('get_telemetry', srv.GetTelemetry)
navigate = rospy.ServiceProxy('navigate', srv.Navigate)
@@ -42,11 +40,11 @@ Unused proxy functions may be removed from the code.
API description
---
> **Note** Blank numeric parameters are set to 0.
> **Note** Omitted numeric parameters are set to 0.
### get_telemetry
Obtaining complete telemetry of the drone.
Obtains complete telemetry of the drone.
Parameters:
@@ -56,11 +54,11 @@ Response format:
* `frame_id` — frame;
* `connected` whether there is a connection to <abbr title="Flight Control Unit flight controller">FCU</abbr>;
* `armed` - state of propellers (the propellers are armed, if true);
* `armed` - drone arming state (armed if true);
* `mode` current [flight mode](modes.md);
* `x, y, z` — local position of the drone *(m)*;
* `lat, lon` latitude, longitude *(degrees)*, [GPS](gps.md) is to be available;
* `alt` altitude in the global system of coordinates (standard [WGS-84](https://ru.wikipedia.org/wiki/WGS_84), not <abbr title="Above Mean Sea Level">AMSL</abbr>!), [GPS](gps.md) is to be available ;
* `lat, lon` drone latitude and longitude *(degrees)*, requires [GPS](gps.md) module;
* `alt` altitude in the global coordinate system (according to [WGS-84](https://ru.wikipedia.org/wiki/WGS_84) standard, not <abbr title="Above Mean Sea Level">AMSL</abbr>!), requires [GPS](gps.md) module;
* `vx, vy, vz` drone velocity *(m/s)*;
* `pitch` pitch angle *(radians)*;
* `roll` roll angle *(radians)*;
@@ -71,7 +69,7 @@ Response format:
* `voltage` total battery voltage *(V)*;
* `cell_voltage` battery cell voltage *(V)*.
> **Note** Fields that are unavailabe for any reason will contain the `NaN` value.
> **Note** Fields that are unavailable for any reason will contain the `NaN` value.
Displaying drone coordinates `x`, `y` and `z` in the local system of coordinates:
@@ -80,7 +78,7 @@ telemetry = get_telemetry()
print telemetry.x, telemetry.y, telemetry.z
```
Displaying drone altitude relative to [the card of ArUco tags](aruco.md):
Displaying drone altitude relative to [the ArUco map](aruco.md):
```python
telemetry = get_telemetry(frame_id='aruco_map')
@@ -92,14 +90,14 @@ Checking global position availability:
```python
import math
if not math.isnan(get_telemetry().lat):
print 'Global position presents'
print 'Global position is available'
else:
print 'No global position'
```
Output of current telemetry (command line):
```(bash)
```bash
rosservice call /get_telemetry "{frame_id: ''}"
```
@@ -111,12 +109,12 @@ Parameters:
* `x`, `y` — coordinates *(m)*;
* `yaw` — yaw angle *(radians)*;
* `yaw_rate` angular yaw velocity (used for setting the yaw to `NaN`) *(rad/s)*;
* `yaw_rate` angular yaw velocity (will be used if yaw is set to `NaN`) *(rad/s)*;
* `speed` flight speed (setpoint speed) *(m/s)*;
* `auto_arm` switch the drone to `OFFBOARD` and arm automatically (**the drone will take off**);
* `frame_id` [system of coordinates](frames.md) for values `x`, `y`, `z`, `vx`, `vy`, `vz`. Example: `map`, `body`, `aruco_map`. Default value: `map`.
* `auto_arm` switch the drone to `OFFBOARD` mode and arm automatically (**the drone will take off**);
* `frame_id` [coordinate system](frames.md) for values `x`, `y`, `z`, `vx`, `vy`, `vz`. Example: `map`, `body`, `aruco_map`. Default value: `map`.
> **Note** To fly without changing the yaw angle, it is sufficient to set the `yaw` to `NaN` (angular velocity by default is 0).
> **Note** If you don't want to change your current yaw set the `yaw` parameter to `NaN` (angular velocity by default is 0).
Ascending to the altitude of 1.5 m with the climb rate of 0.5 m/s:
@@ -148,7 +146,7 @@ Turn 90 degrees counterclockwise:
navigate(yaw=math.radians(-90), frame_id='body')
```
Flying to point 3:2 (altitude 2) in the system of coordinates [of the marker field](aruco.md) at the speed of 1 m/s:
Flying to point 3:2 (with the altitude of 2 m) in the [ArUco map](aruco.md) coordinate system with the speed of 1 m/s:
```python
navigate(x=3, y=2, z=2, speed=1, frame_id='aruco_map')
@@ -174,7 +172,7 @@ rosservice call /navigate "{x: 0.0, y: 0.0, z: 2, yaw: 0.0, yaw_rate: 0.0, speed
### navigate_global
Flying in a straight line to a point in the global system of coordinates (latitude/longitude).
Flying in a straight line to a point in the global coordinate system (latitude/longitude).
Parameters:
@@ -184,11 +182,11 @@ Parameters:
* `yaw_rate` angular yaw velocity (used for setting the yaw to `NaN`) *(rad/s)*;
* `speed` flight speed (setpoint speed) *(m/s)*;
* `auto_arm` switch the drone to `OFFBOARD` and arm automatically (**the drone will take off**);
* `frame_id` [system of coordinates](frames.md), given `z` и `yaw` (Default value: `map`).
* `frame_id` [coordinate system](frames.md) for `z` and `yaw` (Default value: `map`).
> **Note** To fly without changing the yaw angle, it is sufficient to set the `yaw` to `NaN` (angular velocity by default is 0).
> **Note** If you don't want to change your current yaw set the `yaw` parameter to `NaN` (angular velocity by default is 0).
Flying to a global point at the speed of 5 m/s, while remaining at current altitude (`yaw` will be set to 0, the drone will face East):
Flying to a global point at the speed of 5 m/s, while maintaining current altitude (`yaw` will be set to 0, the drone will face East):
```python
navigate_global(lat=55.707033, lon=37.725010, z=0, speed=5, frame_id='body')
@@ -202,15 +200,15 @@ navigate_global(lat=55.707033, lon=37.725010, z=0, speed=5, yaw=float('nan'), fr
Flying to a global point (command line):
```(bash)
```bash
rosservice call /navigate_global "{lat: 55.707033, lon: 37.725010, z: 0.0, yaw: 0.0, yaw_rate: 0.0, speed: 5.0, frame_id: 'body', auto_arm: false}"
```
### set_position
Set the target for position and yaw. This service may be used to specify the continuous flow of target points, for example, for flying along complex trajectories (circular, arcuate, etc.).
Set the setpoint for position and yaw. This service may be used to specify the continuous flow of target points, for example, for flying along complex trajectories (circular, arcuate, etc.).
> **Hint** For flying to a point in a straight line or takeoff, use the [`navigate`] higher-level service (#navigate).
> **Hint** Use the [`navigate`](#navigate) higher-level service to fly to a point in a straight line or to perform takeoff.
Parameters:
@@ -218,7 +216,7 @@ Parameters:
* `yaw` — yaw angle *(radians)*;
* `yaw_rate` angular yaw velocity (used for setting the yaw to NaN) *(rad/s)*;
* `auto_arm` switch the drone to `OFFBOARD` and arm automatically (**the drone will take off**);
* `frame_id` [system of coordinates](frames.md), given `x`, `y`, `z` и `yaw` (Default value: `map`).
* `frame_id` [coordinate system](frames.md) for `x`, `y`, `z` and `yaw` parameters (Default value: `map`).
Hovering on the spot:
@@ -246,13 +244,13 @@ set_position(x=0, y=0, z=0, frame_id='body', yaw=float('nan'), yaw_rate=0.5)
### set_velocity
Setting speed and yaw.
Set speed and yaw setpoints.
* `vx`, `vy`, `vz` required flight speed *(m/s)*;
* `vx`, `vy`, `vz` flight speed *(m/s)*;
* `yaw` — yaw angle *(radians)*;
* `yaw_rate` angular yaw velocity (used for setting the yaw to NaN) *(rad/s)*;
* `auto_arm` switch the drone to `OFFBOARD` and arm automatically (**the drone will take off**);
* `frame_id` [system of coordinates](frames.md), given `vx`, `vy`, `vz` и `yaw` (Default value: `map`).
* `frame_id` [coordinate system](frames.md) for `vx`, `vy`, `vz` and `yaw` (Default value: `map`).
> **Note** Parameter `frame_id` specifies only the orientation of the resulting velocity vector, but not its length.
@@ -262,7 +260,7 @@ Flying forward (relative to the drone) at the speed of 1 m/s:
set_velocity(vx=1, vy=0.0, vz=0, frame_id='body')
```
One of variants of flying in a circle:
One possible way of flying in a circle:
```python
set_velocity(vx=0.4, vy=0.0, vz=0, yaw=float('nan'), yaw_rate=0.4, frame_id='body')
@@ -270,30 +268,30 @@ set_velocity(vx=0.4, vy=0.0, vz=0, yaw=float('nan'), yaw_rate=0.4, frame_id='bod
### set_attitude
Setting pitch, roll, yaw and throttle level (approximate analogue to control in [the `STABILIZED` mode](modes.md)). This service may be used for lower level monitoring of the drone behavior or controlling the drone, if no reliable data on its position are available.
Set pitch, roll, yaw and throttle level (similar to [the `STABILIZED` mode](modes.md)). This service may be used for lower level control of the drone behavior, or controlling the drone when no reliable data on its position is available.
Parameters:
* `pitch`, `roll`, `yaw` required pitch, roll, and yaw angle *(radians)*;
* `thrust` — throttle level from 0 (no throttle, propellers are stopped) to 1 (full throttle).
* `auto_arm` switch the drone to `OFFBOARD` and arm automatically (**the drone will take off**);
* `frame_id` [system of coordinates](frames.md), given `yaw` (Default value: `map`).
* `pitch`, `roll`, `yaw` requested pitch, roll, and yaw angle *(radians)*;
* `thrust` — throttle level, ranges from 0 (no throttle, propellers are stopped) to 1 (full throttle).
* `auto_arm` switch the drone to `OFFBOARD` mode and arm automatically (**the drone will take off**);
* `frame_id` [coordinate system](frames.md) for `yaw` (Default value: `map`).
### set_rates
Setting pitch, roll, and yaw angular velocity and the throttle level (approximate analogue to control in [the `ACRO` mode](modes.md)). This is the lowest drone control level (excluding direct control of motor rotation speed). This service may be used to automatically perform acrobatic tricks (e.g., flips).
Set pitch, roll, and yaw rates and the throttle level (similar to [the `ACRO` mode](modes.md)). This is the lowest drone control level (excluding direct control of motor rotation speed). This service may be used to automatically perform aerobatic tricks (e.g., flips).
Parameters:
* `pitch_rate`, `roll_rate`, `yaw_rate` angular pitch, roll, and yaw velocity *(rad/s)*;
* `thrust` — throttle level from 0 (no throttle, propellers are stopped) to 1 (full throttle).
* `pitch_rate`, `roll_rate`, `yaw_rate` pitch, roll, and yaw rates *(rad/s)*;
* `thrust` — throttle level, ranges from 0 (no throttle, propellers are stopped) to 1 (full throttle).
* `auto_arm` switch the drone to `OFFBOARD` and arm automatically (**the drone will take off**);
### land
Transfer the drone to the landing [mode](modes.md) (`AUTO.LAND` or similar).
Switch the drone to landing [mode](modes.md) (`AUTO.LAND` or similar).
> **Note** For automatic propeller disabling after landing, [parameter PX4](px4_parameters.md) `COM_DISARM_LAND` is to be set to a value > 0.
> **Note** Set the `COM_DISARM_LAND` [PX4 parameter](px4_parameters.md) to a value greater than 0 to enable automatic disarm after landing.
Landing the drone:
@@ -306,7 +304,7 @@ if res.success:
Landing the drone (command line):
```(bash)
```bash
rosservice call /land "{}"
```
@@ -319,5 +317,5 @@ Stop publishing setpoints to the drone (release control). Required to continue m
Additional materials
------------------------
* [Flying in the field of ArUco markers](aruco.md).
* [Samples of programs and snippets](snippets.md).
* [ArUco-based position estimation and navigation](aruco.md).
* [Program samples and snippets](snippets.md).

View File

@@ -128,6 +128,13 @@ time.sleep(5)
navigate(2, 2, 2, speed=1, frame_id='aruco_map') # полет в координату 2:2, высота 3 метра
```
Начиная с версии [образа](image.md) 0.18, доступны также полеты относительно отдельного маркера в карте, даже если дрон его не видит:
```python
# Полет на высоту 1 м над маркером 5
navigate(frame_id='aruco_5', x=0, y=0, z=1)
```
## Дополнительные настройки
<!-- TODO: статья по пидам -->

View File

@@ -1,6 +1,6 @@
# Генератор ArUco карт
Начиная с образа версии *0.16* изменился подход к созданию карт маркеров: маркеры больше не привязаны к сетке и каждый из них теперь можно повернуть на любой угол вокруг всех трёх осей. Вместе с этим изменился и способ задания карт маркеров. Теперь карта загружается из текстового файла (подробнее в статье [**Навигация по картам ArUco-маркеров**](https://clever.copterexpress.com/ru/aruco_map.html)). Для упрощения процесса создания текстового файла был создан [*конструктор полей*](https://aruco.tenessinum.ru/).
Начиная с образа версии *0.16* изменился подход к созданию карт маркеров: маркеры больше не привязаны к сетке и каждый из них теперь можно повернуть на любой угол вокруг всех трёх осей. Вместе с этим изменился и способ задания карт маркеров. Теперь карта загружается из текстового файла (подробнее в статье [**Навигация по картам ArUco-маркеров**](aruco_map.md)). Для упрощения процесса создания текстового файла был создан [*конструктор полей*](https://aruco.tenessinum.ru/).
<img alt="" src="../assets/arucogenmap.PNG"/>

View File

@@ -7,8 +7,8 @@
Крупные города страдают из-за пробок и перегруженности транспорта. Пробки на дорогах и перегруженность транспорта влечёт за собой многие неудобства. Одной из таких проблем является отсутствие возможности быстро добраться из точки А в точку Б. При этом воздушное пространство практически не используется. Предлагаемое решение заключается в создании системы, которая в режиме реального времени наблюдает и контролирует движение беспилотных летательных аппаратов. Такое решение приводит к полной автоматизации процесса полёта и исключает возможность воздушно-транспортных происшествий. В результате проделанной работы удалось сделать систему, которая состоит из нескольких дронов и сервера. Сервер прокладывает маршрут дронам из начальной точки в заданную по проложенным дорогам. Также в работу сервера входит логистика, благодаря которой беспилотники не сталкиваются в полёте.
<iframe width="966" height="543" src="https://www.youtube.com/embed/nq1DKjacs6U" frameborder="0" allow="accelerometer; autoplay; encrypted-media; gyroscope; picture-in-picture" allowfullscreen></iframe>
<iframe width="966" height="543" src="https://www.youtube.com/embed/QdgZ4lzPmwQ" frameborder="0" allow="accelerometer; autoplay; encrypted-media; gyroscope; picture-in-picture" allowfullscreen></iframe>
<iframe width="100%" height="433" src="https://www.youtube.com/embed/nq1DKjacs6U" frameborder="0" allow="accelerometer; autoplay; encrypted-media; gyroscope; picture-in-picture" allowfullscreen></iframe>
<iframe width="100%" height="433" src="https://www.youtube.com/embed/QdgZ4lzPmwQ" frameborder="0" allow="accelerometer; autoplay; encrypted-media; gyroscope; picture-in-picture" allowfullscreen></iframe>
## Настройка сервера
@@ -32,12 +32,12 @@ pip install -r requirements.txt
python manage.py runserver 0.0.0.0:8000
```
Чтобы перейти на веб страницу наберите в адресной строке ip адрес сервера в локальной сети и укажите порт 8000 (`http://ip:8000`).
Чтобы перейти на веб страницу наберите в адресной строке ip адрес сервера в локальной сети и укажите порт 8000 (`http://ip:8000`).
[Как узнать ip адрес устройства](https://remontka.pro/ip-adres/)
## Настройка коптеров
В первую очередь подготовьте SD-карту с образом Clever ([Инструкция](https://clever.copterexpress.com/ru/microsd_images.html))
В первую очередь подготовьте SD-карту с образом Clever ([Инструкция](image.md))
Чтобы скачать проект на Raspberry Pi в коптере выполните команду
@@ -45,7 +45,7 @@ python manage.py runserver 0.0.0.0:8000
git clone https://github.com/Tennessium/HUEX
```
Перед началом работы с системой необходимо перевести коптеры в режим клиента и подключить к сети WiFi. Вы можете воспользоваться [этим мануалом](https://clever.copterexpress.com/ru/network.html#переключение-адаптера-в-режим-клиента)
Перед началом работы с системой необходимо перевести коптеры в режим клиента и подключить к сети WiFi. Вы можете воспользоваться [этим мануалом](network.md#переключение-адаптера-в-режим-клиента)
Однако, для упрощения развертывания системы на нескольких коптреах, рекомендуется использование нашего скрипта, лежащего в папке *copter/setup/*

View File

@@ -91,4 +91,4 @@
<img src="../assets/github-pull-request-create.png" alt="GitHub Create Pull">
10. Дождитесь комментариев на свою статью, сделайте правки, если потребуется.
11. Порадуйтесь своей новой полезной статье, опубликованной на https://clever.copterexpress.com !
11. Порадуйтесь своей новой полезной статье, опубликованной на https://clever.coex.tech !

View File

@@ -9,7 +9,7 @@
## Ссылки на литературу
- [Руководство по оценке позы человека](https://blog.nanonets.com/human-pose-estimation-2d-guide/)
- [Умные беспилотники учебники](https://clever.copterexpress.com/en/)
- [Умные беспилотники учебники](https://clever.coex.tech/en/)
- [Posnet GitHub РЕПО](https://github.com/tensorflow/tfjs-models/tree/master/posenet)
- [Posnet Medium артикул](https://medium.com/tensorflow/real-time-human-pose-estimation-in-the-browser-with-tensorflow-js-7dd0bc881cd5)
- [Tensorflow.js Демонстрация](https://www.tensorflow.org/js/demos)

View File

@@ -46,7 +46,7 @@
* [Инструкция по сборке.](assemble_3.md)
* [Инструкция по настройке.](setup.md)
* [Проверочные задания.](tests.md)
* Информационные материалы на сайте https://clever.copterexpress.com.
* Информационные материалы на сайте https://clever.coex.tech.
## Промежуточный контроль

View File

@@ -27,7 +27,7 @@
> **Note** Перед осуществлением перепрошивки Pixracer не должен быть подключен к компьютеру по USB.
Для Клевера, в особенности для осуществления автономных полетов, рекомендуется использовать версию прошивки PX4 от Copter Express. Скачайте актуальную версию прошивки на GitHub — **<a class="latest-firmware v4" href="https://github.com/CopterExpress/clever/releases">скачать</a>**.
Для Клевера, в особенности для осуществления автономных полетов, рекомендуется использовать версию прошивки PX4 от Copter Express. Скачайте актуальную версию прошивки на GitHub — **<a class="latest-firmware v4" href="https://github.com/CopterExpress/Firmware/releases">скачать</a>**.
Далее загрузите прошивку в полетный контролер.

View File

@@ -90,7 +90,7 @@ print telemetry.z
```python
import math
if not math.isnan(get_telemetry().lat):
print 'Global position presents'
print 'Global position is available'
else:
print 'No global position'
```

View File

@@ -79,7 +79,7 @@ roslaunch mavros px4.launch fcu_url:=udp://@127.0.0.1:14557
> **Caution** Среда `ROS Kinetic` в изначально ориентированна для `Ubuntu (Xenial)` версии 16.04, по этому актуальность данной инструкции гарантируется только для соответственной версии операционной системы.
В первую очередь вам потребуется установить полный пакет ROS Kinetic desktop-full, инструкцию по установке вы можете найти в [статье по установке ROS](https://clever.copterexpress.com/ru/ros-install.html).
В первую очередь вам потребуется установить полный пакет ROS Kinetic desktop-full, инструкцию по установке вы можете найти в [статье по установке ROS](ros-install.md).
После того, как вы выполнили указанные выше инструкции, вам нужно проверить, есть ли в вашем пакете `ROS` все нужные пакеты.