Compare commits

..

4 Commits

Author SHA1 Message Date
Oleg Kalachev
20a229a954 docs: add link to raspberry article in glossary 2019-08-09 00:50:30 +03:00
Oleg Kalachev
aae9eec42f docs: add more info to glossary 2019-08-09 00:48:56 +03:00
Oleg Kalachev
6e4e25a2cb docs: merge safety articles 2019-08-08 22:31:32 +03:00
Oleg Kalachev
11555d7d70 docs: start working on clever 4 instruction 2019-05-13 08:30:04 +03:00
41 changed files with 206 additions and 689 deletions

View File

@@ -67,6 +67,17 @@ jobs:
verbose: true
on:
branch: master
deploy:
provider: pages
local-dir: _book
skip-cleanup: true
github-token: ${GITHUB_OAUTH_TOKEN}
keep-history: false
target-branch: master
repo: okalachev/cl4wip
verbose: true
on:
branch: clever4
- stage: Annotate
name: Auto-generate changelog
language: python

View File

@@ -216,7 +216,4 @@ 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()

View File

@@ -36,7 +36,6 @@
#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>
@@ -179,13 +178,7 @@ public:
double center_x = 0, center_y = 0, center_z = 0;
alignObjPointsToCenter(obj_points, center_x, center_y, center_z);
// Step 1: Solve using EPnP
valid = solvePnP(obj_points, img_points, camera_matrix_, dist_coeffs_, rvec, tvec, false, cv::SOLVEPNP_EPNP);
// Step 2: Use iterative method to refine results
valid &= solvePnP(obj_points, img_points, camera_matrix_, dist_coeffs_, rvec, tvec, true);
// Step 3: Check tvec magnitude. Iterative method tends to diverge sometimes, and this divergence is not picked up
// by OpenCV code
valid &= norm(tvec) < 1e6;
valid = solvePnP(obj_points, img_points, camera_matrix_, dist_coeffs_, rvec, tvec, false);
if (!valid) goto publish_debug;
fillTransform(transform_.transform, rvec, tvec);
@@ -277,50 +270,10 @@ publish_debug:
std::istringstream s(line);
// 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
if (!(s >> id >> length >> x >> y >> z >> yaw >> pitch >> roll)) {
ROS_ERROR("aruco_map: cannot parse line: %s", line.c_str());
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);
}
@@ -386,19 +339,6 @@ publish_debug:
void addMarker(int id, double length, double x, double y, double z,
double yaw, double pitch, double roll)
{
// Check whether the id is in range for current dictionary
int num_markers = board_->dictionary->bytesList.rows;
if (num_markers <= id) {
ROS_ERROR("aruco_map: Marker id %d is not in dictionary; current dictionary contains %d markers. "
"Please see https://github.com/CopterExpress/clever/blob/master/aruco_pose/README.md#parameters for details",
id, num_markers);
return;
}
// Check if marker is already in the board
if (std::count(board_->ids.begin(), board_->ids.end(), id) > 0) {
ROS_ERROR("aruco_map: Marker id %d is already in the map", id);
return;
}
// Create transform
tf::Quaternion q;
q.setRPY(roll, pitch, yaw);

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

@@ -11,7 +11,7 @@
set -e # Exit immidiately on non-zero result
SOURCE_IMAGE="https://downloads.raspberrypi.org/raspbian_lite/images/raspbian_lite-2019-04-09/2019-04-08-raspbian-stretch-lite.zip"
SOURCE_IMAGE="https://downloads.raspberrypi.org/raspbian_lite/images/raspbian_lite-2018-11-15/2018-11-13-raspbian-stretch-lite.zip"
export DEBIAN_FRONTEND=${DEBIAN_FRONTEND:='noninteractive'}
export LANG=${LANG:='C.UTF-8'}

View File

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

View File

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

View File

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

View File

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

View File

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

View File

@@ -4,21 +4,16 @@ import math
import subprocess
import re
import traceback
from threading import Event
import numpy
import rospy
from systemd import journal
import tf2_ros
import tf2_geometry_msgs
from pymavlink import mavutil
from std_srvs.srv import Trigger
from sensor_msgs.msg import Image, CameraInfo, NavSatFix, Imu, Range
from mavros_msgs.msg import State, OpticalFlowRad, Mavlink
from mavros_msgs.msg import State, OpticalFlowRad
from mavros_msgs.srv import ParamGet
from geometry_msgs.msg import PoseStamped, TwistStamped, PoseWithCovarianceStamped, Vector3Stamped
from geometry_msgs.msg import PoseStamped, TwistStamped, PoseWithCovarianceStamped
import tf.transformations as t
from aruco_pose.msg import MarkerArray
from mavros import mavlink
from systemd import journal
# TODO: check attitude is present
@@ -33,41 +28,28 @@ from mavros import mavlink
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):
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)
failures.append(text % args)
def check(name):
def inner(fn):
def wrapper(*args, **kwargs):
failures[:] = []
infos[:] = []
global current_check
current_check = name
try:
fn(*args, **kwargs)
for f in failures:
rospy.logwarn('%s: %s', name, f)
except Exception as e:
for f in failures:
rospy.logwarn('%s: %s', name, f)
traceback.print_exc()
rospy.logerr('%s: exception occurred', name)
return
if not failures and not infos:
if not failures:
rospy.loginfo('%s: OK', name)
return wrapper
return inner
@@ -91,116 +73,36 @@ 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:
info('selected estimator: LPE')
rospy.loginfo('Selected estimator: LPE')
fuse = get_param('LPE_FUSION')
if fuse & (1 << 4):
info('LPE_FUSION: land detector fusion is enabled')
rospy.loginfo('LPE_FUSION: land detector fusion is enabled')
else:
info('LPE_FUSION: land detector fusion is disabled')
rospy.loginfo('LPE_FUSION: land detector fusion is disabled')
if fuse & (1 << 7):
info('LPE_FUSION: barometer fusion is enabled')
rospy.loginfo('LPE_FUSION: barometer fusion is enabled')
else:
info('LPE_FUSION: barometer fusion is disabled')
rospy.loginfo('LPE_FUSION: barometer fusion is disabled')
elif est == 2:
info('selected estimator: EKF2')
rospy.loginfo('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)')
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
@check('Camera')
def check_camera(name):
try:
img = rospy.wait_for_message(name + '/image_raw', Image, timeout=1)
@@ -208,86 +110,28 @@ def check_camera(name):
failure('%s: no images (is the camera connected properly?)', name)
return
try:
camera_info = rospy.wait_for_message(name + '/camera_info', CameraInfo, timeout=1)
info = rospy.wait_for_message(name + '/camera_info', CameraInfo, timeout=1)
except rospy.ROSException:
failure('%s: no calibration info', name)
return
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')
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)
@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')
@check('ArUco detector')
def check_aruco():
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')
try:
rospy.wait_for_message('aruco_detect/markers', MarkerArray, timeout=1)
except rospy.ROSException:
failure('no markers detection')
return
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')
try:
rospy.wait_for_message('aruco_map/pose', PoseWithCovarianceStamped, timeout=1)
except rospy.ROSException:
failure('no map detection')
@check('Vision position estimate')
@@ -316,14 +160,14 @@ def check_vpe():
if vision_yaw_w == 0:
failure('vision yaw weight is zero, change ATT_W_EXT_HDG parameter')
else:
info('Vision yaw weight: %.2f', vision_yaw_w)
rospy.loginfo('Vision yaw weight: %.2f', vision_yaw_w)
fuse = get_param('LPE_FUSION')
if not fuse & (1 << 2):
failure('vision position fusion is disabled, change LPE_FUSION parameter')
delay = get_param('LPE_VIS_DELAY')
if delay != 0:
failure('LPE_VIS_DELAY parameter is %s, but it should be zero', delay)
info('LPE_VIS_XY is %.2f m, LPE_VIS_Z is %.2f m', get_param('LPE_VIS_XY'), get_param('LPE_VIS_Z'))
rospy.loginfo('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):
@@ -333,7 +177,7 @@ def check_vpe():
delay = get_param('EKF2_EV_DELAY')
if delay != 0:
failure('EKF2_EV_DELAY is %.2f, but it should be zero', delay)
info('EKF2_EVA_NOISE is %.3f, EKF2_EVP_NOISE is %.3f',
rospy.loginfo('EKF2_EVA_NOISE is %.3f, EKF2_EVP_NOISE is %.3f',
get_param('EKF2_EVA_NOISE'),
get_param('EKF2_EVP_NOISE'))
@@ -452,7 +296,7 @@ def check_optical_flow():
if not numpy.isclose(scale, 1.0):
failure('LPE_FLW_SCALE parameter is %.2f, but it should be 1.0', scale)
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',
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'),
@@ -465,7 +309,7 @@ def check_optical_flow():
delay = get_param('EKF2_OF_DELAY')
if delay != 0:
failure('EKF2_OF_DELAY is %.2f, but it should be zero', delay)
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',
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'),
@@ -499,21 +343,21 @@ def check_rangefinder():
if est == 1:
fuse = get_param('LPE_FUSION')
if not fuse & (1 << 5):
info('"pub agl as lpos down" in LPE_FUSION is disabled, NOT operating over flat surface')
rospy.loginfo('"pub agl as lpos down" in LPE_FUSION is disabled, NOT operating over flat surface')
else:
info('"pub agl as lpos down" in LPE_FUSION is enabled, operating over flat surface')
rospy.loginfo('"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:
info('EKF2_HGT_MODE != Range sensor, NOT operating over flat surface')
rospy.loginfo('EKF2_HGT_MODE != Range sensor, NOT operating over flat surface')
else:
info('EKF2_HGT_MODE = Range sensor, operating over flat surface')
rospy.loginfo('EKF2_HGT_MODE = Range sensor, operating over flat surface')
aid = get_param('EKF2_RNG_AID')
if aid != 1:
info('EKF2_RNG_AID != 1, range sensor aiding disabled')
rospy.loginfo('EKF2_RNG_AID != 1, range sensor aiding disabled')
else:
info('EKF2_RNG_AID = 1, range sensor aiding enabled')
rospy.loginfo('EKF2_RNG_AID = 1, range sensor aiding enabled')
@check('Boot duration')
@@ -567,42 +411,14 @@ def check_clever_service():
failure(error)
@check('Image')
def check_image():
info('version: %s', open('/etc/clever_version').read().strip())
@check('Preflight status')
def check_preflight_status():
# Make sure the console is available to us
mavlink_exec('\n')
cmdr_output = mavlink_exec('commander check')
if cmdr_output == '':
failure('No data from FCU')
return
cmdr_lines = cmdr_output.split('\n')
r = re.compile(r'^(.*)(Preflight|Prearm) check: (.*)')
for line in cmdr_lines:
if 'WARN' in line:
failure(line[line.find(']') + 2:])
continue
match = r.search(line)
if match is not None:
check_status = match.groups()[2]
if check_status != 'OK':
failure(' '.join([match.groups()[1], 'check:', check_status]))
def selfcheck():
check_image()
check_clever_service()
check_fcu()
check_imu()
check_local_position()
check_velocity()
check_global_position()
check_preflight_status()
check_main_camera()
check_camera('main_camera')
check_aruco()
check_simpleoffboard()
check_optical_flow()

Binary file not shown.

Before

Width:  |  Height:  |  Size: 83 KiB

After

Width:  |  Height:  |  Size: 83 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 11 KiB

View File

@@ -3,8 +3,14 @@
* [Введение](README.md)
* [Глоссарий](gloss.md)
* Сборка
* [Сборка Клевера 2](assemble_2.md)
* [Сборка Клевера 3](assemble_3.md)
* Клевер 4
* [Комплект](clever4/equipment.md)
* [Рама](clever4/frame.md)
* [Пульт](clever4/rc.md)
* [Настройка](setup.md)
* [Клевер 3](assemble_2.md)
* [Клевер 2](assemble_3.md)
* [Захват](grab.md)
* [Установка FPV](fpv.md)
* [Безопасность](safety.md)
* [Подключение регулятора 4 в 1](4in1.md)
@@ -17,7 +23,7 @@
* Настройка
* [Первоначальная настройка](setup.md)
* [Полетные режимы](modes.md)
* [Прошивка полетного контролера](firmware.md)
* [Прошивка Pixhawk/Pixracer](firmware.md)
* [Параметры PX4](px4_parameters.md)
* [Настройка PID](calibratePID.md)
* Работа с Raspberry Pi
@@ -29,13 +35,13 @@
* [Настройка сети RPi](network.md)
* [Работа с QGroundControl через Wi-Fi](gcs_bridge.md)
* [Пилотирование со смартфона](rc.md)
* [Интерфейс UART](uart.md)
* [Просмотр видеострима с камер](web_video_server.md)
* [Системы координат](frames.md)
* [Интерфейс UART](uart.md)
* Программирование
* [ROS](ros.md)
* [MAVROS](mavros.md)
* [Автономный полет (OFFBOARD)](simple_offboard.md)
* [Автономный полет в OFFBOARD](simple_offboard.md)
* Визуальные маркеры (ArUco)
* [Общая информация](aruco.md)
* [Распознавание маркеров](aruco_marker.md)

View File

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

View File

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

View File

@@ -0,0 +1,5 @@
---
description: Комплект поставки конструктора квадрокоптера Клевер 4
---
# Комплект

5
docs/ru/clever4/frame.md Normal file
View File

@@ -0,0 +1,5 @@
---
description: Сборка рамы и корпуса, монтаж компонентов конструктора квадрокоптера Клевер 4
---
# Сборка рамы и монтаж компонентов

5
docs/ru/clever4/rc.md Normal file
View File

@@ -0,0 +1,5 @@
---
description: Установка и настройка пульта на квадрокоптере Клевер 4
---
# Установка и настройка пульта

View File

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

View File

@@ -15,6 +15,10 @@ Pixhawk, Ardupilot, Naze32, CC3D.
**2\.** Программное обеспечение для платы управления мультикоптером. Примеры: PX4, APM, CleanFlight.
## Прошивка
Программное обеспечение, управляющее работой какого-либо устройства, например, полетного контроллера или регулятора мотора (ESC).
## Мотор
Электродвигатель, который вращает винты мультикоптера. Обычно используются бесколлекторные электродвигатели. Такие двигатели подключаются к ESC.
@@ -43,11 +47,21 @@ ESC имеет прошивку, которая определяет особе
Armed состояние коптера готовности к полету. При поднятии стика газа либо при посылке внешней команды с целевой точкой – коптер полетит. Обычно коптер начинает вращать винтами при переходе в состояние "armed" даже если стик газа находится внизу.
Противолположным состоянием является Disarmed.
Противоположным состоянием является Disarmed.
## PX4
Популярный полетный контроллер с открытым исходным кодом, работащий на платах Pixhawk, Pixracer и других. PX4 рекомендуется для использования на Клевере.
Популярный полетный контроллер с открытым исходным кодом, работающий на платах Pixhawk, Pixracer и других. PX4 рекомендуется для использования на Клевере.
## Raspberry Pi
[Популярный одноплатный микрокомпьютер](raspberry.md), использующийся в конструкторе Клевер.
## Образ SD-карты
Полная копия содержимого SD-карты, представленная в виде файла. Такой файл можно зазгрузить на SD-карту, воспользовавшись специальной утилитой, например Etcher. SD-карта, вставленная в Raspberry Pi является единственным его долговременным хранилищем и полностью определяет, что он будет делать.
Конструктор Клевер включает в себя [рекомендованный образ для SD-карты](microsd_images.md).
## APM / ArduPilot

View File

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

View File

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

View File

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

View File

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

View File

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

View File

@@ -4,36 +4,40 @@
Пайка
-----
### Предварительный осмотр
<img src="../assets/stand.jpg" align=right width=200>
Перед началом работы, важно проверить целостность проводки и штепсельной вилки.
Повреждения могут привести к поражению пользователя током.
Работы, связанные с пайкой и лужением, должны проводиться в специально оборудованных и предварительно подготовленных помещениях. Обязательно должна присутствовать система вентиляции.
### Жало паяльника
Перед началом работы необходимо:
Жало паяльника нагревается до очень высокой температуры, поэтому, в случае его прикосновения к электрическому проводу в ходе пайки, изоляция будет повреждена в считанные мгновения, с последующим коротким замыканием.
1. Привести в порядок рабочее место, ничего не должно мешать процессу. Рабочее место должно быть хорошо освещено.
2. Проверить целостность проводки и штепсельной вилки.
3. Паяльник, находящийся в рабочем состоянии, установить в зоне действия местной вытяжной вентиляции, в специальную подставку.
4. Перед началом работы надеть защитный халат, очки и, при необходимости, перчатки.
### Подставка
Во время пайки:
При работе с горячим паяльником важно использовать подставку. В отсутствии заводской подставки, можно использовать изготовленную
из деревянного бруска и металлических держателей. Подставка позволяет расположить инструмент, без риска,
что он упадет на горючие материалы.
1. Паяльник следует держать только за ручку, так как жало имеет высокую температуру.
### Проветривание помещения
<img src="../assets/keep.png" width=300>
2. Жало паяльника нагревается до очень высокой температуры, поэтому, в случае его прикосновения к электрическому проводу в ходе пайки изоляция будет повреждена в считанные мгновения, с последующим коротким замыканием.
3. Для перемещения изделий применять специальные инструменты (пинцеты, клещи или другие инструменты), обеспечивающие безопасность при пайке.
4. Во избежание ожогов расплавленным припоем при распайке не выдергивать резко с большим усилием паяемые провода.
5. При пайке мелких и подвижных изделий пользоваться специальным держателем.
<img src="../assets/helphand.jpg" width=300>
6. Паяльник переносить за корпус, а не за провод или рабочую часть. При перерывах в работе паяльник отключать от электросети.
> **Caution** При обнаружении неисправной работы паяльника или возникновении возгорания отключить его от питающей электросети.
Канифоль и припой при плавлении выделяют значительное количество вредных веществ.
Настойчиво советуется проветривать помещение после каждой пайки.
Через каждые 30 минут нужно делать небольшие перерывы со сквозным проветриванием помещения и не забывать при этом отключать паяльник.
### Как держать паяльник?
Паяльник можно держать только за ручку.
Если кто-то утверждает обратное - не верьте, вас вводят в заблуждение:)
![Паяльник состав](../assets/solderConsist.gif)
[Подробнее о технике безопасности при пайке](tb.md)
Полеты
------
@@ -66,20 +70,17 @@
* При обучении полётам летать на уровне ниже собственного роста.
* Летать рядом с собой на расстоянии, на котором вам видна ориентация коптера в пространстве. Не улетать далеко от себя. В случае сомнений в ориентации коптера немедленно выполнить посадку на месте. Не пытаться взлететь. Подойти ближе к коптеру и выполнить взлёт.
* При управлении все движения стиками выполнять аккуратно и плавно. Не допускать резких движений. При необходимости изменить направление полёта двигать стиками следует энергично, но не резко.
> **Caution** Резкие движения стиками запрещаются. Движения стиками в края запрещаются.
* Летать следует осторожно и выполнять только те элементы, в которых нет сомнений. Запрещается выполнять фигуры пилотажа, в успехе которых возникают сомнения и фигуры, связанные с риском.
* Соблюдать скоростной режим. Скорость полёта коптера держать в пределах скорости идущего человека.
* Вернуть коптер к месту посадки к рассчитанному времени, не допускать полной разрядки аккумулятора в полёте.
* Посадку выполнять только на ровную открытую площадку вдали от препятствий
* Посадку выполнять только на ровную открытую площадку вдали от препятствий.
### Аварийная посадка
В случае удара об землю или жесткой посадки выполнить следующие действия:
1. Прекратить полёт. Посадить коптер на землю. Левый стик (газ) в минимум
2. Disarm (Левый стик влево-вниз на 3 секунды)
1. Прекратить полёт. Посадить коптер на землю. Левый стик (газ) в минимум.
2. Disarm (левый стик влево-вниз на 3 секунды).
3. Отключить Li-ion аккумулятор на коптере.
4. Выключить пульт.
5. Осмотреть коптер и при необходимости отремонтировать.
@@ -89,5 +90,5 @@
После запланированной посадки выполнить следующие действия:
1. Disarm (Левый стик влево-вниз на 3 секунды)
2. Отключить Li-ion аккумулятор на коптере.
2. Отключить Li-ion аккумулятор на коптере.
3. Выключить пульт.

View File

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

View File

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

View File

@@ -280,18 +280,12 @@ set_mode(custom_mode='STABILIZED')
def flip():
start = get_telemetry() # memorize starting position
set_rates(thrust=1) # bump up
rospy.sleep(0.2)
set_rates(roll_rate=20, thrust=0.2) # maximum roll rate
set_rates(roll_rate=5, thrust=0.2) # maximum roll rate
while True:
telem = get_telemetry()
if -math.pi + 0.1 < telem.roll < -0.2:
if abs(telem.roll) > math.pi / 2:
break
rospy.loginfo('finish flip')
set_position(x=start.x, y=start.y, z=start.z, yaw=start.yaw) # finish flip
print navigate(z=4, speed=1, auto_arm=True) # take off
@@ -300,5 +294,3 @@ rospy.sleep(10)
rospy.loginfo('flip')
flip()
```
Необходимо использование [специальной сборки PX4 для Клевера](firmware.md#прошивка-для-клевера). Перед выполнением флипа необходимо принять все меры безопасности.

View File

@@ -1,28 +0,0 @@
Техника безопасности при пайке
==============================
Работы, связанные с пайкой и лужением, должны проводиться в специально оборудованных и предварительно подготовленных помещениях. Обязательно должна присутствовать система вентиляции.
Перед началом работы необходимо:
1. Привести в порядок рабочее место, ничего не должно мешать процессу. Рабочее место должно быть хорошо освещено.
2. Паяльник, находящийся в рабочем состоянии, установить в зоне действия местной вытяжной вентиляции, в специальную подставку.
3. Перед началом работы надеть защитный халат, очки и, при необходимости, перчатки.
![stand](../assets/stand.jpg)
Во время пайки:
1. Паяльник следует держать только за ручку, так как жало имеет высокую температуру.
![keep](../assets/keep.png)
2. Для перемещения изделий применять специальные инструменты (пинцеты, клещи или другие инструменты), обеспечивающие безопасность при пайке.
3. Во избежание ожогов расплавленным припоем при распайке не выдергивать резко с большим усилием паяемые провода.
4. При пайке мелких и подвижных изделий пользоваться специальным держателем.
![helphand](../assets/helphand.jpg)
5. Паяльник переносить за корпус, а не за провод или рабочую часть. При перерывах в работе паяльник отключать от электросети.
> **Caution** При обнаружении неисправной работы паяльника или возникновении возгорания отключить его от питающей электросети.