Compare commits

...

34 Commits

Author SHA1 Message Date
Oleg Kalachev
8a5e1318c7 docs: "fix" English version link 2019-05-31 19:11:23 +03:00
Oleg Kalachev
7d6acc52e9 docs: clarify snippets a little 2019-05-31 18:37:09 +03:00
Oleg Kalachev
b850844fa2 Remove bad 17 marker from cmit aruco map 2019-05-30 22:47:18 +03:00
Alamoris
4c01e710fc aruco_pose: Add cmit aruco map 2019-05-30 19:46:35 +03:00
Oleg Kalachev
161506d89a docs: translate images to English 2019-05-30 00:54:26 +03:00
sfalexrog
bb2c2cfac9 builder: Use PWM peripheral for pigpiod 2019-05-28 21:00:28 +03:00
sfalexrog
8019712d8c Revert "aruco_map: Use two-pass solvePnP"
This reverts commit 91f6f6dd32. Additional testing revealed this "fix" to provide incorrect results.
2019-05-28 20:54:49 +03:00
Oleg Kalachev
41e9f407fd docs: fix IR connection illustration 2019-05-27 16:09:28 +03:00
sfalexrog
c8008efeac builder: Update base image and packages 2019-05-27 13:52:50 +03:00
Oleg Kalachev
c5dbf44bba docs: correct flip snippet 2019-05-25 14:34:41 +03:00
Oleg Kalachev
c0217d8aff docs: add autogenerated link to clever firmware + small fixes 2019-05-25 14:34:29 +03:00
Oleg Kalachev
ee1a493636 selfcheck.py: don't show OK if there were info messages 2019-05-24 00:29:56 +03:00
Oleg Kalachev
2a755005a6 selfcheck.py: print image version 2019-05-24 00:24:00 +03:00
Oleg Kalachev
4807db85a7 selfcheck.py: improve aruco check 2019-05-24 00:24:00 +03:00
Oleg Kalachev
82a2a5e5f7 clever.launch: remove launching arduino bridge 2019-05-24 00:24:00 +03:00
sfalexrog
73e17aeb48 builder: Add realsense packages 2019-05-23 16:50:24 +03:00
Oleg Kalachev
0af7d406bd Merge pull request #125 from sfalexrog/WIP/aruco_fix
aruco_map: Use two-pass solvePnP
2019-05-22 15:19:42 +03:00
sfalexrog
78f43ad078 builder: Update kernel version 2019-05-21 08:53:52 +03:00
Oleg Kalachev
8faa838bb9 selfcheck.py: function for printing checks info 2019-05-20 20:29:42 +03:00
Oleg Kalachev
f499608cc2 selfcheck.py: describe camera orientation 2019-05-20 18:46:48 +03:00
Oleg Kalachev
486c62f625 docs: simplify wi-fi config instructions 2019-05-20 16:54:45 +03:00
Oleg Kalachev
29b9f47eea selfcheck.py: follow PEP-8 in imports 2019-05-20 16:10:33 +03:00
Oleg Kalachev
bba9f3db76 selfcheck.py: simplify camera check 2019-05-20 16:02:47 +03:00
sfalexrog
91f6f6dd32 aruco_map: Use two-pass solvePnP
There are cases when iterative solvePnP method converges on a "wrong" camera position due to projectPoints not treating negative Z values properly.
Other methods don't seem to be affected by that, but their results differ from the iterative method slightly. By combining these two methods we
"nudge" the iterative method towards the correct camera position and get satisfactory results most of the time.

