Compare commits
96 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
4786b51466 | ||
|
|
d3fffb7b54 | ||
|
|
e1444978bb | ||
|
|
9932062631 | ||
|
|
8a5e1318c7 | ||
|
|
7d6acc52e9 | ||
|
|
b850844fa2 | ||
|
|
4c01e710fc | ||
|
|
161506d89a | ||
|
|
bb2c2cfac9 | ||
|
|
8019712d8c | ||
|
|
41e9f407fd | ||
|
|
c8008efeac | ||
|
|
c5dbf44bba | ||
|
|
c0217d8aff | ||
|
|
ee1a493636 | ||
|
|
2a755005a6 | ||
|
|
4807db85a7 | ||
|
|
82a2a5e5f7 | ||
|
|
73e17aeb48 | ||
|
|
0af7d406bd | ||
|
|
78f43ad078 | ||
|
|
8faa838bb9 | ||
|
|
f499608cc2 | ||
|
|
486c62f625 | ||
|
|
29b9f47eea | ||
|
|
bba9f3db76 | ||
|
|
91f6f6dd32 | ||
|
|
ec57f7d0a3 | ||
|
|
683e06dc20 | ||
|
|
6dfba25d45 | ||
|
|
ffa2f89c8e | ||
|
|
a99c381f11 | ||
|
|
36d088d648 | ||
|
|
f0ab0a8e11 | ||
|
|
53c2cf6998 | ||
|
|
ae3d3a955b | ||
|
|
2e11db0756 | ||
|
|
66e21443a9 | ||
|
|
81c3d6d42b | ||
|
|
9f4df86cae | ||
|
|
beca5f25e9 | ||
|
|
10785183e1 | ||
|
|
7c5af5f494 | ||
|
|
cabe76a607 | ||
|
|
d2912aebd8 | ||
|
|
efb9bf2f7a | ||
|
|
7f8b78ad7d | ||
|
|
34095bfaa7 | ||
|
|
747f26742d | ||
|
|
31f586070d | ||
|
|
021aa69110 | ||
|
|
b5a01e6a7e | ||
|
|
5b02f59583 | ||
|
|
1c33102b8f | ||
|
|
bca7445ebe | ||
|
|
d47a95e134 | ||
|
|
064e402a2d | ||
|
|
5b617d91a9 | ||
|
|
2a4dce3e09 | ||
|
|
cf9b7abcfa | ||
|
|
751caa906c | ||
|
|
ff244345a7 | ||
|
|
c73c7857c6 | ||
|
|
b9b4d762ea | ||
|
|
8929fd534f | ||
|
|
dff4487d9b | ||
|
|
00c12ed305 | ||
|
|
91cae1e4c6 | ||
|
|
328572f7b1 | ||
|
|
73f600b41b | ||
|
|
2a5d511b2b | ||
|
|
bc0039ccb7 | ||
|
|
378efd9fab | ||
|
|
c2b974f407 | ||
|
|
1778f1d9eb | ||
|
|
25ca8f8b97 | ||
|
|
94c191f65f | ||
|
|
6f95037e56 | ||
|
|
17916f931c | ||
|
|
d09dfba905 | ||
|
|
e631459181 | ||
|
|
86da07bca8 | ||
|
|
bb9f56f6a6 | ||
|
|
a37f58ada9 | ||
|
|
a3bc692679 | ||
|
|
bd8b17a51d | ||
|
|
9ac980f278 | ||
|
|
742041448d | ||
|
|
fe83930e42 | ||
|
|
a93ae126bc | ||
|
|
199247c745 | ||
|
|
4746f3181d | ||
|
|
74f84a22d9 | ||
|
|
d37ac64f64 | ||
|
|
3f94335554 |
@@ -24,6 +24,8 @@
|
||||
"Python",
|
||||
"C++",
|
||||
"PX4",
|
||||
"px4.io",
|
||||
"logs.px4.io",
|
||||
"QGroundControl",
|
||||
"QGC",
|
||||
"WireShark",
|
||||
@@ -38,6 +40,10 @@
|
||||
"RPi",
|
||||
"Linux",
|
||||
"Windows",
|
||||
"Docker",
|
||||
"Travis",
|
||||
"travis-ci.org",
|
||||
"travis-ci.com",
|
||||
"macOS",
|
||||
"iOS",
|
||||
"Android",
|
||||
|
||||
36
.travis.yml
@@ -23,7 +23,16 @@ jobs:
|
||||
# Check if there are any cached images, copy them to our "images" directory
|
||||
- if [ -n "$(ls -A imgcache/*.zip)" ]; then mkdir -p images && cp imgcache/*.zip images; fi
|
||||
script:
|
||||
- docker run --privileged --rm -v /dev:/dev -v $(pwd):/builder/repo -e TRAVIS_TAG="${TRAVIS_TAG}" ${DOCKER}
|
||||
- if [[ -z ${TRAVIS_TAG} && ${TRAVIS_PULL_REQUEST} ]]; then
|
||||
echo "Commit range is ${TRAVIS_COMMIT_RANGE}" &&
|
||||
if [ $(git diff --name-only ${TRAVIS_COMMIT_RANGE} | grep -v ^"docs/" | wc -l) -eq 0 ]; then
|
||||
echo " === Docs-only change; skipping build ===" &&
|
||||
export SKIP_BUILD=true;
|
||||
fi;
|
||||
fi
|
||||
- if [ -z ${SKIP_BUILD} ]; then
|
||||
docker run --privileged --rm -v /dev:/dev -v $(pwd):/builder/repo -e TRAVIS_TAG="${TRAVIS_TAG}" ${DOCKER};
|
||||
fi
|
||||
before_cache:
|
||||
- cp images/*.zip imgcache
|
||||
before_deploy:
|
||||
@@ -55,19 +64,18 @@ jobs:
|
||||
- markdownlint docs
|
||||
- gitbook install
|
||||
- gitbook build
|
||||
# ***
|
||||
# Disable deployments for now, revisit this later
|
||||
# --sfalexrog, 06.02.2019
|
||||
# ***
|
||||
# deploy:
|
||||
# provider: pages
|
||||
# local-dir: _book
|
||||
# skip-cleanup: true
|
||||
# github-token: ${GITHUB_OAUTH_TOKEN}
|
||||
# keep-history: true
|
||||
# target-branch: gh-pages
|
||||
# on:
|
||||
# branch: WIP/gitbook-autobuild
|
||||
deploy:
|
||||
provider: pages
|
||||
local-dir: _book
|
||||
skip-cleanup: true
|
||||
github-token: ${GITHUB_OAUTH_TOKEN}
|
||||
keep-history: true
|
||||
target-branch: master
|
||||
repo: CopterExpress/clever-gitbook
|
||||
fqdn: clever.copterexpress.com
|
||||
verbose: true
|
||||
on:
|
||||
branch: master
|
||||
- stage: Annotate
|
||||
name: Auto-generate changelog
|
||||
language: python
|
||||
|
||||
@@ -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()
|
||||
|
||||
@@ -74,6 +74,7 @@ It's recommended to run it within the same nodelet manager with the camera nodel
|
||||
* `~image_width` – debug image width (default: 2000)
|
||||
* `~image_height` – debug image height (default: 2000)
|
||||
* `~image_margin` – debug image margin (default: 200)
|
||||
* `~dictionary` (*int*) – ArUco dictionary (default: 2) - should be the same as `dictionary` parameter of `aruco_detect` nodelet
|
||||
|
||||
Map file has one marker per line with the following line format:
|
||||
|
||||
|
||||
100
aruco_pose/map/cmit.txt
Normal 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
|
||||
@@ -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);
|
||||
|
||||
@@ -1,5 +1,13 @@
|
||||
#!/usr/bin/env python
|
||||
|
||||
# Copyright (C) 2018 Copter Express Technologies
|
||||
#
|
||||
# Author: Oleg Kalachev <okalachev@gmail.com>
|
||||
#
|
||||
# Distributed under MIT License (available at https://opensource.org/licenses/MIT).
|
||||
# The above copyright notice and this permission notice shall be included in all
|
||||
# copies or substantial portions of the Software.
|
||||
|
||||
"""Markers map generator
|
||||
|
||||
Generate map file for aruco_map nodelet.
|
||||
|
||||
@@ -1,3 +1,14 @@
|
||||
/*
|
||||
* Utility functions
|
||||
* Copyright (C) 2018 Copter Express Technologies
|
||||
*
|
||||
* Author: Oleg Kalachev <okalachev@gmail.com>
|
||||
*
|
||||
* Distributed under MIT License (available at https://opensource.org/licenses/MIT).
|
||||
* The above copyright notice and this permission notice shall be included in all
|
||||
* copies or substantial portions of the Software.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <cmath>
|
||||
|
||||
@@ -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
|
||||
|
||||
27
aruco_pose/test/test_node_failure.py
Executable 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)
|
||||
13
aruco_pose/test/test_node_failure.test
Normal 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>
|
||||
4
aruco_pose/test/test_node_failure.txt
Normal 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!
|
||||
24
aruco_pose/test/test_parser_empty_map.py
Executable 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)
|
||||
13
aruco_pose/test/test_parser_empty_map.test
Normal 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>
|
||||
6
aruco_pose/test/test_parser_empty_map.txt
Normal 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
|
||||
75
aruco_pose/test/test_parser_pass.py
Executable 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)
|
||||
13
aruco_pose/test/test_parser_pass.test
Normal 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>
|
||||
23
aruco_pose/test/test_parser_pass.txt
Normal 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
|
||||
@@ -4,6 +4,7 @@
|
||||
"author": "Copter Express",
|
||||
"language": "ru",
|
||||
"root": "docs/",
|
||||
"gitbook": "^3.2.2",
|
||||
"plugins": [
|
||||
"youtube",
|
||||
"richquotes@https://github.com/okalachev/gitbook-plugin-richquotes.git",
|
||||
|
||||
@@ -8,6 +8,10 @@
|
||||
#
|
||||
# Author: Artem Smirnov <urpylka@gmail.com>
|
||||
#
|
||||
# Distributed under MIT License (available at https://opensource.org/licenses/MIT).
|
||||
# The above copyright notice and this permission notice shall be included in all
|
||||
# copies or substantial portions of the Software.
|
||||
#
|
||||
|
||||
set -e # Exit immidiately on non-zero result
|
||||
|
||||
|
||||
@@ -8,6 +8,10 @@
|
||||
#
|
||||
# Author: Artem Smirnov <urpylka@gmail.com>
|
||||
#
|
||||
# Distributed under MIT License (available at https://opensource.org/licenses/MIT).
|
||||
# The above copyright notice and this permission notice shall be included in all
|
||||
# copies or substantial portions of the Software.
|
||||
#
|
||||
|
||||
set -e # Exit immidiately on non-zero result
|
||||
|
||||
|
||||
@@ -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]
|
||||
|
||||
8
builder/assets/pigpiod.service
Normal 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
|
||||
@@ -1,17 +1,21 @@
|
||||
#! /usr/bin/env bash
|
||||
|
||||
#
|
||||
# Script for build the image. Used builder script of the target repo
|
||||
# Script for build the image. Used builder script of the target repo.
|
||||
# For build: docker run --privileged -it --rm -v /dev:/dev -v $(pwd):/builder/repo smirart/builder
|
||||
#
|
||||
# Copyright (C) 2018 Copter Express Technologies
|
||||
#
|
||||
# Author: Artem Smirnov <urpylka@gmail.com>
|
||||
#
|
||||
# Distributed under MIT License (available at https://opensource.org/licenses/MIT).
|
||||
# The above copyright notice and this permission notice shall be included in all
|
||||
# copies or substantial portions of the Software.
|
||||
#
|
||||
|
||||
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 +113,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/'
|
||||
|
||||
@@ -1,12 +1,16 @@
|
||||
#! /usr/bin/env bash
|
||||
|
||||
#
|
||||
# Script for initialisation image
|
||||
# Script for image initialisation
|
||||
#
|
||||
# Copyright (C) 2018 Copter Express Technologies
|
||||
#
|
||||
# Author: Artem Smirnov <urpylka@gmail.com>
|
||||
#
|
||||
# Distributed under MIT License (available at https://opensource.org/licenses/MIT).
|
||||
# The above copyright notice and this permission notice shall be included in all
|
||||
# copies or substantial portions of the Software.
|
||||
#
|
||||
|
||||
set -e # Exit immidiately on non-zero result
|
||||
|
||||
|
||||
@@ -1,12 +1,16 @@
|
||||
#! /usr/bin/env bash
|
||||
|
||||
#
|
||||
# Script for network configure
|
||||
# Script for network configuration
|
||||
#
|
||||
# Copyright (C) 2018 Copter Express Technologies
|
||||
#
|
||||
# Author: Artem Smirnov <urpylka@gmail.com>
|
||||
#
|
||||
# Distributed under MIT License (available at https://opensource.org/licenses/MIT).
|
||||
# The above copyright notice and this permission notice shall be included in all
|
||||
# copies or substantial portions of the Software.
|
||||
#
|
||||
|
||||
set -e # Exit immidiately on non-zero result
|
||||
|
||||
|
||||
@@ -8,6 +8,10 @@
|
||||
#
|
||||
# Author: Artem Smirnov <urpylka@gmail.com>
|
||||
#
|
||||
# Distributed under MIT License (available at https://opensource.org/licenses/MIT).
|
||||
# The above copyright notice and this permission notice shall be included in all
|
||||
# copies or substantial portions of the Software.
|
||||
#
|
||||
|
||||
set -e # Exit immidiately on non-zero result
|
||||
|
||||
@@ -42,9 +46,10 @@ echo_stamp() {
|
||||
my_travis_retry() {
|
||||
local result=0
|
||||
local count=1
|
||||
while [ $count -le 3 ]; do
|
||||
local max_count=50
|
||||
while [ $count -le $max_count ]; do
|
||||
[ $result -ne 0 ] && {
|
||||
echo -e "\n${ANSI_RED}The command \"$@\" failed. Retrying, $count of 3.${ANSI_RESET}\n" >&2
|
||||
echo -e "\nThe command \"$@\" failed. Retrying, $count of $max_count.\n" >&2
|
||||
}
|
||||
# ! { } ignores set -e, see https://stackoverflow.com/a/4073372
|
||||
! { "$@"; result=$?; }
|
||||
@@ -53,21 +58,21 @@ my_travis_retry() {
|
||||
sleep 1
|
||||
done
|
||||
|
||||
[ $count -gt 3 ] && {
|
||||
echo -e "\n${ANSI_RED}The command \"$@\" failed 3 times.${ANSI_RESET}\n" >&2
|
||||
[ $count -gt $max_count ] && {
|
||||
echo -e "\nThe command \"$@\" failed $max_count times.\n" >&2
|
||||
}
|
||||
|
||||
return $result
|
||||
}
|
||||
|
||||
# TODO: 'kinetic-rosdep-clever.yaml' should add only if we use our repo?
|
||||
echo_stamp "Init rosdep" \
|
||||
&& rosdep init \
|
||||
&& echo "yaml file:///etc/ros/rosdep/kinetic-rosdep-clever.yaml" >> /etc/ros/rosdep/sources.list.d/20-default.list \
|
||||
&& rosdep update
|
||||
echo_stamp "Init rosdep"
|
||||
my_travis_retry rosdep init
|
||||
echo "yaml file:///etc/ros/rosdep/kinetic-rosdep-clever.yaml" >> /etc/ros/rosdep/sources.list.d/20-default.list
|
||||
my_travis_retry rosdep update
|
||||
|
||||
echo_stamp "Populate rosdep for ROS user"
|
||||
sudo -u pi rosdep update
|
||||
my_travis_retry sudo -u pi rosdep update
|
||||
|
||||
resolve_rosdep() {
|
||||
# TEMPLATE: resolve_rosdep <CATKIN_PATH> <ROS_DISTRO> <OS_DISTRO> <OS_VERSION>
|
||||
@@ -137,6 +142,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 \
|
||||
@@ -168,7 +177,8 @@ apt-get install -y --no-install-recommends \
|
||||
ros-kinetic-rosserial \
|
||||
ros-kinetic-usb-cam \
|
||||
ros-kinetic-vl53l1x \
|
||||
ros-kinetic-opencv3=3.3.19-0stretch
|
||||
ros-kinetic-opencv3=3.3.19-0stretch \
|
||||
ros-kinetic-rosshow
|
||||
|
||||
# TODO move GeographicLib datasets to Mavros debian package
|
||||
echo_stamp "Install GeographicLib datasets (needs for mavros)" \
|
||||
|
||||
@@ -1,12 +1,16 @@
|
||||
#! /usr/bin/env bash
|
||||
|
||||
#
|
||||
# Script for install software to the image.
|
||||
# Script for installing software to the image.
|
||||
#
|
||||
# Copyright (C) 2018 Copter Express Technologies
|
||||
#
|
||||
# Author: Artem Smirnov <urpylka@gmail.com>
|
||||
#
|
||||
# Distributed under MIT License (available at https://opensource.org/licenses/MIT).
|
||||
# The above copyright notice and this permission notice shall be included in all
|
||||
# copies or substantial portions of the Software.
|
||||
#
|
||||
|
||||
set -e # Exit immidiately on non-zero result
|
||||
|
||||
@@ -86,7 +90,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 \
|
||||
@@ -99,14 +103,23 @@ libffi-dev \
|
||||
monkey=1.6.9-1 \
|
||||
pigpio python-pigpio python3-pigpio \
|
||||
i2c-tools \
|
||||
espeak espeak-data python-espeak \
|
||||
ntpdate \
|
||||
python-dev \
|
||||
python3-dev \
|
||||
python-systemd \
|
||||
&& echo_stamp "Everything was installed!" "SUCCESS" \
|
||||
|| (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.20190215-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
|
||||
@@ -154,6 +167,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.
|
||||
|
||||
@@ -7,6 +7,10 @@
|
||||
#
|
||||
# Author: Oleg Kalachev <okalachev@gmail.com>
|
||||
#
|
||||
# Distributed under MIT License (available at https://opensource.org/licenses/MIT).
|
||||
# The above copyright notice and this permission notice shall be included in all
|
||||
# copies or substantial portions of the Software.
|
||||
#
|
||||
|
||||
set -ex
|
||||
|
||||
|
||||
@@ -25,6 +25,6 @@ import pymavlink
|
||||
from pymavlink import mavutil
|
||||
import rpi_ws281x
|
||||
import pigpio
|
||||
from espeak import espeak
|
||||
|
||||
print cv2.getBuildInformation()
|
||||
|
||||
|
||||
@@ -28,6 +28,7 @@ monkey --version
|
||||
pigpiod -v
|
||||
i2cdetect -V
|
||||
butterfly -h
|
||||
espeak --version
|
||||
|
||||
# ros stuff
|
||||
|
||||
@@ -46,3 +47,4 @@ rosversion rosserial
|
||||
rosversion usb_cam
|
||||
rosversion cv_camera
|
||||
rosversion web_video_server
|
||||
rosversion rosshow
|
||||
|
||||
@@ -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">
|
||||
@@ -21,6 +20,7 @@
|
||||
<!-- web video server -->
|
||||
<node name="web_video_server" pkg="web_video_server" type="web_video_server" if="$(arg web_video_server)" required="false" respawn="true" respawn_delay="5">
|
||||
<param name="default_stream_type" value="ros_compressed"/>
|
||||
<param name="publish_rate" value="1.0"/>
|
||||
</node>
|
||||
|
||||
<!-- aruco markers -->
|
||||
@@ -63,15 +63,9 @@
|
||||
<!-- vl53l1x ToF rangefinder -->
|
||||
<node name="vl53l1x" pkg="vl53l1x" type="vl53l1x_node" output="screen" if="$(arg rangefinder_vl53l1x)">
|
||||
<param name="frame_id" value="rangefinder"/>
|
||||
<param name="offset" value="-0.05"/>
|
||||
<remap from="~range" to="mavros/distance_sensor/rangefinder_sub"/> <!-- redirect data to FCU -->
|
||||
</node>
|
||||
|
||||
<!-- 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>
|
||||
|
||||
@@ -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> -->
|
||||
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -1,21 +1,34 @@
|
||||
#!/usr/bin/env python
|
||||
|
||||
# Copyright (C) 2018 Copter Express Technologies
|
||||
#
|
||||
# Author: Oleg Kalachev <okalachev@gmail.com>
|
||||
#
|
||||
# Distributed under MIT License (available at https://opensource.org/licenses/MIT).
|
||||
# The above copyright notice and this permission notice shall be included in all
|
||||
# copies or substantial portions of the Software.
|
||||
|
||||
import math
|
||||
from subprocess import Popen, PIPE
|
||||
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 mavros import mavlink
|
||||
|
||||
|
||||
# TODO: roscore is running
|
||||
# TODO: clever.service is running
|
||||
# TODO: check attitude is present
|
||||
# TODO: disk free space
|
||||
# TODO: map, base_link, body
|
||||
@@ -28,28 +41,41 @@ from aruco_pose.msg import MarkerArray
|
||||
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.logwarn('%s: exception occurred', name)
|
||||
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
|
||||
@@ -59,7 +85,12 @@ param_get = rospy.ServiceProxy('mavros/param/get', ParamGet)
|
||||
|
||||
|
||||
def get_param(name):
|
||||
res = param_get(param_id=name)
|
||||
try:
|
||||
res = param_get(param_id=name)
|
||||
except rospy.ServiceException as e:
|
||||
failure('%s: %s', name, str(e))
|
||||
return None
|
||||
|
||||
if not res.success:
|
||||
failure('Unable to retrieve PX4 parameter %s', name)
|
||||
else:
|
||||
@@ -68,36 +99,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)
|
||||
@@ -105,32 +216,91 @@ 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')
|
||||
def check_vpe():
|
||||
vis = None
|
||||
try:
|
||||
vis = rospy.wait_for_message('mavros/vision_pose/pose', PoseStamped, timeout=1)
|
||||
except rospy.ROSException:
|
||||
@@ -138,7 +308,11 @@ def check_vpe():
|
||||
vis = rospy.wait_for_message('mavros/mocap/pose', PoseStamped, timeout=1)
|
||||
except rospy.ROSException:
|
||||
failure('no VPE or MoCap messages')
|
||||
return
|
||||
# check if vpe_publisher is running
|
||||
try:
|
||||
subprocess.check_output(['pgrep', '-x', 'vpe_publisher'])
|
||||
except subprocess.CalledProcessError:
|
||||
return # it's not running, skip following checks
|
||||
|
||||
# check PX4 settings
|
||||
est = get_param('SYS_MC_EST_GROUP')
|
||||
@@ -150,26 +324,29 @@ 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 fusing is disabled, change LPE_FUSION parameter')
|
||||
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):
|
||||
failure('vision position fusing is disabled, change EKF2_AID_MASK parameter')
|
||||
failure('vision position fusion is disabled, change EKF2_AID_MASK parameter')
|
||||
if not fuse & (1 << 4):
|
||||
failure('vision yaw fusing is disabled, change EKF2_AID_MASK parameter')
|
||||
failure('vision yaw fusion is disabled, change EKF2_AID_MASK parameter')
|
||||
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',
|
||||
get_param('EKF2_EVA_NOISE'),
|
||||
get_param('EKF2_EVP_NOISE'))
|
||||
info('EKF2_EVA_NOISE is %.3f, EKF2_EVP_NOISE is %.3f',
|
||||
get_param('EKF2_EVA_NOISE'),
|
||||
get_param('EKF2_EVP_NOISE'))
|
||||
|
||||
if not vis:
|
||||
return
|
||||
|
||||
# check vision pose and estimated pose inconsistency
|
||||
try:
|
||||
@@ -240,7 +417,7 @@ def check_velocity():
|
||||
failure('vertical velocity estimation is %.2f m/s; is copter staying still?' % vert)
|
||||
|
||||
angular = velocity.twist.angular
|
||||
ANGULAR_VELOCITY_LIMIT = 0.01
|
||||
ANGULAR_VELOCITY_LIMIT = 0.1
|
||||
if abs(angular.x) > ANGULAR_VELOCITY_LIMIT:
|
||||
failure('pitch rate estimation is %.2f rad/s (%.2f deg/s); is copter staying still?',
|
||||
angular.x, math.degrees(angular.x))
|
||||
@@ -276,32 +453,32 @@ def check_optical_flow():
|
||||
if est == 1:
|
||||
fuse = get_param('LPE_FUSION')
|
||||
if not fuse & (1 << 1):
|
||||
failure('optical flow fusing is disabled, change LPE_FUSION parameter')
|
||||
failure('optical flow fusion is disabled, change LPE_FUSION parameter')
|
||||
if not fuse & (1 << 1):
|
||||
failure('flow gyro compensation is disabled, change LPE_FUSION parameter')
|
||||
scale = get_param('LPE_FLW_SCALE')
|
||||
if scale != 0:
|
||||
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',
|
||||
get_param('LPE_FLW_QMIN'),
|
||||
get_param('LPE_FLW_R'),
|
||||
get_param('LPE_FLW_RR'),
|
||||
get_param('SENS_FLOW_MINHGT'),
|
||||
get_param('SENS_FLOW_MAXHGT'))
|
||||
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'),
|
||||
get_param('SENS_FLOW_MINHGT'),
|
||||
get_param('SENS_FLOW_MAXHGT'))
|
||||
elif est == 2:
|
||||
fuse = get_param('EKF2_AID_MASK')
|
||||
if not fuse & (1 << 1):
|
||||
failure('optical flow fusing is disabled, change EKF2_AID_MASK parameter')
|
||||
failure('optical flow fusion is disabled, change EKF2_AID_MASK parameter')
|
||||
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',
|
||||
get_param('EKF2_OF_QMIN'),
|
||||
get_param('EKF2_OF_N_MIN'),
|
||||
get_param('EKF2_OF_N_MAX'),
|
||||
get_param('SENS_FLOW_MINHGT'),
|
||||
get_param('SENS_FLOW_MAXHGT'))
|
||||
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'),
|
||||
get_param('SENS_FLOW_MINHGT'),
|
||||
get_param('SENS_FLOW_MAXHGT'))
|
||||
|
||||
except rospy.ROSException:
|
||||
failure('no optical flow data (from Raspberry)')
|
||||
@@ -312,13 +489,13 @@ def check_rangefinder():
|
||||
# TODO: check FPS!
|
||||
rng = False
|
||||
try:
|
||||
rospy.wait_for_message('mavros/distance_sensor/rangefinder_sub', Range, timeout=0.5)
|
||||
rospy.wait_for_message('mavros/distance_sensor/rangefinder_sub', Range, timeout=4)
|
||||
rng = True
|
||||
except rospy.ROSException:
|
||||
failure('no rangefinder data from Raspberry')
|
||||
|
||||
try:
|
||||
rospy.wait_for_message('mavros/distance_sensor/rangefinder', Range, timeout=0.5)
|
||||
rospy.wait_for_message('mavros/distance_sensor/rangefinder', Range, timeout=4)
|
||||
rng = True
|
||||
except rospy.ROSException:
|
||||
failure('no rangefinder data from PX4')
|
||||
@@ -330,28 +507,26 @@ 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')
|
||||
def check_boot_duration():
|
||||
proc = Popen('systemd-analyze', stdout=PIPE)
|
||||
proc.wait()
|
||||
output = proc.communicate()[0]
|
||||
output = subprocess.check_output('systemd-analyze')
|
||||
r = re.compile(r'([\d\.]+)s$')
|
||||
duration = float(r.search(output).groups()[0])
|
||||
if duration > 15:
|
||||
@@ -362,9 +537,7 @@ def check_boot_duration():
|
||||
def check_cpu_usage():
|
||||
WHITELIST = 'nodelet',
|
||||
CMD = "top -n 1 -b -i | tail -n +8 | awk '{ printf(\"%-8s\\t%-8s\\t%-8s\\n\", $1, $9, $12); }'"
|
||||
proc = Popen(CMD, stdout=PIPE, shell=True)
|
||||
proc.wait()
|
||||
output = proc.communicate()[0]
|
||||
output = subprocess.check_output(CMD, shell=True)
|
||||
processes = output.split('\n')
|
||||
for process in processes:
|
||||
if not process:
|
||||
@@ -376,13 +549,68 @@ def check_cpu_usage():
|
||||
cpu.strip(), cmd.strip(), pid.strip())
|
||||
|
||||
|
||||
@check('clever.service')
|
||||
def check_clever_service():
|
||||
output = subprocess.check_output('systemctl show -p ActiveState --value clever.service'.split())
|
||||
if 'inactive' in output:
|
||||
failure('clever.service is not running, try sudo systemctl restart clever')
|
||||
return
|
||||
j = journal.Reader()
|
||||
j.this_boot()
|
||||
j.add_match(_SYSTEMD_UNIT='clever.service')
|
||||
j.add_disjunction()
|
||||
j.add_match(UNIT='clever.service')
|
||||
node_errors = []
|
||||
r = re.compile(r'^(.*)\[(FATAL|ERROR)\] \[\d+.\d+\]: (.*)$')
|
||||
for event in j:
|
||||
msg = event['MESSAGE']
|
||||
if ('Stopped Clever ROS package' in msg) or ('Started Clever ROS package' in msg):
|
||||
node_errors = []
|
||||
elif ('[ERROR]' in msg) or ('[FATAL]' in msg):
|
||||
msg = r.search(msg).groups()[2]
|
||||
if msg in node_errors:
|
||||
continue
|
||||
node_errors.append(msg)
|
||||
for error in node_errors:
|
||||
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()
|
||||
|
||||
@@ -70,6 +70,7 @@ ros::Duration global_position_timeout;
|
||||
ros::Duration battery_timeout;
|
||||
float default_speed;
|
||||
bool auto_release;
|
||||
bool land_only_in_offboard;
|
||||
std::map<string, string> reference_frames;
|
||||
|
||||
// Publishers
|
||||
@@ -644,6 +645,12 @@ bool land(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
|
||||
|
||||
checkState();
|
||||
|
||||
if (land_only_in_offboard) {
|
||||
if (state.mode != "OFFBOARD") {
|
||||
throw std::runtime_error("Copter is not in OFFBOARD mode");
|
||||
}
|
||||
}
|
||||
|
||||
static mavros_msgs::SetMode sm;
|
||||
sm.request.custom_mode = "AUTO.LAND";
|
||||
|
||||
@@ -688,6 +695,7 @@ int main(int argc, char **argv)
|
||||
nh.param<string>("mavros/local_position/tf/child_frame_id", fcu_frame, "base_link");
|
||||
nh_priv.param("target_frame", target.child_frame_id, string("navigate_target"));
|
||||
nh_priv.param("auto_release", auto_release, true);
|
||||
nh_priv.param("land_only_in_offboard", land_only_in_offboard, true);
|
||||
nh_priv.param("default_speed", default_speed, 0.5f);
|
||||
nh_priv.getParam("reference_frames", reference_frames);
|
||||
|
||||
|
||||
|
Before Width: | Height: | Size: 83 KiB After Width: | Height: | Size: 83 KiB |
|
Before Width: | Height: | Size: 180 KiB After Width: | Height: | Size: 227 KiB |
BIN
docs/assets/en/1_10.png
Normal file
|
After Width: | Height: | Size: 272 KiB |
BIN
docs/assets/en/1_12.png
Normal file
|
After Width: | Height: | Size: 27 KiB |
BIN
docs/assets/en/1_13.png
Normal file
|
After Width: | Height: | Size: 79 KiB |
BIN
docs/assets/en/1_5.png
Normal file
|
After Width: | Height: | Size: 143 KiB |
BIN
docs/assets/en/1_6.png
Normal file
|
After Width: | Height: | Size: 15 KiB |
BIN
docs/assets/en/1_7.png
Normal file
|
After Width: | Height: | Size: 14 KiB |
BIN
docs/assets/en/1_8.png
Normal file
|
After Width: | Height: | Size: 15 KiB |
BIN
docs/assets/en/additonal_eqipment.jpg
Normal file
|
After Width: | Height: | Size: 268 KiB |
BIN
docs/assets/en/calculation.png
Normal file
|
After Width: | Height: | Size: 29 KiB |
BIN
docs/assets/en/cl3_connectionESC4in1.jpg
Normal file
|
After Width: | Height: | Size: 431 KiB |
BIN
docs/assets/en/cl3_mountBEC.JPG
Normal file
|
After Width: | Height: | Size: 656 KiB |
BIN
docs/assets/en/cl3_mountElements.JPG
Normal file
|
After Width: | Height: | Size: 350 KiB |
BIN
docs/assets/en/cl3_mountRpiCamera.JPG
Normal file
|
After Width: | Height: | Size: 683 KiB |
BIN
docs/assets/en/cl3_prepareMotors.JPG
Normal file
|
After Width: | Height: | Size: 305 KiB |
BIN
docs/assets/en/conditional_refer.jpg
Normal file
|
After Width: | Height: | Size: 265 KiB |
BIN
docs/assets/en/connectionPixhawk.png
Normal file
|
After Width: | Height: | Size: 171 KiB |
BIN
docs/assets/en/consistofTransmitter.jpg
Normal file
|
After Width: | Height: | Size: 318 KiB |
BIN
docs/assets/en/cutwire14AWG.jpg
Normal file
|
After Width: | Height: | Size: 102 KiB |
BIN
docs/assets/en/fpv_1.png
Normal file
|
After Width: | Height: | Size: 61 KiB |
BIN
docs/assets/en/fpv_2.png
Normal file
|
After Width: | Height: | Size: 224 KiB |
BIN
docs/assets/en/fpv_3.png
Normal file
|
After Width: | Height: | Size: 627 KiB |
BIN
docs/assets/en/fpv_4.png
Normal file
|
After Width: | Height: | Size: 467 KiB |
BIN
docs/assets/en/mount5vconnector.jpg
Normal file
|
After Width: | Height: | Size: 228 KiB |
BIN
docs/assets/en/oscillRoll.jpg
Normal file
|
After Width: | Height: | Size: 70 KiB |
BIN
docs/assets/en/safetyPower.png
Normal file
|
After Width: | Height: | Size: 61 KiB |
BIN
docs/assets/en/table.png
Normal file
|
After Width: | Height: | Size: 52 KiB |
BIN
docs/assets/en/zapPDBtest.jpg
Normal file
|
After Width: | Height: | Size: 140 KiB |
BIN
docs/assets/esp8266_flashing_ftdi.jpg
Normal file
|
After Width: | Height: | Size: 64 KiB |
BIN
docs/assets/esp8266_pixracer_connection.jpg
Normal file
|
After Width: | Height: | Size: 82 KiB |
BIN
docs/assets/esp8266_pixracer_top_wifi.jpg
Normal file
|
After Width: | Height: | Size: 94 KiB |
BIN
docs/assets/esp8266_qgroundcontrol.png
Normal file
|
After Width: | Height: | Size: 175 KiB |
BIN
docs/assets/esp8266_qgroundcontrol_settings.png
Normal file
|
After Width: | Height: | Size: 113 KiB |
BIN
docs/assets/esp8266_web_interface.png
Normal file
|
After Width: | Height: | Size: 52 KiB |
BIN
docs/assets/gpio_mosfet_magnet.png
Normal file
|
After Width: | Height: | Size: 11 KiB |
BIN
docs/assets/op.png
Normal file
|
After Width: | Height: | Size: 29 KiB |
BIN
docs/assets/travis-instruction-0.png
Normal file
|
After Width: | Height: | Size: 155 KiB |
BIN
docs/assets/travis-instruction-1.png
Normal file
|
After Width: | Height: | Size: 141 KiB |
BIN
docs/assets/travis-instruction-10.png
Normal file
|
After Width: | Height: | Size: 72 KiB |
BIN
docs/assets/travis-instruction-11.png
Normal file
|
After Width: | Height: | Size: 209 KiB |
BIN
docs/assets/travis-instruction-12.png
Normal file
|
After Width: | Height: | Size: 186 KiB |
BIN
docs/assets/travis-instruction-2.png
Normal file
|
After Width: | Height: | Size: 32 KiB |
BIN
docs/assets/travis-instruction-3.png
Normal file
|
After Width: | Height: | Size: 142 KiB |
BIN
docs/assets/travis-instruction-4.png
Normal file
|
After Width: | Height: | Size: 68 KiB |
BIN
docs/assets/travis-instruction-5.png
Normal file
|
After Width: | Height: | Size: 142 KiB |
BIN
docs/assets/travis-instruction-6.png
Normal file
|
After Width: | Height: | Size: 132 KiB |
BIN
docs/assets/travis-instruction-7.png
Normal file
|
After Width: | Height: | Size: 78 KiB |
BIN
docs/assets/travis-instruction-8.png
Normal file
|
After Width: | Height: | Size: 145 KiB |
BIN
docs/assets/travis-instruction-9.png
Normal file
|
After Width: | Height: | Size: 166 KiB |
@@ -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.
|
||||
|
||||

|
||||

|
||||
|
||||
@@ -43,12 +43,15 @@
|
||||
* [Working with a LED strip on Raspberry 3](leds.md)
|
||||
* [Using rviz and rqt](rviz.md)
|
||||
* [Working with the ultrasonic distance gage](sonar.md)
|
||||
* [Working with a laser rangefinder](laser.md)
|
||||
* [PX4 Simulation](sitl.md)
|
||||
* [Software autorun](autolaunch.md)
|
||||
* [Controlling the copter from Arduino](arduino.md)
|
||||
* [Using an external 3G modem](3g.md)
|
||||
* Clever-based projects
|
||||
* [Copter spheric guard](shield.md)
|
||||
* [Face recognition system](face_recognition.md)
|
||||
* [An Android transmitter](android.md)
|
||||
* [Copter Hack 2018](copterhack2018.md)
|
||||
* [Copter Hack 2017](copterhack2017.md)
|
||||
* Supplementary materials
|
||||
@@ -56,5 +59,7 @@
|
||||
* [Flashing ESCs using BLHeliSuite](esc_firmware.md)
|
||||
* [MAVLink](mavlink.md)
|
||||
* [PX4 Logs and Topics](flight_logs.md)
|
||||
* [Camera calibration](calibration.md)
|
||||
* [Working with IR sensors on Raspberry Pi 3](ir_sensors.md)
|
||||
* Textbook
|
||||
* [Theory and Videos](lessons.md)
|
||||
|
||||
141
docs/en/android.md
Normal file
@@ -0,0 +1,141 @@
|
||||
# An Android transmitter
|
||||
|
||||
As early as in the frosty January 2018, all owners of Apple mobile devices got a nice Wi-Fi piloting app for iOS. And now, a year later, such an application is available for another operating system. The latest version may be downloaded [**here**](https://vk.com/away.php?to=https%3A%2F%2Fplay.google.com%2Fstore%2Fapps%2Fdetails%3Fid%3Dexpress.copter.cleverrc&cc_key=).
|
||||
|
||||
## Introduction
|
||||
|
||||
In this article, I will tell you how to write your own or modify an existing transmitter for Android yourself. We will use the popular language *Kotlin*, and we will use *Android Studio* for an IDE. For those who never used it, I recommend reading the following [*materials*](https://www.google.com/search?ei=xQxDXMH0C8OOmgW4mYigDQ&q=%D0%A7%D1%82%D0%BE+%D0%B4%D0%B5%D0%BB%D0%B0%D1%82%D1%8C+%D0%B5%D1%81%D0%BB%D0%B8+%D1%8F+%D0%BD%D0%B5+%D1%83%D0%BC%D0%B5%D1%8E+%D0%BF%D0%B8%D1%81%D0%B0%D1%82%D1%8C+%D0%BF%D0%BE%D0%B4+%D0%B0%D0%BD%D0%B4%D1%80%D0%BE%D0%B8%D0%B4%3F&oq=%D0%A7%D1%82%D0%BE+%D0%B4%D0%B5%D0%BB%D0%B0%D1%82%D1%8C+%D0%B5%D1%81%D0%BB%D0%B8+%D1%8F+%D0%BD%D0%B5+%D1%83%D0%BC%D0%B5%D1%8E+%D0%BF%D0%B8%D1%81%D0%B0%D1%82%D1%8C+%D0%BF%D0%BE%D0%B4+%D0%B0%D0%BD%D0%B4%D1%80%D0%BE%D0%B8%D0%B4%3F&gs_l=psy-ab.3...4413.17423..17726...9.0..2.442.4577.45j5j1j0j1....2..0....1..gws-wiz.....6..0i71j35i39j0i131j0j0i67j0i131i67j0i22i30j33i22i29i30j33i21j33i160.0bZz-WGxoHY). The entire application code can be found [**here**](https://github.com/Tennessium/android). If you want to immediately get an app to further tuning, run the following command:
|
||||
|
||||
```Bash
|
||||
git clone https://github.com/Tennessium/android
|
||||
```
|
||||
|
||||
However, to make you fully understand the application, I will tell you about each stage of the project, as if you were building it from scratch.
|
||||
|
||||
## Wrapper
|
||||
|
||||
Let's start with the simplest thing — the appearance of our application. At [**GitHub**](https://github.com/CopterExpress/clever/tree/master/apps/android/app/src/main/assets), you can find *HTML*, *CSS* and *JavaScript* files, which make up the web page to be used for controlling the copter. To have this page displayed in our application, do the following:
|
||||
|
||||
1. Create folder **assets** in the main folder of the app named **app**
|
||||
|
||||
2. Add to it all files from [here](https://github.com/CopterExpress/clever/tree/master/apps/android/app/src/main/assets)
|
||||
|
||||
If you reached this stage, you already have the web page you want, congratulations! Now we have to display it somehow in the app. To do this, in class *activity* in method **onCreate**, write the following code:
|
||||
|
||||
```Kotlin
|
||||
main_web.loadUrl("file:///android_asset/index.html")
|
||||
```
|
||||
|
||||
Where *main_web* is the ID of your *WebView*, which is in the *xml* file of the *activity* selected by you.
|
||||
|
||||
Unfortunately, the quadcopter transmitter requires the entire screen of the device, while the interface elements of the system interfere with full-fledged use of the program. For this purpose, at the beginning of method **onCreate**, call the following function:
|
||||
|
||||
```Kotlin
|
||||
private fun fullScreenCall() {
|
||||
window.setFlags(WindowManager.LayoutParams.FLAG_FULLSCREEN, WindowManager.LayoutParams.FLAG_FULLSCREEN)
|
||||
if (Build.VERSION.SDK_INT < 19) {
|
||||
val v = this.window.decorView
|
||||
v.systemUiVisibility = View.GONE
|
||||
} else {
|
||||
//for higher API versions.
|
||||
val decorView = window.decorView
|
||||
val uiOptions = View.SYSTEM_UI_FLAG_HIDE_NAVIGATION or View.SYSTEM_UI_FLAG_IMMERSIVE_STICKY
|
||||
decorView.systemUiVisibility = uiOptions
|
||||
}
|
||||
}
|
||||
```
|
||||
|
||||
This feature allows getting rid of the system interface elements. Let's go ahead.
|
||||
|
||||
This is how the transmitter looks at this stage:
|
||||
|
||||
<img src="../assets/IMG_4397.PNG" width="50%">
|
||||
|
||||
If you run your application, you will see that the sticks are not functioning. This is due to the fact that *JavaScript* is disabled in our page. To enable it, write the following code:
|
||||
|
||||
```Kotlin
|
||||
main_web.settings.apply {
|
||||
domStorageEnabled = true
|
||||
javaScriptEnabled = true
|
||||
loadWithOverviewMode = true
|
||||
useWideViewPort = true
|
||||
setSupportZoom(false)
|
||||
}
|
||||
```
|
||||
|
||||
This piece of code allows the page to use *JavaScript* and at the same time prepares for the next stage - **logics**.
|
||||
|
||||
## Receiving data from the web page
|
||||
|
||||
To let your phone receive data from the *HTML page*, create a class for interacting with the web interface
|
||||
|
||||
```Kotlin
|
||||
class WebAppInterface(c: Context) {
|
||||
@JavascriptInterface
|
||||
public fun postMessage(message: String) {
|
||||
val data = JSONObject(message)
|
||||
send("255.255.255.255", 35602, pack(
|
||||
data.getInt("x").toShort(),
|
||||
data.getInt("y").toShort(),
|
||||
data.getInt("z").toShort(),
|
||||
data.getInt("r").toShort()))
|
||||
}
|
||||
}
|
||||
```
|
||||
|
||||
This class will receive messages from the web page sent by the *postMessage* where argument *message* is the message from the page.
|
||||
|
||||
Now we have to link classes **WebAppInterface** and **MainActivity**. For this you have to add just one line to method **onCreate**:
|
||||
|
||||
```Kotlin
|
||||
main_web.addJavascriptInterface(WebAppInterface(this), "appInterface")
|
||||
```
|
||||
|
||||
## Sending data to the copter
|
||||
|
||||
**Important!**
|
||||
For working in Internet in the *Android* platform, add the following line to tag *manifest* in file **AndroidManifest.xml**:
|
||||
|
||||
```XML
|
||||
<uses-permission android:name="android.permission.INTERNET"/>
|
||||
```
|
||||
|
||||
It will grant your application access to the Internet, and the ability to send data via **Wi-Fi**. And you will now learn how to do that. Let's go ahead.
|
||||
|
||||
You have probably noticed function *send* in class **WebAppInterface**. It is this function that sends data to the copter. Let's declare it **outside classes**:
|
||||
|
||||
```Kotlin
|
||||
fun send(host: String, port: Int, data: ByteArray, senderPort: Int = 0): Boolean {
|
||||
var ret = false
|
||||
var socket: DatagramSocket? = null
|
||||
try {
|
||||
socket = DatagramSocket(senderPort)
|
||||
val address = InetAddress.getByName(host)
|
||||
val packet = DatagramPacket(data, data.size, address, port)
|
||||
socket.send(packet)
|
||||
ret = true
|
||||
} catch (e: Exception) {
|
||||
e.printStackTrace()
|
||||
} finally {
|
||||
socket?.close()
|
||||
}
|
||||
return ret
|
||||
}
|
||||
```
|
||||
|
||||
This function sends data via the [*user datagram protocol*](https://www.google.com/search?q=udp+%D0%BF%D1%80%D0%BE%D1%82%D0%BE%D0%BA%D0%BE%D0%BB&oq=udp+&aqs=chrome.0.69i59j69i57j35i39j0l3.1434j1j7&sourceid=chrome&ie=UTF-8) to the copter. The program sends **bytes**, so it would be a good idea to declare the function for creating an array of **bytes** from four variables:
|
||||
|
||||
```Kotlin
|
||||
fun pack(x: Short, y: Short, z: Short, r: Short): ByteArray {
|
||||
val pump_on_buf: ByteBuffer = ByteBuffer.allocate(8)
|
||||
pump_on_buf.putShort(r)
|
||||
pump_on_buf.putShort(z)
|
||||
pump_on_buf.putShort(y)
|
||||
pump_on_buf.putShort(x)
|
||||
return pump_on_buf.array().reversedArray()
|
||||
}
|
||||
```
|
||||
|
||||
## Summary
|
||||
|
||||
Now your app has the full functionality of its analog for **iOS**. You can customize it as you wish. For any questions about the app, contact us in Telegram @Tenessinum.
|
||||
@@ -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 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 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)
|
||||
|
||||

|
||||

|
||||
|
||||
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
|
||||
|
||||

|
||||

|
||||
|
||||
#### 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)
|
||||
|
||||

|
||||

|
||||
|
||||
### ESC assembly
|
||||
|
||||
|
||||
@@ -14,11 +14,11 @@ TODO
|
||||
|
||||
## Additional equipment
|
||||
|
||||

|
||||

|
||||
|
||||
## Conventional symbols
|
||||
|
||||

|
||||

|
||||
|
||||
## Installation of motors
|
||||
|
||||
@@ -36,7 +36,7 @@ TODO
|
||||
|
||||
Cut the remaining part of the clamp (tie wrap) with scissors.
|
||||
|
||||

|
||||

|
||||
|
||||
## 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.
|
||||
|
||||

|
||||

|
||||
|
||||
## Installation of the BEC voltage converter (to be soldered and tested)
|
||||
|
||||
@@ -93,7 +93,7 @@ TODO
|
||||
Black -> GND
|
||||
Blue -> Din
|
||||
|
||||

|
||||

|
||||
|
||||
## 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).
|
||||
|
||||

|
||||

|
||||
|
||||
## Installation of the remaining structural elements
|
||||
|
||||
|
||||
@@ -56,4 +56,4 @@ When scripting languages are used, [shebang] should be placed at the beginning o
|
||||
|
||||
```(bash)
|
||||
#!/usr/bin/env python
|
||||
```
|
||||
```
|
||||
|
||||
@@ -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).
|
||||
|
||||

|
||||

|
||||
|
||||
228
docs/en/calibration.md
Normal file
@@ -0,0 +1,228 @@
|
||||
# Camera calibration
|
||||
|
||||
Computer vision is becoming more and more widespread. Often, computer vision algorithms are not precise and obtain distorted images from the camera, which is especially true for fisheye cameras.
|
||||
|
||||

|
||||
|
||||
> The image is "rounded" closer to the edge.
|
||||
|
||||
Any computer vision algorithm will perceive the picture incorrectly. To remove such distortion, the camera that receives the image is to be calibrated in accordance with its own peculiarities.
|
||||
|
||||
## Script installation
|
||||
|
||||
First, you have to install the necessary libraries:
|
||||
|
||||
```
|
||||
pip install numpy
|
||||
pip install opencv-python
|
||||
pip install glob
|
||||
pip install pyyaml
|
||||
pip install urllib.request
|
||||
```
|
||||
|
||||
Then download the script from the repository:
|
||||
|
||||
```(bash)
|
||||
git clone https://github.com/tinderad/clever_cam_calibration.git
|
||||
```
|
||||
|
||||
Go to the downloaded folder and install the script:
|
||||
|
||||
```(bash)
|
||||
cd clever_cam_calibration
|
||||
sudo python setup.py build
|
||||
sudo python setup.py install
|
||||
```
|
||||
|
||||
If you are using Windows, download the archive from the [repository](https://github.com/tinderad/clever_cam_calibration/archive/master.zip), unzip it and install:
|
||||
|
||||
```(bash)
|
||||
cd path\to\archive\clever_cam_calibration\
|
||||
python setup.py build
|
||||
python setup.py install
|
||||
```
|
||||
|
||||
> path\to\archive – path to unpacked archive.
|
||||
|
||||
## Preparing for calibration
|
||||
|
||||
You will have to prepare a calibration target. It looks like a chessboard. The file is available for downloading [here](https://www.oreilly.com/library/view/learning-opencv-3/9781491937983/assets/lcv3_ac01.png).
|
||||
Glue a printed target to any solid surface. Count the number of intersections on the board lengthwise and widthwise, measure the size of a cell (mm).
|
||||
|
||||

|
||||
|
||||
Turn on Clever and connect to its Wi-Fi.
|
||||
|
||||
> Navigate to 192.168.11.1:8080 and check whether the computer receives images from the image_raw topic.
|
||||
|
||||
## Calibration
|
||||
|
||||
Run script **_calibrate_cam_**:
|
||||
|
||||
**Windows:**
|
||||
|
||||
```(bash)
|
||||
>path\to\python\Scripts\calibrate_cam.exe
|
||||
```
|
||||
|
||||
> path\to\Python – path to the Python folder
|
||||
|
||||
**Linux:**
|
||||
|
||||
```(bash)
|
||||
>calibrate_cam
|
||||
```
|
||||
|
||||
Specify board parameters:
|
||||
|
||||
```(bash)
|
||||
>calibrate_cam
|
||||
Chessboard width: # Intersections widthwise
|
||||
Chessboard height: # Intersections heightwise
|
||||
Square size: # Length of cell edge (mm)
|
||||
Saving mode (YES - on): # Save mode
|
||||
```
|
||||
|
||||
> Save mode: if enabled, all received pictures will be saved in the current folder.
|
||||
|
||||
The script will start running:
|
||||
|
||||
```
|
||||
Calibration started!
|
||||
Commands:
|
||||
help, catch (key: Enter), delete, restart, stop, finish
|
||||
```
|
||||
|
||||
To calibrate the camera, make at least 25 photos of the chessboard at various angles.
|
||||
|
||||

|
||||
|
||||
To make a photo, enter command **_catch_**.
|
||||
|
||||
```(bash)
|
||||
>catch
|
||||
```
|
||||
|
||||
The program will inform you about the calibration status.
|
||||
|
||||
```(bash)
|
||||
...
|
||||
Chessboard not found, now 0 (25 required)
|
||||
> # Enter
|
||||
---
|
||||
Image added, now 1 (25 required)
|
||||
```
|
||||
|
||||
> Instead of entering command **_catch_** each time, you can just press **_Enter_** (enter a blank line).
|
||||
|
||||
After you have made a sufficient number of images, enter command **_finish_**.
|
||||
|
||||
```(bash)
|
||||
...
|
||||
>finish
|
||||
Calibration successful!
|
||||
```
|
||||
|
||||
### Calibration by the existing images
|
||||
|
||||
If you already have images, you can calibrate the camera by them with the help of script **_calibrate_cam_ex_**.
|
||||
|
||||
```(bash)
|
||||
>calibrate_cam_ex
|
||||
```
|
||||
|
||||
Specify target characteristics and the path to the folder with images:
|
||||
|
||||
```(bash)
|
||||
>calibrate_cam_ex
|
||||
Chessboard width: # Intersections widthwise
|
||||
Chessboard height: # Intersections heightwise
|
||||
Square size: # Length of cell edge (mm)
|
||||
Path: # Path to the folder with images
|
||||
```
|
||||
|
||||
Apart from that, this script works similarly to **_calibrate_cam_**.
|
||||
|
||||
The program will process all received pictures, and create file **_camera_info_****_._****_yaml_** in the current folder. Using this file, you can equalize distortions in the images obtained from this camera.
|
||||
|
||||
> If you change the resolution of the received image, you will have to re-calibrate the camera.
|
||||
|
||||
## Correcting distortions
|
||||
|
||||
Function **_get_undistorted_image(cv2_image, camera_info)_** is responsible for obtaining a corrected image:
|
||||
|
||||
* **_cv2_image_**: An image encoded into a cv2 array.
|
||||
* **_camera_****___****_info_**: The path to the calibration file.¬
|
||||
|
||||
The function returns a cv2 array, into which the corrected image is coded.
|
||||
|
||||
> If you are using a fisheye camera provided with Clever, for processing images with resolution 320x240 or 640x480, you can use the existing calibration settings. To do this, pass parameters **_clever_cam_calibration.clevercamcalib.CLEVER_FISHEYE_CAM_320_** or **_clever_cam_calibration.clevercamcalib.CLEVER_FISHEYE_CAM_640_** as argument **_camera_info_**, respectively.
|
||||
|
||||
## Examples of operation
|
||||
|
||||
Source images:
|
||||
|
||||

|
||||
|
||||

|
||||
|
||||
Corrected images:
|
||||
|
||||

|
||||
|
||||

|
||||
|
||||
## An example of usage
|
||||
|
||||
**Processing image stream from the camera**.
|
||||
|
||||
This program receives images from the camera on Clever and displays them on the screen in corrected for, using the existing calibration file.
|
||||
|
||||
```python
|
||||
import clevercamcalib.clevercamcalib as ccc
|
||||
import cv2
|
||||
import urllib.request
|
||||
import numpy as np
|
||||
while True:
|
||||
req = urllib.request.urlopen('http://192.168.11.1:8080/snapshot?topic=/main_camera/image_raw')
|
||||
arr = np.asarray(bytearray(req.read()), dtype=np.uint8)
|
||||
image = cv2.imdecode(arr, -1)
|
||||
undistorted_img = ccc.get_undistorted_image(image, ccc.CLEVER_FISHEYE_CAM_640)
|
||||
cv2.imshow("undistort", undistorted_img)
|
||||
cv2.waitKey(33)
|
||||
cv2.destroyAllWindows()
|
||||
```
|
||||
|
||||
## The usage for ArUco
|
||||
|
||||
To apply the calibration parameters to the ArUco navigation system, move the calibration .yaml file to Raspberry Pi of Clever, and initialize it.
|
||||
|
||||
> Don't forget to connect to Wi-Fi of Clever.
|
||||
|
||||
The SFTP protocol is used for transferring the file. This example, WinSCP program is used.
|
||||
|
||||
Connect to Raspberry Pi via SFTP:
|
||||
|
||||
> Password: _**raspberry**_
|
||||
|
||||

|
||||
|
||||
Press “Enter”. Go to _**/home/pi/catkin_ws/src/clever/clever/camera_info/**_, and copy the calibration .yaml file to this folder:
|
||||
|
||||

|
||||
|
||||
Now we have to select this file in ArUco configuration. Connection via SSH is used for this purpose. This example, PuTTY program is used.
|
||||
|
||||
Connect to Raspberry Pi via SSH:
|
||||
|
||||

|
||||
|
||||
Log in with username _**pi**_ and password _**raspberry**_, go to directory _**/home/pi/catkin_ws/src/clever/clever/launch**_ and start editing configuration _**main_camera.launch**_:
|
||||
|
||||