Sometimes, though, even with the "nudge" the iterative method diverges catastrophically, and this is not caught by the solver. We work around that
by assuming our camera position cannot be too far from the markers.
2019-05-20 12:29:42 +03:00
sfalexrog
ec57f7d0a3 builder: Fix git configuration 2019-05-17 11:48:16 +03:00
sfalexrog
683e06dc20 builder: Remove pymavlink definition
Rosdep repository has pymavlink definition as of 831b1b2ad5
2019-05-15 23:19:46 +03:00
sfalexrog
6dfba25d45 selfcheck.py: perform version and preflight checks (#123)
* selfcheck: Perform version and preflight checks

* selfcheck: Fail commander check if no data received

* selfcheck: Print firmware version

* selfcheck: Create publishers and subscribers globally

* selfcheck.py: add note about firmware in gitbook

* selfcheck: Move firmware version checks to FCU checks

* selfcheck: Show commander warnings

* selfcheck: Remove prompt line from received mavlink message

* clever: Add pymavlink as a ROS dependency
2019-05-15 16:51:12 +03:00
sfalexrog
ffa2f89c8e builder: Set default keyboard layout to US 2019-05-14 19:38:18 +03:00
sfalexrog
a99c381f11 builder: Install libjpeg8 manually 2019-05-14 19:26:26 +03:00
Oleg Kalachev
36d088d648 docs: that’s unneeded 2019-05-14 05:04:55 +03:00
sfalexrog
f0ab0a8e11 docs: Add MOSFET+magnet schematic 2019-05-13 19:16:42 +03:00
sfalexrog
53c2cf6998 aruco_map: map parser improvements (#118)
* aruco_map: Improve parser

* aruco_map: Use marker id for map visualization

* aruco_pose: Add parser pass test

* aruco_map: Code style

* aruco_pose: Add more test cases

* aruco_map: Better message handling

* aruco_map: Be more informative about bad lines

* aruco_map: Add failure mode tests

* aruco_map: Be less strict about map contents

* aruco_pose: Restructure tests

* aruco_map: Don't use marker id in visualization

* aruco_map: Check for marker uniqueness

* aruco_pose: Use board data to reject duplicate markers

* aruco_pose/test: Spelling fixes
2019-05-13 17:43:20 +03:00
Oleg Kalachev
ae3d3a955b docs: recommend disabling baro in LPE_FUSION for aruco VPE 2019-05-13 14:47:44 +03:00
Oleg Kalachev
2e11db0756 docs: recommend LPE for aruco VPE 2019-05-13 14:45:16 +03:00
73 changed files with 778 additions and 159 deletions

View File

@@ -216,4 +216,7 @@ target_link_libraries(aruco_pose
if (CATKIN_ENABLE_TESTING)
find_package(rostest REQUIRED)
add_rostest(test/basic.test)
add_rostest(test/test_parser_pass.test)
add_rostest(test/test_parser_empty_map.test)
add_rostest(test/test_node_failure.test)
endif()

100
aruco_pose/map/cmit.txt Normal file
View File

@@ -0,0 +1,100 @@
0 0.33 0.0 9.0 0 0 0 0
1 0.33 1.0 9.0 0 0 0 0
2 0.33 2.0 9.0 0 0 0 0
3 0.33 3.0 9.0 0 0 0 0
4 0.33 4.0 9.0 0 0 0 0
5 0.33 5.0 9.0 0 0 0 0
6 0.33 6.0 9.0 0 0 0 0
7 0.33 7.0 9.0 0 0 0 0
8 0.33 8.0 9.0 0 0 0 0
9 0.33 9.0 9.0 0 0 0 0
10 0.33 0.0 8.0 0 0 0 0
11 0.33 1.0 8.0 0 0 0 0
12 0.33 2.0 8.0 0 0 0 0
13 0.33 3.0 8.0 0 0 0 0
14 0.33 4.0 8.0 0 0 0 0
15 0.33 5.0 8.0 0 0 0 0
16 0.33 6.0 8.0 0 0 0 0
#17 0.33 7.0 8.0 0 0 0 0
18 0.33 8.0 8.0 0 0 0 0
19 0.33 9.0 8.0 0 0 0 0
20 0.33 0.0 7.0 0 0 0 0
21 0.33 1.0 7.0 0 0 0 0
22 0.33 2.0 7.0 0 0 0 0
23 0.33 3.0 7.0 0 0 0 0
24 0.33 4.0 7.0 0 0 0 0
25 0.33 5.0 7.0 0 0 0 0
26 0.33 6.0 7.0 0 0 0 0
27 0.33 7.0 7.0 0 0 0 0
28 0.33 8.0 7.0 0 0 0 0
29 0.33 9.0 7.0 0 0 0 0
30 0.33 0.0 6.0 0 0 0 0
31 0.33 1.0 6.0 0 0 0 0
32 0.33 2.0 6.0 0 0 0 0
33 0.33 3.0 6.0 0 0 0 0
34 0.33 4.0 6.0 0 0 0 0
35 0.33 5.0 6.0 0 0 0 0
36 0.33 6.0 6.0 0 0 0 0
37 0.33 7.0 6.0 0 0 0 0
38 0.33 8.0 6.0 0 0 0 0
39 0.33 9.0 6.0 0 0 0 0
40 0.33 0.0 5.0 0 0 0 0
41 0.33 1.0 5.0 0 0 0 0
42 0.33 2.0 5.0 0 0 0 0
43 0.33 3.0 5.0 0 0 0 0
44 0.33 4.0 5.0 0 0 0 0
45 0.33 5.0 5.0 0 0 0 0
46 0.33 6.0 5.0 0 0 0 0
47 0.33 7.0 5.0 0 0 0 0
48 0.33 8.0 5.0 0 0 0 0
49 0.33 9.0 5.0 0 0 0 0
50 0.33 0.0 4.0 0 0 0 0
51 0.33 1.0 4.0 0 0 0 0
52 0.33 2.0 4.0 0 0 0 0
53 0.33 3.0 4.0 0 0 0 0
54 0.33 4.0 4.0 0 0 0 0
55 0.33 5.0 4.0 0 0 0 0
56 0.33 6.0 4.0 0 0 0 0
57 0.33 7.0 4.0 0 0 0 0
58 0.33 8.0 4.0 0 0 0 0
59 0.33 9.0 4.0 0 0 0 0
60 0.33 0.0 3.0 0 0 0 0
61 0.33 1.0 3.0 0 0 0 0
62 0.33 2.0 3.0 0 0 0 0
63 0.33 3.0 3.0 0 0 0 0
64 0.33 4.0 3.0 0 0 0 0
65 0.33 5.0 3.0 0 0 0 0
66 0.33 6.0 3.0 0 0 0 0
67 0.33 7.0 3.0 0 0 0 0
68 0.33 8.0 3.0 0 0 0 0
69 0.33 9.0 3.0 0 0 0 0
70 0.33 0.0 2.0 0 0 0 0
71 0.33 1.0 2.0 0 0 0 0
72 0.33 2.0 2.0 0 0 0 0
73 0.33 3.0 2.0 0 0 0 0
74 0.33 4.0 2.0 0 0 0 0
75 0.33 5.0 2.0 0 0 0 0
76 0.33 6.0 2.0 0 0 0 0
77 0.33 7.0 2.0 0 0 0 0
78 0.33 8.0 2.0 0 0 0 0
79 0.33 9.0 2.0 0 0 0 0
80 0.33 0.0 1.0 0 0 0 0
81 0.33 1.0 1.0 0 0 0 0
82 0.33 2.0 1.0 0 0 0 0
83 0.33 3.0 1.0 0 0 0 0
84 0.33 4.0 1.0 0 0 0 0
85 0.33 5.0 1.0 0 0 0 0
86 0.33 6.0 1.0 0 0 0 0
87 0.33 7.0 1.0 0 0 0 0
88 0.33 8.0 1.0 0 0 0 0
89 0.33 9.0 1.0 0 0 0 0
90 0.33 0.0 0.0 0 0 0 0
91 0.33 1.0 0.0 0 0 0 0
92 0.33 2.0 0.0 0 0 0 0
93 0.33 3.0 0.0 0 0 0 0
94 0.33 4.0 0.0 0 0 0 0
95 0.33 5.0 0.0 0 0 0 0
96 0.33 6.0 0.0 0 0 0 0
97 0.33 7.0 0.0 0 0 0 0
98 0.33 8.0 0.0 0 0 0 0
99 0.33 9.0 0.0 0 0 0 0

View File

@@ -36,6 +36,7 @@
#include <sensor_msgs/Image.h>
#include <visualization_msgs/Marker.h>
#include <visualization_msgs/MarkerArray.h>
#include <algorithm>
#include <aruco_pose/MarkerArray.h>
#include <aruco_pose/Marker.h>
@@ -270,10 +271,50 @@ publish_debug:
std::istringstream s(line);
if (!(s >> id >> length >> x >> y >> z >> yaw >> pitch >> roll)) {
ROS_ERROR("aruco_map: cannot parse line: %s", line.c_str());
// Read first character to see whether it's a comment
char first = 0;
if (!(s >> first)) {
// No non-whitespace characters, must be a blank line
continue;
}
if (first == '#') {
ROS_DEBUG("aruco_map: Skipping line as a comment: %s", line.c_str());
continue;
} else if (isdigit(first)) {
// Put the digit back into the stream
// Note that this is a non-modifying putback, so this should work with istreams
// (see https://en.cppreference.com/w/cpp/io/basic_istream/putback)
s.putback(first);
} else {
// Probably garbage data; inform user and throw an exception, possibly killing nodelet
ROS_FATAL("aruco_map: Malformed input: %s", line.c_str());
ros::shutdown();
throw std::runtime_error("Malformed input");
}
if (!(s >> id >> length >> x >> y)) {
ROS_ERROR("aruco_map: Not enough data in line: %s; "
"Each marker must have at least id, length, x, y fields", line.c_str());
continue;
}
// Be less strict about z, yaw, pitch roll
if (!(s >> z)) {
ROS_DEBUG("aruco_map: No z coordinate provided for marker %d, assuming 0", id);
z = 0;
}
if (!(s >> yaw)) {
ROS_DEBUG("aruco_map: No yaw provided for marker %d, assuming 0", id);
yaw = 0;
}
if (!(s >> pitch)) {
ROS_DEBUG("aruco_map: No pitch provided for marker %d, assuming 0", id);
pitch = 0;
}
if (!(s >> roll)) {
ROS_DEBUG("aruco_map: No roll provided for marker %d, assuming 0", id);
roll = 0;
}
addMarker(id, length, x, y, z, yaw, pitch, roll);
}
@@ -339,6 +380,19 @@ publish_debug:
void addMarker(int id, double length, double x, double y, double z,
double yaw, double pitch, double roll)
{
// Check whether the id is in range for current dictionary
int num_markers = board_->dictionary->bytesList.rows;
if (num_markers <= id) {
ROS_ERROR("aruco_map: Marker id %d is not in dictionary; current dictionary contains %d markers. "
"Please see https://github.com/CopterExpress/clever/blob/master/aruco_pose/README.md#parameters for details",
id, num_markers);
return;
}
// Check if marker is already in the board
if (std::count(board_->ids.begin(), board_->ids.end(), id) > 0) {
ROS_ERROR("aruco_map: Marker id %d is already in the map", id);
return;
}
// Create transform
tf::Quaternion q;
q.setRPY(roll, pitch, yaw);

View File

@@ -1,7 +1,11 @@
# Default markers
1 0.33 0 0 0 0 0 0
2 0.33 1 0 0 0 0 0
3 0.33 0 1 0 0 0 0
4 0.33 1 1 0 0 0 0
# Marker with non-zero yaw rotation
10 0.5 0.5 2 0 1.2 0 0
# Marker with non-zero pitch and roll rotation
11 0.2 0.5 0.5 0 0.0 -1 1
# Marker with yaw, pitch and roll rotation
12 0.4 0.2 0.5 0 0.1 -1.2 -0.5

View File

@@ -0,0 +1,27 @@
#!/usr/bin/env python
import sys
import unittest
import json
import rospy
import rostest
from geometry_msgs.msg import PoseWithCovarianceStamped
from sensor_msgs.msg import Image
from aruco_pose.msg import MarkerArray
from visualization_msgs.msg import MarkerArray as VisMarkerArray
class TestArucoMapPass(unittest.TestCase):
def setUp(self):
rospy.init_node('test_parser_fail', anonymous=True)
def test_node_failure(self):
try:
markers = rospy.wait_for_message('aruco_map/visualization', VisMarkerArray, timeout=5)
did_post_message = True
except rospy.exceptions.ROSException:
did_post_message = False
self.assertFalse(did_post_message)
rostest.rosrun('aruco_pose', 'test_aruco_map', TestArucoMapPass, sys.argv)

View File

@@ -0,0 +1,13 @@
<launch>
<node pkg="nodelet" type="nodelet" name="nodelet_manager" args="manager"/>
<node name="aruco_map" pkg="nodelet" type="nodelet" args="load aruco_pose/aruco_map nodelet_manager" clear_params="true">
<remap from="image_raw" to="main_camera/image_raw"/>
<remap from="camera_info" to="main_camera/camera_info"/>
<remap from="markers" to="aruco_detect/markers"/>
<param name="type" value="map"/>
<param name="map" value="$(find aruco_pose)/test/test_node_failure.txt"/>
</node>
<test test-name="test_aruco_map_fail_dict" pkg="aruco_pose" type="test_node_failure.py"/>
</launch>

View File

@@ -0,0 +1,4 @@
# Any garbage data (pretty much anything apart from a comment starting with a hash starting
# with a hash sign or a number) will be interpreted as garbage data; the node should fail
# after reading it.
// Don't try to put your comments this way, it will kill your node!

View File

@@ -0,0 +1,24 @@
#!/usr/bin/env python
import sys
import unittest
import json
import rospy
import rostest
from geometry_msgs.msg import PoseWithCovarianceStamped
from sensor_msgs.msg import Image
from aruco_pose.msg import MarkerArray
from visualization_msgs.msg import MarkerArray as VisMarkerArray
class TestArucoMapPass(unittest.TestCase):
def setUp(self):
rospy.init_node('test_parser_fail', anonymous=True)
def test_node_failure(self):
markers = rospy.wait_for_message('aruco_map/visualization', VisMarkerArray, timeout=5)
self.assertEquals(len(markers.markers), 0)
rostest.rosrun('aruco_pose', 'test_aruco_map', TestArucoMapPass, sys.argv)

View File

@@ -0,0 +1,13 @@
<launch>
<node pkg="nodelet" type="nodelet" name="nodelet_manager" args="manager"/>
<node name="aruco_map" pkg="nodelet" type="nodelet" args="load aruco_pose/aruco_map nodelet_manager" clear_params="true">
<remap from="image_raw" to="main_camera/image_raw"/>
<remap from="camera_info" to="main_camera/camera_info"/>
<remap from="markers" to="aruco_detect/markers"/>
<param name="type" value="map"/>
<param name="map" value="$(find aruco_pose)/test/test_parser_empty_map.txt"/>
</node>
<test test-name="test_aruco_map_incomplete" pkg="aruco_pose" type="test_parser_empty_map.py"/>
</launch>

View File

@@ -0,0 +1,6 @@
# Failing markers: Not enough parameters to add a marker
1
2 1
3 0.5 1
# Failing markers: Marker IDs outside of dictionary range
1001 1 1 0

View File

@@ -0,0 +1,75 @@
#!/usr/bin/env python
import sys
import unittest
import json
import rospy
import rostest
from geometry_msgs.msg import PoseWithCovarianceStamped
from sensor_msgs.msg import Image
from aruco_pose.msg import MarkerArray
from visualization_msgs.msg import MarkerArray as VisMarkerArray
class TestArucoMapPass(unittest.TestCase):
def setUp(self):
rospy.init_node('test_parser_pass', anonymous=True)
def test_markers(self):
markers = rospy.wait_for_message('aruco_map/visualization', VisMarkerArray, timeout=5)
self.assertEqual(len(markers.markers), 6)
# FIXME: visual marker id is not ArUco marker id
# self.assertEqual(markers.markers[0].id, 1)
# self.assertEqual(markers.markers[1].id, 2)
# self.assertEqual(markers.markers[2].id, 3)
# self.assertEqual(markers.markers[3].id, 4)
self.assertAlmostEqual(markers.markers[0].pose.position.x, 0, places=7)
self.assertAlmostEqual(markers.markers[0].pose.position.y, 0, places=7)
self.assertAlmostEqual(markers.markers[0].pose.position.z, 0, places=7)
self.assertAlmostEqual(markers.markers[1].pose.position.x, 1, places=7)
self.assertAlmostEqual(markers.markers[1].pose.position.y, 1, places=7)
self.assertAlmostEqual(markers.markers[1].pose.position.z, 1, places=7)
self.assertAlmostEqual(markers.markers[2].pose.position.x, 1, places=7)
self.assertAlmostEqual(markers.markers[2].pose.position.y, 0, places=7)
self.assertAlmostEqual(markers.markers[2].pose.position.z, 0.5, places=7)
self.assertAlmostEqual(markers.markers[3].pose.position.x, 0, places=7)
self.assertAlmostEqual(markers.markers[3].pose.position.y, 1, places=7)
self.assertAlmostEqual(markers.markers[3].pose.position.z, 0, places=7)
self.assertAlmostEqual(markers.markers[4].pose.position.x, 1, places=7)
self.assertAlmostEqual(markers.markers[4].pose.position.y, 0.5, places=7)
self.assertAlmostEqual(markers.markers[4].pose.position.z, 0, places=7)
self.assertAlmostEqual(markers.markers[5].pose.position.x, 2.2, places=7)
self.assertAlmostEqual(markers.markers[5].pose.position.y, 0.2, places=7)
self.assertAlmostEqual(markers.markers[5].pose.position.z, 0, places=7)
self.assertAlmostEqual(markers.markers[0].scale.x, 0.33, places=7)
self.assertAlmostEqual(markers.markers[0].scale.y, 0.33, places=7)
self.assertAlmostEqual(markers.markers[1].scale.x, 0.225, places=7)
self.assertAlmostEqual(markers.markers[1].scale.y, 0.225, places=7)
self.assertAlmostEqual(markers.markers[2].scale.x, 0.45, places=7)
self.assertAlmostEqual(markers.markers[2].scale.y, 0.45, places=7)
self.assertAlmostEqual(markers.markers[3].scale.x, 0.15, places=7)
self.assertAlmostEqual(markers.markers[3].scale.y, 0.15, places=7)
self.assertAlmostEqual(markers.markers[4].scale.x, 0.25, places=7)
self.assertAlmostEqual(markers.markers[4].scale.y, 0.25, places=7)
self.assertAlmostEqual(markers.markers[5].scale.x, 0.35, places=7)
self.assertAlmostEqual(markers.markers[5].scale.y, 0.35, places=7)
def test_map_image(self):
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')
# def test_transforms(self):
# pass
rostest.rosrun('aruco_pose', 'test_aruco_map', TestArucoMapPass, sys.argv)

View File

@@ -0,0 +1,13 @@
<launch>
<node pkg="nodelet" type="nodelet" name="nodelet_manager" args="manager"/>
<node name="aruco_map" pkg="nodelet" type="nodelet" args="load aruco_pose/aruco_map nodelet_manager" clear_params="true">
<remap from="image_raw" to="main_camera/image_raw"/>
<remap from="camera_info" to="main_camera/camera_info"/>
<remap from="markers" to="aruco_detect/markers"/>
<param name="type" value="map"/>
<param name="map" value="$(find aruco_pose)/test/test_parser_pass.txt"/>
</node>
<test test-name="test_aruco_map" pkg="aruco_pose" type="test_parser_pass.py"/>
</launch>

View File

@@ -0,0 +1,23 @@
# Parser test #1 - correct file
# 1. Commentary test
#Commentary text without space after pound sign
# Commentary text with space after pound sign
# Commentary text with spaces before pound sign
# Commentary text with tab before pound sign
# Text with tabs before pound sign
# Empty line test:
# All-whitespace line test:
# 2. Default coordinates test
# Fully filled marker description, tab-delimited:
1 0.33 0 0 0 0 0 0
# Fully filled marker description, space-delimited:
2 0.225 1 1 1 0 0 0
# Default roll, pitch, yaw angles
3 0.45 1 0 0.5
# Default roll, pitch, yaw, z
4 0.15 0 1
# Inline commentary
5 0.25 1 0.5# Comment straight after digit
6 0.35 2.2 0.2 # Comment with a space after digit

View File

@@ -541,3 +541,12 @@ tf2_web_republisher:
image_publisher:
debian:
stretch: [ros-kinetic-image-publisher]
raspberry-kernel-headers:
debian:
stretch: [raspberry-kernel-headers]
ddynamic_reconfigure:
debian:
stretch: [ros-kinetic-ddynamic-reconfigure]
realsense2_camera:
debian:
stretch: [ros-kinetic-realsense2-camera]

View File

@@ -0,0 +1,8 @@
[Unit]
Description=Daemon required to control GPIO pins via pigpio
[Service]
ExecStart=/usr/bin/pigpiod -l -t 0 -x 0x0FFF3FF0
ExecStop=/bin/systemctl kill pigpiod
Type=forking
[Install]
WantedBy=multi-user.target

View File

@@ -11,7 +11,7 @@
set -e # Exit immidiately on non-zero result
SOURCE_IMAGE="https://downloads.raspberrypi.org/raspbian_lite/images/raspbian_lite-2018-11-15/2018-11-13-raspbian-stretch-lite.zip"
SOURCE_IMAGE="https://downloads.raspberrypi.org/raspbian_lite/images/raspbian_lite-2019-04-09/2019-04-08-raspbian-stretch-lite.zip"
export DEBIAN_FRONTEND=${DEBIAN_FRONTEND:='noninteractive'}
export LANG=${LANG:='C.UTF-8'}
@@ -109,6 +109,7 @@ ${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/roscore
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/roscore.service' '/lib/systemd/system/'
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/kinetic-rosdep-clever.yaml' '/etc/ros/rosdep/'
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/ros_python_paths' '/etc/sudoers.d/'
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/pigpiod.service' '/lib/systemd/system/'
# ${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/kinetic-ros-clever.rosinstall' '/home/pi/ros_catkin_ws/'
# Add PX4 udev rules
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/99-px4fmu.rules' '/lib/udev/rules.d/'

View File

@@ -138,6 +138,10 @@ fi
export ROS_IP='127.0.0.1' # needed for running tests
echo_stamp "Reconfiguring Clever repository for simplier unshallowing"
cd /home/pi/catkin_ws/src/clever
git config remote.origin.fetch "+refs/heads/*:refs/remotes/origin/*"
echo_stamp "Installing CLEVER" \
&& cd /home/pi/catkin_ws/src/clever \
&& git status \

View File

@@ -86,7 +86,7 @@ dnsmasq=2.76-5+rpt1+deb9u1 \
tmux=2.3-4 \
vim=2:8.0.0197-4+deb9u1 \
cmake=3.7.2-1 \
libjpeg8-dev=8d1-2 \
libjpeg8=8d1-2 \
tcpdump \
ltrace \
libpoco-dev=1.7.6+dfsg1-5+deb9u1 \
@@ -108,7 +108,14 @@ python-systemd \
|| (echo_stamp "Some packages wasn't installed!" "ERROR"; exit 1)
echo_stamp "Updating kernel to fix camera bug"
apt-get install --no-install-recommends -y raspberrypi-kernel=1.20190401-1
apt-get install --no-install-recommends -y \
raspberrypi-kernel=1.20190517-1 \
raspberrypi-bootloader=1.20190517-1 \
libraspberrypi-bin=1.20190517-1 \
libraspberrypi-dev=1.20190517-1 \
libraspberrypi0=1.20190517-1 \
wireless-regdb=2018.05.09-0~rpt1 \
wpasupplicant=2:2.6-21~bpo9~rpt1
# Deny byobu to check available updates
sed -i "s/updates_available//" /usr/share/byobu/status/status
@@ -156,6 +163,9 @@ syntax on
autocmd BufNewFile,BufRead *.launch set syntax=xml
EOF
echo_stamp "Change default keyboard layout to US"
sed -i 's/XKBLAYOUT="gb"/XKBLAYOUT="us"/g' /etc/default/keyboard
echo_stamp "Attempting to kill dirmngr"
gpgconf --kill dirmngr
# dirmngr is only used by apt-key, so we can safely kill it.

View File

@@ -9,7 +9,6 @@
<arg name="aruco" default="false"/>
<arg name="rc" default="true"/>
<arg name="rangefinder_vl53l1x" default="false"/>
<arg name="arduino" default="false"/>
<!-- mavros -->
<include file="$(find clever)/launch/mavros.launch">
@@ -68,9 +67,4 @@
<!-- rc backend -->
<node name="rc" pkg="clever" type="rc" output="screen" if="$(arg rc)"/>
<!-- Arduino bridge -->
<node pkg="rosserial_python" type="serial_node.py" name="serial_node" output="screen" if="$(arg arduino)">
<param name="port" value="/dev/serial/by-id/usb-1a86_USB2.0-Serial-if00-port0"/>
</node>
</launch>

View File

@@ -37,6 +37,7 @@
<depend>mjpg-streamer</depend>
<depend>rosbridge_server</depend>
<depend>web_video_server</depend>
<exec_depend>python-pymavlink</exec_depend>
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->

View File

@@ -1,6 +1,5 @@
flask==0.12.3
docopt==0.6.2
geopy==1.11.0
pymavlink==2.2.10
smbus2==0.2.1
VL53L1X==0.0.2

View File

@@ -4,16 +4,21 @@ import math
import subprocess
import re
import traceback
from threading import Event
import numpy
import rospy
from systemd import journal
import tf2_ros
import tf2_geometry_msgs
from pymavlink import mavutil
from std_srvs.srv import Trigger
from sensor_msgs.msg import Image, CameraInfo, NavSatFix, Imu, Range
from mavros_msgs.msg import State, OpticalFlowRad
from mavros_msgs.msg import State, OpticalFlowRad, Mavlink
from mavros_msgs.srv import ParamGet
from geometry_msgs.msg import PoseStamped, TwistStamped, PoseWithCovarianceStamped
from geometry_msgs.msg import PoseStamped, TwistStamped, PoseWithCovarianceStamped, Vector3Stamped
import tf.transformations as t
from aruco_pose.msg import MarkerArray
from systemd import journal
from mavros import mavlink
# TODO: check attitude is present
@@ -28,28 +33,41 @@ from systemd import journal
rospy.init_node('selfcheck')
tf_buffer = tf2_ros.Buffer()
tf_listener = tf2_ros.TransformListener(tf_buffer)
failures = []
infos = []
current_check = None
def failure(text, *args):
failures.append(text % args)
msg = text % args
rospy.logwarn('%s: %s', current_check, msg)
failures.append(msg)
def info(text, *args):
msg = text % args
rospy.loginfo('%s: %s', current_check, msg)
infos.append(msg)
def check(name):
def inner(fn):
def wrapper(*args, **kwargs):
failures[:] = []
infos[:] = []
global current_check
current_check = name
try:
fn(*args, **kwargs)
for f in failures:
rospy.logwarn('%s: %s', name, f)
except Exception as e:
for f in failures:
rospy.logwarn('%s: %s', name, f)
traceback.print_exc()
rospy.logerr('%s: exception occurred', name)
return
if not failures:
if not failures and not infos:
rospy.loginfo('%s: OK', name)
return wrapper
return inner
@@ -73,36 +91,116 @@ def get_param(name):
return res.value.real
recv_event = Event()
link = mavutil.mavlink.MAVLink('', 255, 1)
mavlink_pub = rospy.Publisher('mavlink/to', Mavlink, queue_size=1)
mavlink_recv = ''
def mavlink_message_handler(msg):
global mavlink_recv
if msg.msgid == 126:
mav_bytes_msg = mavlink.convert_to_bytes(msg)
mav_msg = link.decode(mav_bytes_msg)
mavlink_recv += ''.join(chr(x) for x in mav_msg.data[:mav_msg.count])
if 'nsh>' in mavlink_recv:
# Remove the last line, including newline before prompt
mavlink_recv = mavlink_recv[:mavlink_recv.find('nsh>') - 1]
recv_event.set()
mavlink_sub = rospy.Subscriber('mavlink/from', Mavlink, mavlink_message_handler)
# FIXME: not sleeping here still breaks things
rospy.sleep(0.5)
def mavlink_exec(cmd, timeout=3.0):
global mavlink_recv
mavlink_recv = ''
recv_event.clear()
if not cmd.endswith('\n'):
cmd += '\n'
msg = mavutil.mavlink.MAVLink_serial_control_message(
device=mavutil.mavlink.SERIAL_CONTROL_DEV_SHELL,
flags=mavutil.mavlink.SERIAL_CONTROL_FLAG_RESPOND | mavutil.mavlink.SERIAL_CONTROL_FLAG_EXCLUSIVE |
mavutil.mavlink.SERIAL_CONTROL_FLAG_MULTI,
timeout=3,
baudrate=0,
count=len(cmd),
data=map(ord, cmd.ljust(70, '\0')))
msg.pack(link)
ros_msg = mavlink.convert_to_rosmsg(msg)
mavlink_pub.publish(ros_msg)
recv_event.wait(timeout)
return mavlink_recv
@check('FCU')
def check_fcu():
try:
state = rospy.wait_for_message('mavros/state', State, timeout=3)
if not state.connected:
failure('no connection to the FCU (check wiring)')
return
# Make sure the console is available to us
mavlink_exec('\n')
version_str = mavlink_exec('ver all')
if version_str == '':
info('no version data available from SITL')
r = re.compile(r'^FW (git tag|version): (v?\d\.\d\.\d.*)$')
is_clever_firmware = False
for ver_line in version_str.split('\n'):
match = r.search(ver_line)
if match is not None:
field, version = match.groups()
info('firmware %s: %s' % (field, version))
if 'clever' in version:
is_clever_firmware = True
if not is_clever_firmware:
failure('not running Clever PX4 firmware, check http://clever.copterexpress.com/firmware.html')
est = get_param('SYS_MC_EST_GROUP')
if est == 1:
rospy.loginfo('Selected estimator: LPE')
info('selected estimator: LPE')
fuse = get_param('LPE_FUSION')
if fuse & (1 << 4):
rospy.loginfo('LPE_FUSION: land detector fusion is enabled')
info('LPE_FUSION: land detector fusion is enabled')
else:
rospy.loginfo('LPE_FUSION: land detector fusion is disabled')
info('LPE_FUSION: land detector fusion is disabled')
if fuse & (1 << 7):
rospy.loginfo('LPE_FUSION: barometer fusion is enabled')
info('LPE_FUSION: barometer fusion is enabled')
else:
rospy.loginfo('LPE_FUSION: barometer fusion is disabled')
info('LPE_FUSION: barometer fusion is disabled')
elif est == 2:
rospy.loginfo('Selected estimator: EKF2')
info('selected estimator: EKF2')
else:
failure('Unknown selected estimator: %s', est)
failure('unknown selected estimator: %s', est)
except rospy.ROSException:
failure('no MAVROS state (check wiring)')
@check('Camera')
def describe_direction(v):
if v.x > 0.9:
return 'forward'
elif v.x < - 0.9:
return 'backward'
elif v.y > 0.9:
return 'left'
elif v.y < -0.9:
return 'right'
elif v.z > 0.9:
return 'upward'
elif v.z < -0.9:
return 'downward'
else:
return None
def check_camera(name):
try:
img = rospy.wait_for_message(name + '/image_raw', Image, timeout=1)
@@ -110,28 +208,86 @@ def check_camera(name):
failure('%s: no images (is the camera connected properly?)', name)
return
try:
info = rospy.wait_for_message(name + '/camera_info', CameraInfo, timeout=1)
camera_info = rospy.wait_for_message(name + '/camera_info', CameraInfo, timeout=1)
except rospy.ROSException:
failure('%s: no calibration info', name)
return
if img.width != info.width:
failure('%s: calibration width doesn\'t match image width (%d != %d)', name, info.width, img.width)
if img.height != info.height:
failure('%s: calibration height doesn\'t match image height (%d != %d))', name, info.height, img.height)
if img.width != camera_info.width:
failure('%s: calibration width doesn\'t match image width (%d != %d)', name, camera_info.width, img.width)
if img.height != camera_info.height:
failure('%s: calibration height doesn\'t match image height (%d != %d))', name, camera_info.height, img.height)
try:
optical = Vector3Stamped()
optical.header.frame_id = img.header.frame_id
optical.vector.z = 1
cable = Vector3Stamped()
cable.header.frame_id = img.header.frame_id
cable.vector.y = 1
optical = describe_direction(tf_buffer.transform(optical, 'base_link').vector)
cable = describe_direction(tf_buffer.transform(cable, 'base_link').vector)
if not optical or not cable:
info('%s: custom camera orientation detected', name)
else:
info('camera is oriented %s, camera cable goes %s', optical, cable)
except tf2_ros.TransformException:
failure('cannot transform from base_link to camera frame')
@check('ArUco detector')
@check('Main camera')
def check_main_camera():
check_camera('main_camera')
def is_process_running(binary, exact=False, full=False):
try:
args = ['pgrep']
if exact:
args.append('-x') # match exactly with the command name
if full:
args.append('-f') # use full process name to match
args.append(binary)
subprocess.check_output(args)
return True
except subprocess.CalledProcessError:
return False
@check('ArUco markers')
def check_aruco():
try:
rospy.wait_for_message('aruco_detect/markers', MarkerArray, timeout=1)
except rospy.ROSException:
failure('no markers detection')
if is_process_running('aruco_detect', full=True):
info('aruco_detect/length = %g m', rospy.get_param('aruco_detect/length'))
known_tilt = rospy.get_param('aruco_detect/known_tilt')
if known_tilt == 'map':
known_tilt += ' (ALL markers are on the floor)'
elif known_tilt == 'map_flipped':
known_tilt += ' (ALL markers are on the ceiling)'
info('aruco_detector/known_tilt = %s', known_tilt)
try:
rospy.wait_for_message('aruco_detect/markers', MarkerArray, timeout=1)
except rospy.ROSException:
failure('no markers detection')
return
else:
info('aruco_detect is not running')
return
try:
rospy.wait_for_message('aruco_map/pose', PoseWithCovarianceStamped, timeout=1)
except rospy.ROSException:
failure('no map detection')
if is_process_running('aruco_map', full=True):
known_tilt = rospy.get_param('aruco_map/known_tilt')
if known_tilt == 'map':
known_tilt += ' (marker\'s map is on the floor)'
elif known_tilt == 'map_flipped':
known_tilt += ' (marker\'s map is on the ceiling)'
info('aruco_map/known_tilt = %s', known_tilt)
try:
rospy.wait_for_message('aruco_map/pose', PoseWithCovarianceStamped, timeout=1)
except rospy.ROSException:
failure('no map detection')
else:
info('aruco_map is not running')
@check('Vision position estimate')
@@ -160,14 +316,14 @@ def check_vpe():
if vision_yaw_w == 0:
failure('vision yaw weight is zero, change ATT_W_EXT_HDG parameter')
else:
rospy.loginfo('Vision yaw weight: %.2f', vision_yaw_w)
info('Vision yaw weight: %.2f', vision_yaw_w)
fuse = get_param('LPE_FUSION')
if not fuse & (1 << 2):
failure('vision position fusion is disabled, change LPE_FUSION parameter')
delay = get_param('LPE_VIS_DELAY')
if delay != 0:
failure('LPE_VIS_DELAY parameter is %s, but it should be zero', delay)
rospy.loginfo('LPE_VIS_XY is %.2f m, LPE_VIS_Z is %.2f m', get_param('LPE_VIS_XY'), get_param('LPE_VIS_Z'))
info('LPE_VIS_XY is %.2f m, LPE_VIS_Z is %.2f m', get_param('LPE_VIS_XY'), get_param('LPE_VIS_Z'))
elif est == 2:
fuse = get_param('EKF2_AID_MASK')
if not fuse & (1 << 3):
@@ -177,7 +333,7 @@ def check_vpe():
delay = get_param('EKF2_EV_DELAY')
if delay != 0:
failure('EKF2_EV_DELAY is %.2f, but it should be zero', delay)
rospy.loginfo('EKF2_EVA_NOISE is %.3f, EKF2_EVP_NOISE is %.3f',
info('EKF2_EVA_NOISE is %.3f, EKF2_EVP_NOISE is %.3f',
get_param('EKF2_EVA_NOISE'),
get_param('EKF2_EVP_NOISE'))
@@ -296,7 +452,7 @@ def check_optical_flow():
if not numpy.isclose(scale, 1.0):
failure('LPE_FLW_SCALE parameter is %.2f, but it should be 1.0', scale)
rospy.loginfo('LPE_FLW_QMIN is %s, LPE_FLW_R is %.4f, LPE_FLW_RR is %.4f, SENS_FLOW_MINHGT is %.3f, SENS_FLOW_MAXHGT is %.3f',
info('LPE_FLW_QMIN is %s, LPE_FLW_R is %.4f, LPE_FLW_RR is %.4f, SENS_FLOW_MINHGT is %.3f, SENS_FLOW_MAXHGT is %.3f',
get_param('LPE_FLW_QMIN'),
get_param('LPE_FLW_R'),
get_param('LPE_FLW_RR'),
@@ -309,7 +465,7 @@ def check_optical_flow():
delay = get_param('EKF2_OF_DELAY')
if delay != 0:
failure('EKF2_OF_DELAY is %.2f, but it should be zero', delay)
rospy.loginfo('EKF2_OF_QMIN is %s, EKF2_OF_N_MIN is %.4f, EKF2_OF_N_MAX is %.4f, SENS_FLOW_MINHGT is %.3f, SENS_FLOW_MAXHGT is %.3f',
info('EKF2_OF_QMIN is %s, EKF2_OF_N_MIN is %.4f, EKF2_OF_N_MAX is %.4f, SENS_FLOW_MINHGT is %.3f, SENS_FLOW_MAXHGT is %.3f',
get_param('EKF2_OF_QMIN'),
get_param('EKF2_OF_N_MIN'),
get_param('EKF2_OF_N_MAX'),
@@ -343,21 +499,21 @@ def check_rangefinder():
if est == 1:
fuse = get_param('LPE_FUSION')
if not fuse & (1 << 5):
rospy.loginfo('"pub agl as lpos down" in LPE_FUSION is disabled, NOT operating over flat surface')
info('"pub agl as lpos down" in LPE_FUSION is disabled, NOT operating over flat surface')
else:
rospy.loginfo('"pub agl as lpos down" in LPE_FUSION is enabled, operating over flat surface')
info('"pub agl as lpos down" in LPE_FUSION is enabled, operating over flat surface')
elif est == 2:
hgt = get_param('EKF2_HGT_MODE')
if hgt != 2:
rospy.loginfo('EKF2_HGT_MODE != Range sensor, NOT operating over flat surface')
info('EKF2_HGT_MODE != Range sensor, NOT operating over flat surface')
else:
rospy.loginfo('EKF2_HGT_MODE = Range sensor, operating over flat surface')
info('EKF2_HGT_MODE = Range sensor, operating over flat surface')
aid = get_param('EKF2_RNG_AID')
if aid != 1:
rospy.loginfo('EKF2_RNG_AID != 1, range sensor aiding disabled')
info('EKF2_RNG_AID != 1, range sensor aiding disabled')
else:
rospy.loginfo('EKF2_RNG_AID = 1, range sensor aiding enabled')
info('EKF2_RNG_AID = 1, range sensor aiding enabled')
@check('Boot duration')
@@ -411,14 +567,42 @@ def check_clever_service():
failure(error)
@check('Image')
def check_image():
info('version: %s', open('/etc/clever_version').read().strip())
@check('Preflight status')
def check_preflight_status():
# Make sure the console is available to us
mavlink_exec('\n')
cmdr_output = mavlink_exec('commander check')
if cmdr_output == '':
failure('No data from FCU')
return
cmdr_lines = cmdr_output.split('\n')
r = re.compile(r'^(.*)(Preflight|Prearm) check: (.*)')
for line in cmdr_lines:
if 'WARN' in line:
failure(line[line.find(']') + 2:])
continue
match = r.search(line)
if match is not None:
check_status = match.groups()[2]
if check_status != 'OK':
failure(' '.join([match.groups()[1], 'check:', check_status]))
def selfcheck():
check_image()
check_clever_service()
check_fcu()
check_imu()
check_local_position()
check_velocity()
check_global_position()
check_camera('main_camera')
check_preflight_status()
check_main_camera()
check_aruco()
check_simpleoffboard()
check_optical_flow()

Binary file not shown.

Before

Width:  |  Height:  |  Size: 83 KiB

After

Width:  |  Height:  |  Size: 83 KiB

BIN
docs/assets/en/1_10.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 272 KiB

BIN
docs/assets/en/1_12.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 27 KiB

BIN
docs/assets/en/1_13.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 79 KiB

BIN
docs/assets/en/1_5.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 143 KiB

BIN
docs/assets/en/1_6.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 15 KiB

BIN
docs/assets/en/1_7.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 14 KiB

BIN
docs/assets/en/1_8.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 15 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 268 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 29 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 431 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 656 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 350 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 683 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 305 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 265 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 171 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 318 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 102 KiB

BIN
docs/assets/en/fpv_1.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 61 KiB

BIN
docs/assets/en/fpv_2.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 224 KiB

BIN
docs/assets/en/fpv_3.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 627 KiB

BIN
docs/assets/en/fpv_4.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 467 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 228 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 70 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 61 KiB

BIN
docs/assets/en/table.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 52 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 140 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 11 KiB

View File

@@ -27,4 +27,4 @@ Using Fig. 1a, 1b, 2a, 2b, map its own control signal to each motor, and connect
For example, motor M3 that rotates counter-clockwise (top left corner) is controlled by signal S4 (green wire). It is connected to port 3.
![Connecting 4 in 1 ESCs](../assets/cl3_connectionESC4in1.jpg)
![Connecting 4 in 1 ESCs](../assets/en/cl3_connectionESC4in1.jpg)

View File

@@ -154,7 +154,7 @@ Solder the prepared wires of the motors to the pads of ESC.
* Length 7 cm (XT60 pin power connector) - 1 red, 1 black
* Length 9 cm (XT60 socket power connector) - 1 red, 1 black
![Preparing wires for the power connector](../assets/cutwire14AWG.jpg)
![Preparing wires for the power connector](../assets/en/cutwire14AWG.jpg)
#### Preparing XT60 pin and XT60 socket high-power connectors
@@ -178,7 +178,7 @@ Solder the prepared wires of the motors to the pads of ESC.
3. Remove the 3rd (orange) wire from the connector, since it is not needed.
4. The length of the remaining black and red wires should be 10 12 cm.
![Installation of the 5V connector](../assets/mount5vconnector.jpg)
![Installation of the 5V connector](../assets/en/mount5vconnector.jpg)
### Installation of the power distribution board
@@ -204,7 +204,7 @@ Check CLOSED CONDITION of the following circuits (presence of the multimeter sou
1. [Blanch*] (zap.md) the contact pads of the power board
2. Using a multimeter, check absence of contact closure on the PCB (check continuity)
![ After-soldering check](../assets/zapPDBtest.jpg)
![ After-soldering check](../assets/en/zapPDBtest.jpg)
To make solder neatly fill the entire pad, it should be warmed up. For this purpose, hold the tip of the soldering gun to the contact pad for 2 seconds (or more if needed)
@@ -279,7 +279,7 @@ IMPORTANT NOTE about polarity
#### SAFETY when working with the battery
![SAFETY when working with the battery](../assets/safetyPower.png)
![SAFETY when working with the battery](../assets/en/safetyPower.png)
#### Enabling the transmitter
@@ -337,7 +337,7 @@ should be increased up to 4 5.
2. Motors to MAIN OUT ports 1,2,3,4, according to the circuit diagram
3. Power by PDB (5V/VCC) to any port except for SB (SBUS)
![Connecting the flight controller](../assets/connectionPixhawk.png)
![Connecting the flight controller](../assets/en/connectionPixhawk.png)
### ESC assembly

View File

@@ -14,11 +14,11 @@ TODO
## Additional equipment
![Additional equipment](../assets/additonal_eqipment.jpg)
![Additional equipment](../assets/en/additonal_eqipment.jpg)
## Conventional symbols
![Conventional symbols](../assets/conditional_refer.jpg)
![Conventional symbols](../assets/en/conditional_refer.jpg)
## Installation of motors
@@ -36,7 +36,7 @@ TODO
Cut the remaining part of the clamp (tie wrap) with scissors.
![Preparation of motors](../assets/cl3_prepareMotors.JPG)
![Preparation of motors](../assets/en/cl3_prepareMotors.JPG)
## Installation of frame elements
@@ -45,7 +45,7 @@ TODO
3. Attach the assembled unit to the frame with М3х16 screws, complying with the layout.
4. Install the frame for the LED strip, using the slots in the leg holders.
![Legs installation on the frame](../assets/cl3_mountElements.JPG)
![Legs installation on the frame](../assets/en/cl3_mountElements.JPG)
## Installation of the BEC voltage converter (to be soldered and tested)
@@ -93,7 +93,7 @@ TODO
Black -> GND
Blue -> Din
![Installation of the BEC voltage Converter](../assets/cl3_mountBEC.JPG)
![Installation of the BEC voltage Converter](../assets/en/cl3_mountBEC.JPG)
## Installation of the 4 in 1 ESC board and the PDB power-board
@@ -213,7 +213,7 @@ article [remote faults](radioerrors.md).
5. Install the legs into the mounts (4 pcs).
![Mounting the RPi camera](../assets/cl3_mountRpiCamera.JPG)
![Mounting the RPi camera](../assets/en/cl3_mountRpiCamera.JPG)
## Installation of the remaining structural elements

View File

@@ -13,4 +13,4 @@ The Rate Pitch and Rate Roll parameters should be the same.
YAW parameters should be changed individually, according to the above instruction (usually the yaw doesn't require serious adjustment, you may leave it default).
![ROLL oscillations](../assets/oscillRoll.jpg)
![ROLL oscillations](../assets/en/oscillRoll.jpg)

View File

@@ -11,7 +11,7 @@
\* The distance between the power distribution board and the estimated location of the camera should be determined in advance!
![FPV1](../assets/fpv_1.png)
![FPV1](../assets/en/fpv_1.png)
## Preparation of the transmitter
@@ -26,20 +26,20 @@ The same procedure applies here:
\* The distance between the power distribution board and the estimated location of the transmitter should be determined in advance!
![FPV2](../assets/fpv_2.png)
![FPV2](../assets/en/fpv_2.png)
## Connection of FPV
Prepared connectors are to be inserted into appropriate sockets, and power wires are to be soldered to the power distribution board according to the circuit diagram:
![FPV3](../assets/fpv_3.png)
![FPV3](../assets/en/fpv_3.png)
> **Warning** In this circuit diagram, the camera is powered from 12 V (however, it is possible to use 5 V).
> The transmitter is powered from the ESC power (however, it is possible to use 12 V).
## Installing FPV components
![FPV4](../assets/fpv_4.png)
![FPV4](../assets/en/fpv_4.png)
The following may be used as fastening materials:

View File

@@ -69,7 +69,7 @@ Control
The copter is controlled from a transmitter that sends commands to the radio receiver. The transmitter is powered by batteries, and the radio receiver is powered from the flight controller. The communication is often one-way, from the transmitter to the receiver. The receiver is connected to the flight controller with at least five wires which are used for transmitting the turn signals around 3 axes, the throttle command, and the flight mode command.
![Control](../assets/1_5.png)
![Control](../assets/en/1_5.png)
**Throttle** — translated as "throttle", "thrust", or "gas" in everyday life. A multicopter throttle is the mean arithmetical between the rotation speeds of all motors is it more the throttle, the higher the total thrust of the engines, and the stronger they pull the copter upwards (in other words, "Step on it" means the fastest ascent possible). It is usually measured as percentage: 0 % — the motors are stopped, 100 % — the motors are rotating at maximum speed. Hovering throttle is the minimum throttle required for the copter to stay at certain altitude.
@@ -77,15 +77,15 @@ The axes of the copter (pitch, roll, and yaw) are the angles used to determine a
**Yaw** The multicopter nose turn. conditionally — turning right or left
![Yaw](../assets/1_6.png)
![Yaw](../assets/en/1_6.png)
**Pitch**. In copters, manipulation with this moment of force allows the copter to move forward or backward due to tilting the nose in the appropriate direction
![Pitch](../assets/1_7.png)
![Pitch](../assets/en/1_7.png)
**Roll** Multicopter tilting to the left or to the right. Due to the roll, the copter can move sideways in the appropriate direction.
![Roll](../assets/1_8.png)
![Roll](../assets/en/1_8.png)
If you can control throttle, pitch, roll and yaw, you can control the quadcopter. They are also sometimes called control channels. There are many flight modes. GPS, barometer, and distance gage are also used, as well as stabilization mode (stab, stabilize, flying and stab), in which the copter keeps the angles set from the transmitter regardless of external factors. Without wind, the copter can hang almost in place in this mode. And the wind will have to be compensated for by the pilot.
The propellers rotation directions are not chosen randomly. If all motors rotated in the same direction, the quadcopter would rotate in the opposite direction due to the generated moments. Therefore, two opposite motors always rotate in the same direction, and other two motors rotate the opposite direction. The effect of rotation moments is used to change the yaw: one pair of motors starts rotating a bit faster than the other, and the quadcopter slowly turns towards us:
@@ -105,7 +105,7 @@ Elements of the copter
Usually, when it comes to controlling a model of boat or an aircraft, the operator has absolute, precise control over the engine. Pressing the joystick on the transmitter results in proportional increasing the speed of the screws (rpm). A distinctive feature of multi-propeller aircraft (regardless of whether it is an advantage or a disadvantage) is in the fact that no one can simultaneously control the rotation speed of 3 and more motors precisely enough to keep the aircraft in the air. That is where the flight controllers come into play.
![Flightctr](../assets/1_10.png)
![Flightctr](../assets/en/1_10.png)
**Flight controller** is the most important part. Ninety percent of flight stability and controllability depends on the characteristics of the flight controller.
A flight controller is intended for translating commands from the transmitter into the signals that set the rotation speed of the motor. It also has inertial measuring sensors that allow keeping an eye on the current position of the platform and performing automatic adjustment
@@ -114,11 +114,11 @@ A flight controller is intended for translating commands from the transmitter in
**ESC** are regulators for adjusting the motors rotation. The fact is that multi copters use special brushless motors that can rotate at very high speeds. To control such motors, it is sometimes necessary to form three phase voltage and relatively high currents, which is performed by ESCs. Each motor requires its own ESC. All ESCs are connected to the flight controller. The ESCs are powered directly from the battery. Each motor is connected to its own ESC with three wires. The order of connecting the wires determines the direction of motor rotation.
![Esc](../assets/1_12.png)
![Esc](../assets/en/1_12.png)
**Motor**. Copters use brushless motors. They feature outstanding characteristics and survivability due to the absence of friction units (brushes) for transmitting the current. Unlike a conventional motor, which has a moving part — the rotor, and a stationary part — the stator, in a brushless motor, the moving part is the stator with permanent magnets, and the stationary part is the rotor with windings of three phases. In order to rotate such a system, the direction of the magnetic field in the windings of the rotor is changed in specific order, whereby permanent magnets in the rotor interact with magnetic fields of the stator and start rotating. This rotation is caused by the ability of magnets with the same poles to repel from each other, and magnets with opposite poles to attract to each other.
![Engine](../assets/1_13.png)
![Engine](../assets/en/1_13.png)
**Radio control equipment**. It includes a transmitter with a control unit, and a receiver. They may have various numbers of channels and frequencies. Most transmitters operate at the frequency of 2.40 GHz, there are also several other frequency bands available in the market.

View File

@@ -2,7 +2,7 @@
## Composition of the FLYSKY i6 transmitter
![Composition of the transmitter](../assets/consistofTransmitter.jpg)
![Composition of the transmitter](../assets/en/consistofTransmitter.jpg)
## Installation of QGroundControl

View File

@@ -16,7 +16,7 @@ As a result of searching for a solution that would fit all our requirements, we
In creating such a shape, two types of edges (beams) are used: short and long ones, their length is calculated based on the desired diameter of a polyhedron inscribed into a sphere. For better understanding, I will insert all necessary formulas from Wikipedia below.
![calculation](../assets/calculation.png)
![calculation](../assets/en/calculation.png)
The corner joints (fittings) were not very easy either. They are of two types as well: with five faces on the vertex (five beams protrude from the vertex) and with six faces (six rays protrude from the vertex).
@@ -28,7 +28,7 @@ Making simple calculations for the required size, we built a model in Inventor C
In the progress of designing, we faced problems in modeling corner joints, but they were solved by simplifying the design, and the differences of the angles were compensated for by flexible materials. Thus, all joints fit slightly tightly.
![table](../assets/table.png)
![table](../assets/en/table.png)
![elements](../assets/elements.png)

View File

@@ -10,7 +10,7 @@ Blanching a contact pad means doing the following:
1. Apply flux on the contact pad
2. Cover the contact pad with solder
![Blanching pads](../assets/zapPDBtest.jpg)
![Blanching pads](../assets/en/zapPDBtest.jpg)
## Blanching wires

View File

@@ -15,7 +15,13 @@
Также у нас есть чат для программистов, которые разрабатывают под PX4, автономную навигацию в помещениях и рои дронов https://t.me/DroneCode.
The English version of this documentation [is available](../en/).
The English version of this documentation <a id='english-link' href="https://clever.copterexpress.com/en/">is available</a>.
<script>
let el = document.querySelector('#english-link');
el.href = '/en/';
el.target = '_self';
</script>
Образ для Raspberry Pi
----------------------

View File

@@ -17,7 +17,7 @@
* Настройка
* [Первоначальная настройка](setup.md)
* [Полетные режимы](modes.md)
* [Прошивка Pixhawk/Pixracer](firmware.md)
* [Прошивка полетного контролера](firmware.md)
* [Параметры PX4](px4_parameters.md)
* [Настройка PID](calibratePID.md)
* Работа с Raspberry Pi
@@ -29,13 +29,13 @@
* [Настройка сети RPi](network.md)
* [Работа с QGroundControl через Wi-Fi](gcs_bridge.md)
* [Пилотирование со смартфона](rc.md)
* [Интерфейс UART](uart.md)
* [Просмотр видеострима с камер](web_video_server.md)
* [Системы координат](frames.md)
* [Интерфейс UART](uart.md)
* Программирование
* [ROS](ros.md)
* [MAVROS](mavros.md)
* [Автономный полет в OFFBOARD](simple_offboard.md)
* [Автономный полет (OFFBOARD)](simple_offboard.md)
* Визуальные маркеры (ArUco)
* [Общая информация](aruco.md)
* [Распознавание маркеров](aruco_marker.md)

View File

@@ -18,16 +18,26 @@ rosrun rosserial_arduino make_libraries.py .
## Настройка Raspberry Pi
Чтобы единоразово запустить программу на Arduino, можно воспользоваться командой:
Для запуска `rosserial` создайте файл `arduino.launch` в каталоге `~/catkin_ws/src/clever/clever/launch/` со следующим содержимым:
```xml
<launch>
<node pkg="rosserial_python" type="serial_node.py" name="serial_node" output="screen" if="$(arg arduino)">
<param name="port" value="/dev/serial/by-id/usb-1a86_USB2.0-Serial-if00-port0"/>
</node>
</launch>
```
Чтобы единоразово запустить программу на Arduino, можно будет воспользоваться командой:
```bash
roslaunch clever arduino.launch
```
Чтобы запускать связку с Arduino при старте системы автоматически, необходимо установить аргумент `arudino` в launch-файле Клевера (`~/catkin_ws/src/clever/clever/launch/clever.launch`):
Чтобы запускать связку с Arduino при старте системы автоматически, необходимо добавить запуск созданного launch-файла в основной launch-файл Клевера (`~/catkin_ws/src/clever/clever/launch/clever.launch`). Добавьте в конец этого файла строку:
```xml
<arg name="arduino" default="true"/>
<include file="$(find clever)/launch/arduino.launch"/>
```
При изменении launch-файла необходимо перезапустить пакет `clever`:

View File

@@ -2,6 +2,10 @@
> **Info** Для распознавания маркеров модуль камеры должен быть корректно подключен и [сконфигурирован](camera.md).
<!-- -->
> **Hint** Рекомендуется использование [специальной сборки PX4 для Клевера](firmware.md#прошивка-для-клевера).
Модуль `aruco_map` распознает карты ArUco-маркеров, как единое целое. Также возможна навигация по картам ArUco-маркеров с использованием механизма Vision Position Estimate (VPE).
## Конфигурирование
@@ -86,7 +90,7 @@ rosrun aruco_pose genmap.py 0.33 2 4 1 1 0 > ~/catkin_ws/src/clever/aruco_pose/m
При использовании **LPE** (параметр `SYS_MC_EST_GROUP` = `local_position_estimator, attitude_estimator_q`):
* В параметре `LPE_FUSION` включены флажки `vision position`, `land detector`.
* В параметре `LPE_FUSION` включены флажки `vision position`, `land detector`. Флажок `baro` рекомендуется отключить.
* Вес угла по рысканью по зрению: `ATT_W_EXT_HDG` = 0.5
* Включена ориентация по Yaw по зрению: `ATT_EXT_HDG_M` = 1 `Vision`.
* Шумы позиции по зрению: `LPE_VIS_XY` = 0.1 m, `LPE_VIS_Z` = 0.1 m.
@@ -94,6 +98,8 @@ rosrun aruco_pose genmap.py 0.33 2 4 1 1 0 > ~/catkin_ws/src/clever/aruco_pose/m
<!-- * Выключен компас: `ATT_W_MAG` = 0 -->
> **Hint** На данный момент для полета по маркерам рекомендуется использование **LPE**.
Для проверки правильности всех настроек можно [воспользоваться утилитой `selfcheck.py`](selfcheck.md).
> **Info** Для использования LPE в Pixhawk необходимо [скачать прошивку с названием `px4fmu-v2_lpe.px4`](https://github.com/PX4/Firmware/releases).

View File

@@ -1,20 +1,50 @@
Прошивка Pixhawk / Pixracer
Прошивка полетного контроллера
===
Pixhawk или Pixracer можно прошить, используя QGroundControl или утилиты командной строки.
Различные варианты сборок стабильных прошивок PX4 можно скачать в разделе [Releases на GitHub](https://github.com/PX4/Firmware/releases).
Прошивка для Клевера
---
В названии файла прошивки кодируется информации о целевой плате и варианте сборки. Примеры:
Для Клевера рекомендуется использование специальной сборки PX4, которая содержит необходимые исправления и более подходящие параметры по умолчанию. Используйте последний стабильный релиз в [GitHub-репозитории](https://github.com/CopterExpress/Firmware/releases), содержащий слово `clever`, например `v1.8.2-clever.4`.
* `px4fmu-v2_default.px4` — прошивка для Pixhawk с EKF2.
* `px4fmu-v2_lpe.px4` — прошивка для Pixhawk с LPE.
* `px4fmu-v4_default.px4` — прошивка для Pixracer с EKF2 и LPE (*Клевер 3*).
* `px4fmu-v3_default.px4` — прошивка для более новых версий Pixhawk (чип ревизии 3, см. илл. + Bootloader v5) с EKF2 и LPE.
<div id="release" style="display:none">
<p>Последний стабильный релиз: <strong><a id="download-latest-release"></a></strong>.</p>
![STM revision](../assets/stmrev.jpg)
<ul>
<li>Скачать файл прошивки для Pixracer (<strong>Клевер 4 / Клевер 3</strong>) <a id="firmware-pixracer" href=""><code>px4fmu-v4_default.px4</code></a>.</li>
<li>Скачать файл прошивки для Pixhawk (<strong>Клевер 2</strong>) <a id="firmware-pixhawk" href=""><code>px4fmu-v2_lpe.px4</code></a>.</li>
</ul>
</div>
> **Note** Для загрузки `px4fmu-v3_default.px4` может понадобиться использование команды `force_upload` из командной строки.
<script type="text/javascript">
// get latest release from GitHub
fetch('https://api.github.com/repos/CopterExpress/Firmware/releases').then(function(res) {
return res.json();
}).then(function(data) {
// look for stable release
let stable;
for (let release of data) {
let clever = release.name.indexOf('clever') != -1;
if (clever && !release.prerelease && !release.draft) {
stable = release;
break;
}
}
let el = document.querySelector('#download-latest-release');
el.innerHTML = stable.name;
el.href = stable.html_url;
document.querySelector('#release').style.display = 'block';
for (let asset of stable.assets) {
console.log(asset.name);
if (asset.name == 'px4fmu-v4_default.px4') {
document.querySelector('#firmware-pixracer').href = asset.browser_download_url;
} else if (asset.name == 'px4fmu-v2_lpe.px4') {
document.querySelector('#firmware-pixhawk').href = asset.browser_download_url;
}
}
});
</script>
QGroundControl
---
@@ -25,7 +55,21 @@ QGroundControl
> **Warning** Не отключайте USB-кабель до окончания процесса прошивки.
TODO: Иллюстрация.
<!-- TODO: Иллюстрация. -->
Варианты прошивок
---
В названии файла прошивки кодируется информации о целевой плате и варианте сборки. Примеры:
* `px4fmu-v4_default.px4` — прошивка для Pixracer с EKF2 и LPE (**Клевер 3** / **Клевер 4**).
* `px4fmu-v2_lpe.px4` — прошивка для Pixhawk с LPE (**Клевер 2**).
* `px4fmu-v2_default.px4` — прошивка для Pixhawk с EKF2.
* `px4fmu-v3_default.px4` — прошивка для более новых версий Pixhawk (чип ревизии 3, см. илл. + Bootloader v5) с EKF2 и LPE.
![STM revision](../assets/stmrev.jpg)
> **Note** Для загрузки `px4fmu-v3_default.px4` может понадобиться использование команды `force_upload` из командной строки.
Командная строка
---

View File

@@ -71,7 +71,7 @@ pi.set_servo_pulsewidth(13, 2000)
## Подключение электромагнита
<!-- TODO схема -->
![GPIO Mosfet Magnet Connection](../assets/gpio_mosfet_magnet.png)
Для подключения электромагнита используйте полевой транзистор (MOSFET). Подключите транзистор к одному из GPIO-пинов Raspberry Pi. Для управления магнитом, подключенным к 15 пину, используйте такой код:

View File

@@ -1,7 +1,5 @@
---
description: Режимы полетного контроллера PX4
meta:
author: Oleg Kalachev
---
Полетные режимы

View File

@@ -45,39 +45,27 @@ Wi-Fi адаптер на Raspberry Pi имеет два основных реж
sudo systemctl disable dnsmasq
```
2. Включите получение IP адреса на беспроводном интерфейсе DHCP клиентом.
Для этого удалите следующие строки
2. Включите получение IP адреса на беспроводном интерфейсе DHCP клиентом. Для этого удалите из файла `/etc/dhcpcd.conf` строки:
```conf
interface wlan0
static ip_address=192.168.11.1/24
```
из файла `/etc/dhcpcd.conf` вручную или введите следующие команды.
3. Настройте `wpa_supplicant` для подключения к существующей точке доступа. Для этого замените содержимое файла `/etc/wpa_supplicant/wpa_supplicant.conf` на:
```bash
sudo sed -i 's/interface wlan0//' /etc/dhcpcd.conf
sudo sed -i 's/static ip_address=192.168.11.1\/24//' /etc/dhcpcd.conf
```
3. Настройте `wpa_supplicant` для подключения к существующей точке доступа.
```bash
cat << EOF | sudo tee /etc/wpa_supplicant/wpa_supplicant.conf
ctrl_interface=DIR=/var/run/wpa_supplicant GROUP=netdev
update_config=1
country=GB
network={
ssid="CLEVER"
psk="cleverwifi"
ssid="SSID"
psk="password"
}
EOF
```
где `CLEVER` название сети, а `cleverwifi` пароль.
где `SSID` название сети, а `password` пароль.
4. Перезапустите службу `dhcpcd`.
@@ -87,35 +75,22 @@ Wi-Fi адаптер на Raspberry Pi имеет два основных реж
## Переключение адаптера в режим точки доступа
1. Включите статический IP адрес на беспроводном интерфейсе.
Для этого добавьте следующие строки
1. Включите статический IP адрес на беспроводном интерфейсе. Для этого добавьте в файл `/etc/dhcpcd.conf` строки:
```conf
interface wlan0
static ip_address=192.168.11.1/24
```
в файл `/etc/dhcpcd.conf` вручную или введите следующую команду
2. Настроите `wpa_supplicant` на работу в режиме точки доступа. Для этого замените содержимое файла `/etc/wpa_supplicant/wpa_supplicant.conf` на:
```bash
cat << EOF | sudo tee -a /etc/dhcpcd.conf
interface wlan0
static ip_address=192.168.11.1/24
EOF
```
2. Настроите wpa_supplicant на работу в режиме точки доступа.
```bash
cat << EOF | sudo tee /etc/wpa_supplicant/wpa_supplicant.conf
ctrl_interface=DIR=/var/run/wpa_supplicant GROUP=netdev
update_config=1
country=GB
network={
ssid="CLEVER-$(head -c 100 /dev/urandom | xxd -ps -c 100 | sed -e 's/[^0-9]//g' | cut -c 1-4)"
ssid="CLEVER-1234"
psk="cleverwifi"
mode=2
proto=RSN
@@ -124,10 +99,10 @@ Wi-Fi адаптер на Raspberry Pi имеет два основных реж
group=CCMP
auth_alg=OPEN
}
EOF
```
где `CLEVER-1234` название сети, а `cleverwifi` пароль.
3. Перезагрузите службу `dhcpcd`.
```bash

View File

@@ -4,18 +4,7 @@
## Включение
> **Note** Для использования Optical Flow необходима <a id="download-firmware" href="https://github.com/CopterExpress/Firmware/releases">кастомная прошивка PX4</a>. Подробнее про прошивку см. [соответствующую статью](firmware.md).
<script type="text/javascript">
fetch('https://api.github.com/repos/CopterExpress/Firmware/releases').then(res => res.json()).then(function(data) {
for (let release of data) {
if (!release.prerelease && !release.draft && release.tag_name.includes('-clever.')) {
document.querySelector('#download-firmware').href = release.html_url;
return;
}
}
});
</script>
> **Hint** Рекомендуется использование [специальной сборки PX4 для Клевера](firmware.md#прошивка-для-клевера).
Необходимо использование дальномера. [Подключите и настройте дальномер VL53L1X](laser.md), используя инструкцию.

View File

@@ -1,7 +1,7 @@
Raspberry Pi
============
**Raspberry Pi** это свободно помещающийся на ладони одноплатный компьютер, созданный на базе мобильного микропроцессора ARM11. У него низкое потребление энергии, и он может работать даже от солнечных батарей. Raspberry Pi 3 входит в комплект программируемого квадрокоптера "Клевер 2" и "Клевер 3".
**Raspberry Pi** это свободно помещающийся на ладони одноплатный компьютер, созданный на базе мобильного микропроцессора ARM11. У него низкое потребление энергии, и он может работать даже от солнечных батарей. Raspberry Pi 3 входит в комплект программируемого квадрокоптера "Клевер 2", "Клевер 3" и "Клевер 4".
<img src="../assets/raspberry3.jpg" width="500">

View File

@@ -21,12 +21,14 @@
![Обновление прошивки](../assets/firmwarePX4.jpg)
> **Hint** Рекомендуется использование [специальной сборки PX4 для Клевера](firmware.md#прошивка-для-клевера).
1. Заходим в Vehicle Setup.
2. Выбираем Firmware.
3. Отключаем Pixhawk от USB. Подключаем Pixhawk к USB снова.
4. Ждем подключения Pixhawk, выбираем прошивку PX4 Flight Stack и активируем Advanced settings.
5. Выбираем тип прошивки Standard Version (stable). Если загружать собственную прошивку/ прошивку внешним файлом (например, скачанную из интернета), то выбираем Customize из выпадающего меню.
6. Кликаем OK. Ждем загрузку.
5. Выбираем тип прошивки Standard Version (stable). Для выбора [кастомной прошивки для Клевера](firmware.md#прошивка-для-клевера) выберите Customize из выпадающего меню.
6. Кликаем OK. Ждем загрузку или выбираем файл прошивки.
7. Ждем, пока Pixhawk выполнит перезагрузку.
## Настройка Pixhawk

View File

@@ -1,13 +1,17 @@
Simple OFFBOARD
Автономный полет (OFFBOARD)
===
> **Note** Документация для версий [образа](microsd_images.md), начиная с **0.15**. Для более ранних версий см. [документацию для версии **0.14**](https://github.com/CopterExpress/clever/blob/v0.14/docs/ru/simple_offboard.md).
Модуль `simple_offboard` пакета `clever` предназначен для упрощенного программирования автономного дрона ([режим](modes.md) `OFFBOARD`). Он позволяет устанавливать желаемые полетные задачи и автоматически трансформирует [систему координат](frames.md).
<!-- -->
> **Hint** Для автономных полетов рекомендуется использование [специальной сборки PX4 для Клевера](firmware.md#прошивка-для-клевера).
Модуль `simple_offboard` пакета `clever` предназначен для упрощенного программирования автономного полета дрона ([режим](modes.md) `OFFBOARD`). Он позволяет устанавливать желаемые полетные задачи и автоматически трансформирует [систему координат](frames.md).
`simple_offboard` является высокоуровневым способом взаимодействия с полетным контроллером. Для более низкоуровневой работы см. [mavros](mavros.md).
Основные сервисы `get_telemetry` (получение всей телеметрии), `navigate` (полет в заданную точку по прямой), `navigate_global` (полет в глобальную точку по прямой), `land` (переход в режим посадки).
Основные сервисы [`get_telemetry`](#gettelemetry) (получение телеметрии), [`navigate`](#navigate) (полет в заданную точку по прямой), [`navigate_global`](#navigateglobal) (полет в глобальную точку по прямой), [`land`](#land) (переход в режим посадки).
Использование из языка Python
---

View File

@@ -18,6 +18,10 @@ Python
Функция определения расстояния между двумя точками (**важно**: точки должны быть в одной [системе координат](frames.md)):
```python
import math
# ...
def get_distance(x1, y1, z1, x2, y2, z2):
return math.sqrt((x1 - x2) ** 2 + (y1 - y2) ** 2 + (z1 - z2) ** 2)
```
@@ -27,6 +31,10 @@ def get_distance(x1, y1, z1, x2, y2, z2):
Функция для приблизительного определения расстояния (в метрах) между двумя глобальными координатами (широта/долгота):
```python
import math
# ...
def get_distance_global(lat1, lon1, lat2, lon2):
return math.hypot(lat1 - lat2, lon1 - lon2) * 1.113195e5
```
@@ -280,12 +288,18 @@ set_mode(custom_mode='STABILIZED')
def flip():
start = get_telemetry() # memorize starting position
set_rates(roll_rate=5, thrust=0.2) # maximum roll rate
set_rates(thrust=1) # bump up
rospy.sleep(0.2)
set_rates(roll_rate=20, thrust=0.2) # maximum roll rate
while True:
telem = get_telemetry()
if abs(telem.roll) > math.pi / 2:
if -math.pi + 0.1 < telem.roll < -0.2:
break
rospy.loginfo('finish flip')
set_position(x=start.x, y=start.y, z=start.z, yaw=start.yaw) # finish flip
print navigate(z=4, speed=1, auto_arm=True) # take off
@@ -294,3 +308,5 @@ rospy.sleep(10)
rospy.loginfo('flip')
flip()
```
Необходимо использование [специальной сборки PX4 для Клевера](firmware.md#прошивка-для-клевера). Перед выполнением флипа необходимо принять все меры безопасности.