|
||||
|
||||
In line _**camera node**_, change parameter _**camera_info**_ to _**camera_info.yaml**_:
|
||||
|
||||

|
||||
|
||||
> Don't forget to change camera resolution.
|
||||
@@ -60,4 +60,4 @@ The first image — how a copter model looks in rviz with these settings, the se
|
||||
```
|
||||
|
||||
<img src="../assets/camera_option_4_rviz.png" width=400>
|
||||
<img src="../assets/camera_option_4_clever.jpg" width=400>
|
||||
<img src="../assets/camera_option_4_clever.jpg" width=400>
|
||||
|
||||
@@ -34,4 +34,4 @@ Winning teams:
|
||||
4. International Post (Novosibirsk) — automatic scattering leaflets from the drone.
|
||||
5. LAMAR (Yekaterinburg) — an automatic quadcopter battery replacement station.
|
||||
|
||||
<img src="../assets/alcopter.jpg" title="Alcopter Team" height=300px>
|
||||
<img src="../assets/alcopter.jpg" title="Alcopter Team" height=300px>
|
||||
|
||||
163
docs/en/face_recognition.md
Normal file
@@ -0,0 +1,163 @@
|
||||
# Face recognition system
|
||||
|
||||
## Introduction
|
||||
|
||||
Recently, face recognition systems have been getting a wider use, the application scope of this technology is really expansive: from regular selfie drones to police drones. Everywhere it is being integrated into various devices. The recognition process itself is really fascinating, and that's what inspired me to create a project associated with it. The purpose of my internship project was to create a simple open source system for face recognition with a Clever quadcopter. The program takes images from the quadcopter's camera and processes it on a PC. Therefore, all other instructions are executed on a PC.
|
||||
|
||||
## Development
|
||||
|
||||
The first task was finding a recognition algorithm. As a solution to the problem, [a ready API for Python](https://github.com/ageitgey/face_recognition) was chosen. This API combines several advantages: recognition speed and accuracy, and ease of use.
|
||||
|
||||
## Installation
|
||||
|
||||
First, you have to install all the necessary libraries:
|
||||
|
||||
```(bash)
|
||||
pip install face_recognition
|
||||
pip install opencv-python
|
||||
```
|
||||
|
||||
Then download the script from the repository:
|
||||
|
||||
```(bash)
|
||||
git clone https://github.com/mmkuznecov/face_recognition_from_clever.git
|
||||
```
|
||||
|
||||
## Code explanation
|
||||
|
||||
Enable libraries:
|
||||
|
||||
```python
|
||||
import face_recognition
|
||||
import cv2
|
||||
import os
|
||||
import urllib.request
|
||||
import numpy as np
|
||||
```
|
||||
|
||||
***This part of the code is intended for Python 3. In Python 2.7, enable urllib2 instead of urllib:***
|
||||
|
||||
```python
|
||||
import urllib2
|
||||
```
|
||||
|
||||
Create a list of encodings for images and a list of names:
|
||||
|
||||
```python
|
||||
faces_images=[]
|
||||
for i in os.listdir('faces/'):
|
||||
faces_images.append(face_recognition.load_image_file('faces/'+i))
|
||||
known_face_encodings=[]
|
||||
for i in faces_images:
|
||||
known_face_encodings.append(face_recognition.face_encodings(i)[0])
|
||||
known_face_names=[]url
|
||||
for i in os.listdir('faces/'):
|
||||
i=i.split('.')[0]
|
||||
known_face_names.append(i)
|
||||
```
|
||||
|
||||
***Addition: all images are stored in folder faces in format name.jpg***
|
||||
|
||||
<img src="../assets/screen.jpg" width="50%">
|
||||
|
||||
<img src="../assets/Mikhail.jpg" width="30%">
|
||||
|
||||
<img src="../assets/Timofey.jpg" width="30%">
|
||||
|
||||
Initialize some variables:
|
||||
|
||||
```python
|
||||
face_locations = []
|
||||
face_encodings = []
|
||||
face_names = []
|
||||
process_this_frame = True
|
||||
```
|
||||
|
||||
Get the image from the server, and convert it to format cv2:
|
||||
|
||||
```python
|
||||
req = urllib.request.urlopen('http://192.168.11.1:8080/snapshot?topic=/main_camera/image_raw')
|
||||
arr = np.asarray(bytearray(req.read()), dtype=np.uint8)
|
||||
frame = cv2.imdecode(arr, -1)
|
||||
```
|
||||
|
||||
***For Python 2.7:***
|
||||
|
||||
```python
|
||||
req = urllib2.urlopen('http://192.168.11.1:8080/snapshot?topic=/main_camera/image_raw')
|
||||
arr = np.asarray(bytearray(req.read()), dtype=np.uint8)
|
||||
frame = cv2.imdecode(arr, -1)
|
||||
```
|
||||
|
||||
Further explanation of the code is available at GitHub of the used API in the comments to [the next script](https://github.com/ageitgey/face_recognition/blob/master/examples/facerec_from_webcam_faster.py)
|
||||
|
||||
## Using
|
||||
|
||||
It is enough to connect to "Clever" via Wi-Fi and check whether the video stream from the camera is working correctly.
|
||||
|
||||
Then just run the script:
|
||||
|
||||
```(bash)
|
||||
python recog.py
|
||||
```
|
||||
|
||||
And the output:
|
||||
|
||||
<img src="../assets/Mikhail_output.jpg" width="50%">
|
||||
|
||||
<img src="../assets/Timofey_output.jpg" width="50%">
|
||||
|
||||
## Possible difficulties
|
||||
|
||||
When the script is started, the following error may pop up:
|
||||
|
||||
```python
|
||||
known_face_encodings.append(face_recognition.face_encodings(i)[0])
|
||||
IndexError: list index out of range
|
||||
```
|
||||
|
||||
In this case, try to edit the images in folder faces, perhaps the program cannot recognize faces in the images due to poor quality.
|
||||
|
||||
## Using the calibration
|
||||
|
||||
To improve recognition accuracy, you can use camera calibration. The calibration module may be installed using [a special package](https://github.com/tinderad/clever_cam_calibration). Instructions for installation and use are available in file calibration.md. The program that uses the calibration package is named recog_undist.py
|
||||
|
||||
**Code brief explanation:**
|
||||
|
||||
Enable installed package:
|
||||
|
||||
```python
|
||||
import clever_cam_calibration.clevercamcalib as ccc
|
||||
```
|
||||
|
||||
Add the following lines:
|
||||
|
||||
```python
|
||||
height_or, width_or, depth_or = frame.shape
|
||||
```
|
||||
|
||||
This way, you will obtain information about image size, where height_or is the height of the initial image in pixels, and width_or is the width of the initial image.
|
||||
Then correct distortions in the initial image, and get its parameters:
|
||||
|
||||
```python
|
||||
if height_or==240 and width_or==320:
|
||||
frame=ccc.get_undistorted_image(frame,ccc.CLEVER_FISHEYE_CAM_320)
|
||||
elif height_or==480 and width_or==640:
|
||||
frame=ccc.get_undistorted_image(frame,ccc.CLEVER_FISHEYE_CAM_640)
|
||||
else:
|
||||
frame=ccc.get_undistorted_image(frame,input("Input your path to the .yaml file: "))
|
||||
height_unz, width_unz, depth_unz = frame.shape
|
||||
```
|
||||
|
||||
***In this case, we pass argument ссс.CLEVER_FISHEYE_CAM_640, since the resolution of the image in this example, is 640x480; you can also use ссс.CLEVER_FISHEYE_CAM_320 for resolution 320x240, otherwise you will have to send the path to the .yaml calibration file as the second argument.***
|
||||
|
||||
Finally, return the image to its initial size:
|
||||
|
||||
```python
|
||||
frame=cv2.resize(frame,(0,0), fx=(width_or/width_unz),fy=(height_or/height_unz))
|
||||
```
|
||||
|
||||
This was, you can significantly improve recognition accuracy since the image processed will not be so badly distorted.
|
||||
|
||||
<img src="../assets/misha_calib.jpg" width="50%">
|
||||
<img src="../assets/tim_calib.jpg" width="50%">
|
||||
@@ -50,4 +50,4 @@ To upload the `v3` firmware to Pixhawk, you may need the `force_upload` command:
|
||||
|
||||
```
|
||||
make px4fmu-v3_default force-upload
|
||||
```
|
||||
```
|
||||
|
||||
@@ -11,7 +11,7 @@
|
||||
|
||||
\* The distance between the power distribution board and the estimated location of the camera should be determined in advance!
|
||||
|
||||

|
||||

|
||||
|
||||
## Preparation of the transmitter
|
||||
|
||||
@@ -26,24 +26,24 @@ The same procedure applies here:
|
||||
|
||||
\* The distance between the power distribution board and the estimated location of the transmitter should be determined in advance!
|
||||
|
||||

|
||||

|
||||
|
||||
## 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:
|
||||
|
||||

|
||||

|
||||
|
||||
> **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
|
||||
|
||||

|
||||

|
||||
|
||||
The following may be used as fastening materials:
|
||||
|
||||
1. Hot-melt glue;
|
||||
1. electrical tape;
|
||||
1. zip-ties (clamps);
|
||||
1. double-sided adhesive tape.
|
||||
1. double-sided adhesive tape.
|
||||
|
||||
@@ -13,4 +13,4 @@ Main frames in package `clever`:
|
||||
|
||||
> **Hint** In accordance with [the agreement](http://www.ros.org/reps/rep-0103.html), for frames associated with the copter, the X-axis directed forward, Y – to the left, and Z – up.
|
||||
|
||||
More clearly, 3D visualization of the coordinate systems can be viewed using [rviz](rviz.md).
|
||||
More clearly, 3D visualization of the coordinate systems can be viewed using [rviz](rviz.md).
|
||||
|
||||