mirror of
https://github.com/CopterExpress/clover.git
synced 2026-05-31 23:19:32 +00:00
Compare commits
63 Commits
v0.23-rc.3
...
v0.23
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
26c2387f5c | ||
|
|
826f631b97 | ||
|
|
52b5d7b04e | ||
|
|
455d52007e | ||
|
|
e9e6cabbb9 | ||
|
|
8fcd6e9b9e | ||
|
|
24d3a1df8d | ||
|
|
9784e7bfa1 | ||
|
|
fbad85d87f | ||
|
|
4fbc4f63ee | ||
|
|
c48a945258 | ||
|
|
c1ca40187e | ||
|
|
39763c4a40 | ||
|
|
c1179869cd | ||
|
|
6c43d5c230 | ||
|
|
265898912f | ||
|
|
d31bd75d7d | ||
|
|
e15ef587d7 | ||
|
|
79903db95d | ||
|
|
2096be5080 | ||
|
|
14a9c0eb46 | ||
|
|
0c879f2aad | ||
|
|
673dbb1feb | ||
|
|
4446b22db4 | ||
|
|
f34e8b4774 | ||
|
|
281f515ba7 | ||
|
|
be76ea82d7 | ||
|
|
6a8806c476 | ||
|
|
00a76a306e | ||
|
|
f66b53f9cb | ||
|
|
273e3191f1 | ||
|
|
28927246db | ||
|
|
ae08c62bf4 | ||
|
|
9f9b1d3115 | ||
|
|
ca5817c3d2 | ||
|
|
f3fb3e4cee | ||
|
|
7717461631 | ||
|
|
3f352ebc06 | ||
|
|
8c8fe5c40c | ||
|
|
d89e5eada7 | ||
|
|
80c853735d | ||
|
|
9bd3c616da | ||
|
|
75209ea2f9 | ||
|
|
2ee90e62fc | ||
|
|
d0a0e5d50d | ||
|
|
848d9dcbe4 | ||
|
|
6d68d06787 | ||
|
|
afe8abcd96 | ||
|
|
d18ca32688 | ||
|
|
bf9f7d035f | ||
|
|
1aec5063d6 | ||
|
|
3b06a33cad | ||
|
|
47e39d5331 | ||
|
|
e7eae1c02d | ||
|
|
e86b4da0ed | ||
|
|
6bcd670190 | ||
|
|
e3958d7fef | ||
|
|
fb47858010 | ||
|
|
b628825420 | ||
|
|
a525714e3a | ||
|
|
29fdbf23af | ||
|
|
6eacb8966a | ||
|
|
d8afb711f0 |
14
.github/workflows/build.yml
vendored
14
.github/workflows/build.yml
vendored
@@ -7,13 +7,13 @@ on:
|
||||
branches: [ master ]
|
||||
|
||||
jobs:
|
||||
melodic:
|
||||
runs-on: ubuntu-latest
|
||||
steps:
|
||||
- uses: actions/checkout@v2
|
||||
- name: Native Melodic build
|
||||
run: |
|
||||
docker run --rm -v $(pwd):/root/catkin_ws/src/clover ros:melodic-ros-base /root/catkin_ws/src/clover/builder/standalone-install.sh
|
||||
# melodic:
|
||||
# runs-on: ubuntu-latest
|
||||
# steps:
|
||||
# - uses: actions/checkout@v2
|
||||
# - name: Native Melodic build
|
||||
# run: |
|
||||
# docker run --rm -v $(pwd):/root/catkin_ws/src/clover ros:melodic-ros-base /root/catkin_ws/src/clover/builder/standalone-install.sh
|
||||
noetic:
|
||||
runs-on: ubuntu-latest
|
||||
steps:
|
||||
|
||||
4
.github/workflows/docs.yml
vendored
4
.github/workflows/docs.yml
vendored
@@ -10,6 +10,10 @@ jobs:
|
||||
docs:
|
||||
runs-on: ubuntu-18.04
|
||||
steps:
|
||||
- name: Cancel previous runs
|
||||
uses: styfle/cancel-workflow-action@0.9.1
|
||||
with:
|
||||
access_token: ${{ github.token }}
|
||||
- uses: actions/checkout@v2
|
||||
- name: Use Node.js
|
||||
uses: actions/setup-node@v1
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>aruco_pose</name>
|
||||
<version>0.21.1</version>
|
||||
<version>0.23.0</version>
|
||||
<description>Positioning with ArUco markers</description>
|
||||
|
||||
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>
|
||||
|
||||
@@ -30,7 +30,7 @@ Options:
|
||||
-o <filename> Output map file name in the 'map' subdirectory of aruco_pose package
|
||||
|
||||
Example:
|
||||
rosrun aruco_pose genmap.py 0.33 2 4 1 1 0 > $(catkin_find aruco_pose map)/test_map.txt
|
||||
rosrun aruco_pose genmap.py 0.33 2 4 1 1 0 -o test_map.txt
|
||||
"""
|
||||
|
||||
from __future__ import print_function
|
||||
|
||||
@@ -90,7 +90,7 @@ echo_stamp "Installing OpenCV 4.2-compatible ROS packages"
|
||||
apt install -y --no-install-recommends \
|
||||
ros-${ROS_DISTRO}-compressed-image-transport=1.14.0-0buster \
|
||||
ros-${ROS_DISTRO}-cv-bridge=1.15.0-0buster \
|
||||
ros-${ROS_DISTRO}-cv-camera=0.5.0-0buster \
|
||||
ros-${ROS_DISTRO}-cv-camera=0.5.1-0buster \
|
||||
ros-${ROS_DISTRO}-image-publisher=1.15.3-0buster \
|
||||
ros-${ROS_DISTRO}-web-video-server=0.2.1-0buster
|
||||
apt-mark hold \
|
||||
|
||||
@@ -138,6 +138,7 @@ echo_stamp "Install and enable Butterfly (web terminal)"
|
||||
echo_stamp "Workaround for tornado >= 6.0 breaking butterfly"
|
||||
export CRYPTOGRAPHY_DONT_BUILD_RUST=1
|
||||
my_travis_retry pip3 install cryptography==3.4.6 # https://stackoverflow.com/a/68472128/6850197
|
||||
my_travis_retry pip3 install pyOpenSSL==20.0.1
|
||||
my_travis_retry pip3 install tornado==5.1.1
|
||||
my_travis_retry pip3 install butterfly
|
||||
my_travis_retry pip3 install butterfly[systemd]
|
||||
|
||||
@@ -58,5 +58,9 @@ rosversion rosshow
|
||||
rosversion nodelet
|
||||
rosversion image_view
|
||||
|
||||
# validate some versions
|
||||
[[ $(rosversion cv_camera) == "0.5.1" ]] # patched version with init fix
|
||||
[[ $(rosversion ws281x) == "0.0.12" ]]
|
||||
|
||||
# validate examples are present
|
||||
[[ $(ls /home/pi/examples/*) ]]
|
||||
|
||||
@@ -8,8 +8,11 @@
|
||||
|
||||
<!-- For additional help go to https://clover.coex.tech/aruco -->
|
||||
|
||||
<arg name="force_init" default="false"/>
|
||||
<arg name="disable" default="false"/> <!-- only force init -->
|
||||
|
||||
<!-- aruco_detect: detect aruco markers, estimate poses -->
|
||||
<node name="aruco_detect" pkg="nodelet" if="$(arg aruco_detect)" type="nodelet" args="load aruco_pose/aruco_detect main_camera_nodelet_manager" output="screen" clear_params="true" respawn="true">
|
||||
<node name="aruco_detect" pkg="nodelet" if="$(eval aruco_detect and not disable)" type="nodelet" args="load aruco_pose/aruco_detect main_camera_nodelet_manager" output="screen" clear_params="true" respawn="true">
|
||||
<remap from="image_raw" to="main_camera/image_raw"/>
|
||||
<remap from="camera_info" to="main_camera/camera_info"/>
|
||||
<remap from="map_markers" to="aruco_map/markers"/>
|
||||
@@ -26,7 +29,7 @@
|
||||
</node>
|
||||
|
||||
<!-- aruco_map: estimate aruco map pose -->
|
||||
<node name="aruco_map" pkg="nodelet" type="nodelet" if="$(arg aruco_map)" args="load aruco_pose/aruco_map main_camera_nodelet_manager" output="screen" clear_params="true" respawn="true">
|
||||
<node name="aruco_map" pkg="nodelet" type="nodelet" if="$(eval aruco_map and not disable)" args="load aruco_pose/aruco_map main_camera_nodelet_manager" output="screen" clear_params="true" respawn="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"/>
|
||||
@@ -41,11 +44,11 @@
|
||||
</node>
|
||||
|
||||
<!-- vpe publisher from aruco markers -->
|
||||
<node name="vpe_publisher" pkg="clover" type="vpe_publisher" if="$(arg aruco_vpe)" output="screen" clear_params="true">
|
||||
<remap from="~pose_cov" to="aruco_map/pose"/>
|
||||
<node name="vpe_publisher" pkg="clover" type="vpe_publisher" if="$(eval aruco_vpe or force_init)" output="screen" clear_params="true">
|
||||
<remap from="~pose_cov" to="aruco_map/pose" if="$(arg aruco_vpe)"/>
|
||||
<remap from="~vpe" to="mavros/vision_pose/pose"/>
|
||||
<param name="frame_id" value="aruco_map_detected"/>
|
||||
<param name="publish_zero" value="true"/>
|
||||
<param name="frame_id" value="aruco_map_detected" if="$(arg aruco_vpe)"/>
|
||||
<param name="force_init" value="$(arg force_init)"/>
|
||||
<param name="offset_frame_id" value="aruco_map"/>
|
||||
</node>
|
||||
</launch>
|
||||
|
||||
@@ -12,6 +12,7 @@
|
||||
<arg name="led" default="true"/>
|
||||
<arg name="blocks" default="false"/>
|
||||
<arg name="rc" default="false"/>
|
||||
<arg name="force_init" value="true"/> <!-- force estimator to init by publishing zero pose -->
|
||||
|
||||
<arg name="simulator" default="false"/> <!-- flag that we are operating on a simulated drone -->
|
||||
|
||||
@@ -33,7 +34,10 @@
|
||||
</node>
|
||||
|
||||
<!-- aruco markers -->
|
||||
<include file="$(find clover)/launch/aruco.launch" if="$(arg aruco)"/>
|
||||
<include file="$(find clover)/launch/aruco.launch" if="$(eval aruco or force_init)">
|
||||
<arg name="force_init" value="$(arg force_init)"/>
|
||||
<arg name="disable" value="$(eval not aruco)"/>
|
||||
</include>
|
||||
|
||||
<!-- optical flow -->
|
||||
<node pkg="nodelet" type="nodelet" name="optical_flow" args="load clover/optical_flow main_camera_nodelet_manager" if="$(arg optical_flow)" clear_params="true" output="screen" respawn="true">
|
||||
@@ -47,9 +51,6 @@
|
||||
|
||||
<!-- simplified offboard control -->
|
||||
<node name="simple_offboard" pkg="clover" type="simple_offboard" output="screen" clear_params="true">
|
||||
<param name="reference_frames/body" value="map"/>
|
||||
<param name="reference_frames/base_link" value="map"/>
|
||||
<param name="reference_frames/navigate_target" value="map"/>
|
||||
<param name="reference_frames/main_camera_optical" value="map"/>
|
||||
</node>
|
||||
|
||||
|
||||
@@ -1,11 +1,11 @@
|
||||
# Config file for mavros
|
||||
# Based on https://raw.githubusercontent.com/mavlink/mavros/master/mavros/launch/px4_config.yaml
|
||||
|
||||
startup_px4_usb_quirk: true
|
||||
startup_px4_usb_quirk: false
|
||||
|
||||
conn:
|
||||
heartbeat_rate: 1.0 # send hertbeat rate in Hertz
|
||||
timeout: 10.0 # hertbeat timeout in seconds
|
||||
heartbeat_rate: 1.0 # send heartbeat rate in Hertz
|
||||
timeout: 10.0 # heartbeat timeout in seconds
|
||||
timesync_rate: 10.0 # TIMESYNC rate in Hertz (feature disabled if 0.0)
|
||||
system_time_rate: 1.0 # send system time to FCU rate in Hertz (disabled if 0.0)
|
||||
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
<?xml version="1.0"?>
|
||||
<package format="3">
|
||||
<name>clover</name>
|
||||
<version>0.21.1</version>
|
||||
<version>0.23.0</version>
|
||||
<description>The Clover package</description>
|
||||
|
||||
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>
|
||||
|
||||
@@ -195,6 +195,9 @@ def check_fcu():
|
||||
failure('no connection to the FCU (check wiring)')
|
||||
return
|
||||
|
||||
clover_tag = re.compile(r'-cl[oe]ver\.\d+$')
|
||||
clover_fw = False
|
||||
|
||||
# Make sure the console is available to us
|
||||
mavlink_exec('\n')
|
||||
version_str = mavlink_exec('ver all')
|
||||
@@ -204,11 +207,16 @@ def check_fcu():
|
||||
for line in version_str.split('\n'):
|
||||
if line.startswith('FW version: '):
|
||||
info(line[len('FW version: '):])
|
||||
elif line.startswith('FW git tag: '):
|
||||
info(line[len('FW git tag: '):])
|
||||
elif line.startswith('FW git tag: '): # only Clover's firmware
|
||||
tag = line[len('FW git tag: '):]
|
||||
clover_fw = clover_tag.search(tag)
|
||||
info(tag)
|
||||
elif line.startswith('HW arch: '):
|
||||
info(line[len('HW arch: '):])
|
||||
|
||||
if not clover_fw:
|
||||
info('not Clover PX4 firmware, check https://clover.coex.tech/firmware')
|
||||
|
||||
est = get_param('SYS_MC_EST_GROUP')
|
||||
if est == 1:
|
||||
info('selected estimator: LPE')
|
||||
@@ -480,6 +488,12 @@ def check_local_position():
|
||||
failure('roll is %.2f deg; place copter horizontally or redo level horizon calib',
|
||||
math.degrees(roll))
|
||||
|
||||
if not tf_buffer.can_transform('base_link', pose.header.frame_id, rospy.get_rostime(), rospy.Duration(0.5)):
|
||||
failure('can\'t transform from %s to base_link (timeout 0.5 s): is TF enabled?', pose.header.frame_id)
|
||||
|
||||
if not tf_buffer.can_transform('body', pose.header.frame_id, rospy.get_rostime(), rospy.Duration(0.5)):
|
||||
failure('can\'t transform from %s to body (timeout 0.5 s)', pose.header.frame_id)
|
||||
|
||||
except rospy.ROSException:
|
||||
failure('no local position')
|
||||
|
||||
@@ -609,7 +623,7 @@ def check_boot_duration():
|
||||
output = subprocess.check_output('systemd-analyze').decode()
|
||||
r = re.compile(r'([\d\.]+)s\s*$', flags=re.MULTILINE)
|
||||
duration = float(r.search(output).groups()[0])
|
||||
if duration > 15:
|
||||
if duration > 20:
|
||||
failure('long Raspbian boot duration: %ss (systemd-analyze for analyzing)', duration)
|
||||
|
||||
|
||||
|
||||
@@ -873,6 +873,13 @@ int main(int argc, char **argv)
|
||||
nh_priv.param<string>("body_frame", body.child_frame_id, "body");
|
||||
nh_priv.getParam("reference_frames", reference_frames);
|
||||
|
||||
// Default reference frames
|
||||
std::map<string, string> default_reference_frames;
|
||||
default_reference_frames[body.child_frame_id] = local_frame;
|
||||
default_reference_frames[fcu_frame] = local_frame;
|
||||
if (!target.child_frame_id.empty()) default_reference_frames[target.child_frame_id] = local_frame;
|
||||
reference_frames.insert(default_reference_frames.begin(), default_reference_frames.end()); // merge defaults
|
||||
|
||||
state_timeout = ros::Duration(nh_priv.param("state_timeout", 3.0));
|
||||
local_position_timeout = ros::Duration(nh_priv.param("local_position_timeout", 2.0));
|
||||
velocity_timeout = ros::Duration(nh_priv.param("velocity_timeout", 2.0));
|
||||
|
||||
@@ -141,11 +141,11 @@ int main(int argc, char **argv) {
|
||||
vpe_pub = nh_priv.advertise<PoseStamped>("vpe", 1);
|
||||
//vpe_cov_pub = nh_priv_.advertise<PoseStamped>("pose_cov_pub", 1);
|
||||
|
||||
if (nh_priv.param("publish_zero", false)) {
|
||||
if (nh_priv.param("force_init", false) || nh_priv.param("publish_zero", false)) { // publish_zero is old name
|
||||
// publish zero to initialize the local position
|
||||
zero_timer = nh.createTimer(ros::Duration(0.1), &publishZero);
|
||||
publish_zero_timout = ros::Duration(nh_priv.param("publish_zero_timout", 5.0));
|
||||
publish_zero_duration = ros::Duration(nh_priv.param("publish_zero_duration", 5.0));
|
||||
publish_zero_timout = ros::Duration(nh_priv.param("force_init_timeout", 5.0));
|
||||
publish_zero_duration = ros::Duration(nh_priv.param("force_init_duration", 5.0));
|
||||
local_position_sub = nh.subscribe("mavros/local_position/pose", 1, &localPositionCallback);
|
||||
}
|
||||
|
||||
|
||||
23
clover/www/console.html
Normal file
23
clover/www/console.html
Normal file
@@ -0,0 +1,23 @@
|
||||
<h1>
|
||||
/var/log/clover.log
|
||||
<a style="font-size: 0.5em; vertical-align: super; font-weight: normal" href="clover.log" download>download</a>
|
||||
</h1>
|
||||
|
||||
<pre></pre>
|
||||
|
||||
<script type="module">
|
||||
var pre = document.querySelector('pre');
|
||||
|
||||
fetch('clover.log?' + Math.random()).then(function(response) { // random to forbid caching
|
||||
if (response.status == 404) {
|
||||
pre.innerHTML = '/var/log/clover.log does not exist';
|
||||
return;
|
||||
} else if (response.status !== 200) {
|
||||
pre.innerHTML('Error ' + response.status);
|
||||
return;
|
||||
}
|
||||
response.text().then(function(content) {
|
||||
pre.innerHTML = content;
|
||||
});
|
||||
});
|
||||
</script>
|
||||
@@ -9,7 +9,7 @@
|
||||
<li><a href="" id="butterfly">Open web terminal</a> (<code>Butterfly</code>)</li>
|
||||
<li>View <a href="viz.html">View 3D visualization</a>, <a href="aruco_map.html">3D visualization for markers map</a> (<code>ros3djs</code>)</li>
|
||||
<li><a href="../clover_blocks/">Blocks programming</a> (<code>Blockly</code>)</li>
|
||||
<li><a href="clover.log">Clover console</a> (<code>/var/log/clover.log</code>)</li>
|
||||
<li><a href="console.html">Clover console</a> (<code>/var/log/clover.log</code>)</li>
|
||||
</ul>
|
||||
|
||||
<div class="version"></div>
|
||||
|
||||
@@ -1,5 +1,6 @@
|
||||
const url = 'ws://' + location.hostname + ':9090';
|
||||
const ros = new ROSLIB.Ros({ url: url });
|
||||
const params = Object.fromEntries(new URLSearchParams(window.location.search).entries());
|
||||
|
||||
ros.on('connection', function () {
|
||||
document.body.classList.add('connected');
|
||||
@@ -52,6 +53,15 @@ function viewTopic(topic) {
|
||||
new ROSLIB.Topic({ ros: ros, name: topic }).subscribe(function(msg) {
|
||||
document.title = topic;
|
||||
if (mouseDown) return;
|
||||
|
||||
if (msg.header.stamp) {
|
||||
if (params.date || params.offset) {
|
||||
let date = new Date(msg.header.stamp.secs * 1e3 + msg.header.stamp.nsecs * 1e-6);
|
||||
if (params.date) msg.header.date = date.toISOString();
|
||||
if (params.offset) msg.header.offset = (new Date() - date) * 1e-3;
|
||||
}
|
||||
}
|
||||
|
||||
topicMessage.innerHTML = yamlStringify(msg); // JSON.stringify(msg, null, 4);
|
||||
});
|
||||
}
|
||||
@@ -62,8 +72,6 @@ topicMessage.addEventListener('mousedown', function() { mouseDown = true; });
|
||||
topicMessage.addEventListener('mouseup', function() { mouseDown = false; });
|
||||
|
||||
function init() {
|
||||
const params = Object.fromEntries(new URLSearchParams(window.location.search).entries());
|
||||
|
||||
if (!params.topic) {
|
||||
viewTopicsList();
|
||||
} else {
|
||||
|
||||
@@ -23,6 +23,6 @@
|
||||
<body>
|
||||
<h1> </h1>
|
||||
<ul id="topics"></ul>
|
||||
<code id="topic-message" title="Hold mouse button to pause">No messages received</code>
|
||||
<code id="topic-message">No messages received</code>
|
||||
</body>
|
||||
</html>
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>clover_blocks</name>
|
||||
<version>0.21.1</version>
|
||||
<version>0.23.0</version>
|
||||
<description>Blockly programming support for Clover</description>
|
||||
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>
|
||||
<license>MIT</license>
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
<package format="2">
|
||||
<name>clover_description</name>
|
||||
<version>0.21.1</version>
|
||||
<version>0.23.0</version>
|
||||
<description>The clover_description package provides URDF models of the Clover series of quadcopters.</description>
|
||||
|
||||
<maintainer email="sfalexrog@gmail.com">Alexey Rogachevskiy</maintainer>
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
<package format="2">
|
||||
<name>clover_simulation</name>
|
||||
<version>0.21.1</version>
|
||||
<version>0.23.0</version>
|
||||
<description>The clover_simulation package provides worlds and launch files for Gazebo.</description>
|
||||
|
||||
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>
|
||||
|
||||
Binary file not shown.
|
Before Width: | Height: | Size: 695 KiB After Width: | Height: | Size: 220 KiB |
Binary file not shown.
|
Before Width: | Height: | Size: 972 KiB |
Binary file not shown.
|
Before Width: | Height: | Size: 1.2 MiB After Width: | Height: | Size: 381 KiB |
@@ -70,7 +70,7 @@
|
||||
* [Remote control app](rc.md)
|
||||
* [Wi-Fi Configuration](network.md)
|
||||
* [UART settings](uart.md)
|
||||
* [PX4 Parameters](px4_parameters.md)
|
||||
* [PX4 Parameters](parameters.md)
|
||||
* [PX4 Logs and Topics](flight_logs.md)
|
||||
* [PX4 Firmware](firmware.md)
|
||||
* [MAVLink](mavlink.md)
|
||||
@@ -101,6 +101,7 @@
|
||||
* [CopterHack-2018](copterhack2018.md)
|
||||
* [CopterHack-2017](copterhack2017.md)
|
||||
* [Video contest](video_contest.md)
|
||||
* [Educational contests](educational_contests.md)
|
||||
* [Clover-based projects](projects.md)
|
||||
* [Autonomous Multirotor Landing System (AMLS)](amls.md)
|
||||
* [Drone show](clever-show.md)
|
||||
|
||||
@@ -1,7 +1,5 @@
|
||||
# ArUco markers
|
||||
|
||||
> **Note** The following applies to [image versions](image.md) **0.16** and up. Older documentation is still available for [for version **0.15.1**](https://github.com/CopterExpress/clover/blob/v0.15.1/docs/en/aruco.md).
|
||||
|
||||
[ArUco markers](https://docs.opencv.org/3.2.0/d5/dae/tutorial_aruco_detection.html) are commonly used for vision-based position estimation.
|
||||
|
||||
Examples of ArUco markers:
|
||||
|
||||
@@ -93,7 +93,7 @@ The marker map adheres to the [ROS coordinate system convention](http://www.ros.
|
||||
|
||||
## VPE setup
|
||||
|
||||
In order to enable vision position estimation you should use the following [PX4 parameters](px4_parameters.md).
|
||||
In order to enable vision position estimation you should use the following [PX4 parameters](parameters.md).
|
||||
|
||||
If you're using **LPE** (`SYS_MC_EST_GROUP` parameter is set to `local_position_estimator,attitude_estimator_q`):
|
||||
|
||||
|
||||
@@ -6,7 +6,7 @@ Software autorun
|
||||
systemd
|
||||
---
|
||||
|
||||
Main documentation: [https://wiki.archlinux.org/index.php/Systemd_(Russian)](https://wiki.archlinux.org/index.php/Systemd_(Russian)).
|
||||
Main documentation: https://wiki.archlinux.org/title/Systemd.
|
||||
|
||||
All automatically started Clover software is launched as a `clover.service` systemd service.
|
||||
|
||||
@@ -50,12 +50,12 @@ You can add your own node to the list of automatically launched ones. To do this
|
||||
|
||||
The started file must have *permission* to run:
|
||||
|
||||
```(bash)
|
||||
```bash
|
||||
chmod +x my_program.py
|
||||
```
|
||||
|
||||
When scripting languages are used, [shebang] should be placed at the beginning of the file (https://ru.wikipedia.org/wiki/Shebang_(Unix)), for example:
|
||||
When scripting languages are used, a <a href="https://en.wikipedia.org/wiki/Shebang_(Unix)">shebang</a> should be placed at the beginning of the file, for example:
|
||||
|
||||
```(bash)
|
||||
#!/usr/bin/env python
|
||||
```bash
|
||||
#!/usr/bin/env python3
|
||||
```
|
||||
|
||||
@@ -14,7 +14,7 @@ In order to perform the sensor calibration, select the *Vehicle Setup* tab and c
|
||||
4. Put the drone in one of the orientations marked by the red outline and wait for the appropriate outline to turn yellow.
|
||||
5. Spin the drone as required until the outline turns green. Do this for all orientations.
|
||||
|
||||
Read more in the PX4 docs: https://docs.px4.io/v1.9.0/en/config/compass.html.
|
||||
Read more in the PX4 docs: https://docs.px4.io/master/en/config/compass.html.
|
||||
|
||||
## Gyroscope
|
||||
|
||||
@@ -27,7 +27,7 @@ Read more in the PX4 docs: https://docs.px4.io/v1.9.0/en/config/compass.html.
|
||||
|
||||
> **Warning** The drone should stay completely still during the calibration.
|
||||
|
||||
Read more in the PX4 docs: https://docs.px4.io/v1.9.0/en/config/gyroscope.html.
|
||||
Read more in the PX4 docs: https://docs.px4.io/master/en/config/gyroscope.html.
|
||||
|
||||
## Accelerometer
|
||||
|
||||
@@ -38,7 +38,7 @@ Read more in the PX4 docs: https://docs.px4.io/v1.9.0/en/config/gyroscope.html.
|
||||
3. Put the drone in one of the orientations marked by the red outline and wait for the appropriate outline to turn yellow.
|
||||
4. Hold the drone in this orientation until the outline turns green. Do this for all orientations.
|
||||
|
||||
Read more in the PX4 docs: https://docs.px4.io/v1.9.0/en/config/accelerometer.html.
|
||||
Read more in the PX4 docs: https://docs.px4.io/master/en/config/accelerometer.html.
|
||||
|
||||
## Level horizon
|
||||
|
||||
@@ -50,6 +50,6 @@ Read more in the PX4 docs: https://docs.px4.io/v1.9.0/en/config/accelerometer.ht
|
||||
4. Press *OK*.
|
||||
5. Wait for the calibration to finish.
|
||||
|
||||
Read more in the PX4 docs: https://docs.px4.io/v1.9.0/en/config/level_horizon_calibration.html.
|
||||
Read more in the PX4 docs: https://docs.px4.io/master/en/config/level_horizon_calibration.html.
|
||||
|
||||
**Next**: [RC setup](radio.md).
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
# COEX Pix
|
||||
|
||||
The **COEX Pix** flight controller is a modified [Pixracer](https://docs.px4.io/v1.9.0/en/flight_controller/pixracer.html) FCU. It is a part of the **Clover 4** quadrotor kit.
|
||||
The **COEX Pix** flight controller is a modified [Pixracer](https://docs.px4.io/master/en/flight_controller/pixracer.html) FCU. It is a part of the **Clover 4** quadrotor kit.
|
||||
|
||||
> **Hint** The source files of the COEX Pix flight controller are [published](https://github.com/CopterExpress/hardware/tree/master/COEX%20Pix) under the CC BY-NC-SA license.
|
||||
|
||||
|
||||
@@ -16,7 +16,7 @@ USB connection is the preferred way to connect to the flight controller.
|
||||
|
||||
The `connected` field should have the `True` value.s
|
||||
|
||||
> **Hint** You need to set the `CBRK_USB_CHK` [parameter](px4_parameters.md) to 197848 for the USB connection to work.
|
||||
> **Hint** You need to set the `CBRK_USB_CHK` [parameter](parameters.md) to 197848 for the USB connection to work.
|
||||
|
||||
## UART connection
|
||||
|
||||
|
||||
@@ -13,27 +13,27 @@ The proposed projects have to be open-source and be compatible with the Clover q
|
||||
|Place|Team|Project|Points|
|
||||
|:-:|-|-|-|
|
||||
||🇰🇬 Alatoo University Team|[Облачная платформа для симулятора Клевера](https://github.com/pteacher/clover/blob/clover_simulator/docs/ru/clover-development-studio.md)||
|
||||
||🇧🇾 FTL|[Advanced Clover 2](https://github.com/FTL-team/clover/blob/FTL-advancedClover2/docs/ru/advancedclover2.md)||
|
||||
||🇻🇳 Dragon&Tanker|[Dragon&Tanker](https://github.com/uml4/clover/blob/drone_observe_autonomous_car/docs/en/dragon_and_tanker_team.md)||
|
||||
||🇧🇾 FTL|[Advanced Clover 2](https://github.com/FTL-team/clover/blob/FTL-advancedClover2/docs/ru/advanced_clover_simulator.md)||
|
||||
||🇷🇺 Stereo|[Neural obstacle avoidance](https://github.com/den250400/clover/blob/neural-obstacle-avoidance/docs/en/neural-obstacle-avoidance.md)||
|
||||
||🇷🇺 Space clowns|[Copter For Space](https://github.com/slavikyd/clover/blob/patch-3/docs/ru/c4s.md)||
|
||||
||🇷🇺 R.S.|[Drone Hawk](https://github.com/slavaroot/clover/blob/droneHawkSecurity/docs/ru/drone-hawk-security.md)||
|
||||
||🇲🇾 Moopt|[IoT Water Monitoring & Optimization](https://github.com/kafechew/clover/blob/master/docs/en/moopt-uav.md)||
|
||||
||🇧🇷 Atena - Grupo SEMEAR|[Swarm in Blocks](https://github.com/Grupo-SEMEAR-USP/clover/blob/Swarm_in_Blocks/docs/en/Swarm_in_Blocks.md)||
|
||||
||🇧🇷 Atena - Grupo SEMEAR|[Swarm in Blocks](https://github.com/Grupo-SEMEAR-USP/clover/blob/Swarm_in_Blocks/docs/en/swarm_in_blocks.md)||
|
||||
||🇷🇺 Clevertron|[Clevertron](https://github.com/Daniel-drone/clover/blob/Clevertron-1/docs/ru/clevertron.md)||
|
||||
||🇷🇺 Clover Rescue Team|[Rescue Clover](https://github.com/DevMBS/clover/blob/CloverRescueTeam/docs/ru/clover-rescue-team.md)||
|
||||
||🇵🇱 Edgenoon|[Neural and vision-based landing method](https://github.com/edgenoon-ai/clover/blob/neural_vision_based_landing_method/docs/en/neural_vision_based_landing_method.md)||
|
||||
||🇷🇺 CopterCat|[CopterCat](https://github.com/matveylapin/clover/blob/CopterCat/docs/ru/сopter_сat.md)||
|
||||
||🇷🇺 Дрой Ронов|[Clover Swarm](https://github.com/stinger000/clever/blob/clover_swarm_request/docs/ru/clover-swarm.md)||
|
||||
||🇩🇪 Inondro|[Inondro Pix](https://github.com/Inondro/clover/blob/inondro-pix/docs/en/inondro_copterhack22_pix.md)||
|
||||
||🇷🇺 V-NAV|[Visual Navigation](https://github.com/v-nav/clover/blob/v-nav_article/docs/ru/v-nav.md)||
|
||||
||🇮🇳 DJS Phoenix|[Autonomous valet parking drone assistance](https://github.com/DJSPhoenix/clover/blob/DJSPhoenix-Ikshana/docs/en/djs_phoenix_ikshana.md)||
|
||||
||🇷🇺 Джедаи 1581|[Ретранслятор на базе Клевера](https://github.com/JJNIK/clover/blob/patch-1/docs/ru/1581.md)||
|
||||
||🇷🇺 SPECTRE|[SPECTRE](https://github.com/alakhmenev/clover/blob/spectre_team/docs/ru/spectre_team.md)||
|
||||
||🇷🇺 Lucky flight|[Swarm of Improved Clover](https://github.com/bessiaka/clover/blob/Lucky-flight/docs/ru/lucky_flight.md)||
|
||||
||🇷🇺 SolidEye|[Разработка лидара без движущихся частей](https://github.com/feanorgg/clover/blob/solideye/docs/ru/solid_eye.md)||
|
||||
||🇰🇬 AI_U_CLOVER|[AIU_CLOVER](https://github.com/zhibekm/clover/blob/zhibekm-patch-1/docs/en/aiu-article.md)||
|
||||
||🇷🇺 С305|[Система мониторинга воздуха](https://github.com/Ruslan2288/clover/blob/master/docs/ru/air_monitor.md)| |
|
||||
|✕|🇻🇳 Dragon&Tanker|[Dragon&Tanker](https://github.com/uml4/clover/blob/drone_observe_autonomous_car/docs/en/dragon_and_tanker_team.md)||
|
||||
|✕|🇷🇺 V-NAV|[Visual Navigation](https://github.com/v-nav/clover/blob/v-nav_article/docs/ru/v-nav.md)||
|
||||
|✕|🇷🇺 Джедаи 1581|[Ретранслятор на базе Клевера](https://github.com/JJNIK/clover/blob/patch-1/docs/ru/1581.md)||
|
||||
|✕|🇷🇺 Lucky flight|[Swarm of Improved Clover](https://github.com/bessiaka/clover/blob/Lucky-flight/docs/ru/lucky_flight.md)||
|
||||
|✕|🇺🇸 EnviroFleet|[EnviroFleet](https://github.com/gueyman/clover/blob/envirofleet/docs/en/enviro_fleet.md)||
|
||||
|✕|🇷🇺 Бизнес-гуси|[Drone Rover Climbing System](https://github.com/HexaHEX/clover/blob/CopterHack2022_Business_Geese-1/docs/ru/business_geese.md)||
|
||||
|✕|🇷🇺 fuall|[Доставка дронами](https://github.com/Silly4s/clover/blob/master/docs/ru/dostavka.md)||
|
||||
|
||||
118
docs/en/educational_contests.md
Normal file
118
docs/en/educational_contests.md
Normal file
@@ -0,0 +1,118 @@
|
||||
# Educational contests
|
||||
|
||||
## 1. Contest for the best educational lecture {#lecture}
|
||||
|
||||
The Copter Express company organizes a contest for the best educational lecture with COEX Clover 4 quadcopter kit application.
|
||||
|
||||
The main goal of the contest is aerial robotics popularization and community development.
|
||||
|
||||
### Lecture requirements
|
||||
|
||||
* The topic of the lecture is of free choice. Programmable quadcopter kit COEX Clover 4 and/or The Clover simulation environment should be used as the main tool in the lecture.
|
||||
> **Note** *The version of COEX Clover is not earlier than [version 4](https://clover.coex.tech/en/assemble_4.html). The virtual machine image is not earlier than [version 1.0](https://github.com/CopterExpress/clover_vm/releases/tag/v1.0).
|
||||
* The video is uploaded on YouTube or another public platform and is public accessible.
|
||||
* The language of the lecture is any. The video contains subtitles in English in case the language is made neither of English nor Russian.
|
||||
* The duration of the lecture is limited from 15 min. to 3 hours.
|
||||
|
||||
### Requirements for the participants
|
||||
|
||||
* The participant must be the author of the lesson.
|
||||
* Third parties can provide technical support for recording a lecture.
|
||||
* The status of the participant is unlimited (student, representative of a general education institution, representative of the industry, amateur).
|
||||
|
||||
Applications deadline: September 1, 2022.
|
||||
|
||||
### How to apply?
|
||||
|
||||
The application to the contest is performed via the [Google Form](https://docs.google.com/forms/d/e/1FAIpQLScE2kN5dO2OYNSM8hOYzOa5Qvh2uDdd9Fjx8OnL1W93bfEBgw/viewform) where the link to the video lecture should be attached.
|
||||
|
||||
Participants who are the authors of the lecture are allowed to participate in the competition.
|
||||
|
||||
### Prizes
|
||||
|
||||
Based on the results of the submitted application, the jury selects the winners of the competition. The quality of the video, it is content, and audience engagement are assessed.
|
||||
|
||||
* 1st place: $500.
|
||||
* 2nd place: $400.
|
||||
* 3rd place: $300.
|
||||
* 4th place: $200.
|
||||
* 5th place: $100.
|
||||
|
||||
## 2. Contest for the best school lesson {#lesson}
|
||||
|
||||
The Copter Express company organizes a contest for the best school lesson with COEX Clover 4 quadcopter kit application.
|
||||
|
||||
The main goal of the contest is aerial robotics popularization and community development.
|
||||
|
||||
### Lesson requirements
|
||||
|
||||
* Programmable quadcopter kit COEX Clover 4 should be used as the main tool for the lesson.
|
||||
> **Note** *The version of COEX Clover is not earlier than [version 4](https://clover.coex.tech/en/assemble_4.html).
|
||||
* Integration of the quadcopter into any of the general education disciplines (physics, mathematics, computer science, etc.).
|
||||
* Practical use of the main tool in the lesson.
|
||||
* Grade - no restrictions (primary, high school).
|
||||
* Lesson duration is 30-45 minutes.
|
||||
* Lesson format - offline.
|
||||
* The video of the lesson was filmed in the classroom of a general education institution.
|
||||
|
||||
### Requirements for the participants
|
||||
|
||||
* The participant must be the author of the lesson.
|
||||
* The participant must be a teacher of a general education institution
|
||||
|
||||
### How to apply?
|
||||
|
||||
The application to the contest is performed via the [Google Form](https://docs.google.com/forms/d/e/1FAIpQLSdelVy6yQ1iN6u88KeiEIKGj7gGaM0xccSt2tiYKB46ICmjkQ/viewform).
|
||||
|
||||
Applications deadline: September 1, 2022.
|
||||
|
||||
### Prizes
|
||||
|
||||
Based on the results of the submitted application, the jury selects the winners of the competition. The video and material quality are assessed.
|
||||
|
||||
* 1st place: $500.
|
||||
* 2nd place: $400.
|
||||
* 3rd place: $300.
|
||||
* 4th place: $200.
|
||||
* 5th place: $100.
|
||||
|
||||
## 3. Contest for the best online course {#course}
|
||||
|
||||
The Copter Express company organizes a contest for the best online course with COEX Clover 4 quadcopter kit application.
|
||||
|
||||
The main goal of the contest is aerial robotics popularization and community development.
|
||||
|
||||
The course is evaluated according to a separate, publicly available lesson submitted for the contest.
|
||||
|
||||
### Course requirements
|
||||
|
||||
* The course is related to the direction of Aerial robotics.
|
||||
* Programmable quadcopter kit COEX Clover 4 and/or The Clover simulation environment should be used as the main tool in the course;
|
||||
> **Note** *The version of COEX Clover is not earlier than [version 4](https://clover.coex.tech/en/assemble_4.html). The virtual machine image is not earlier than [version 1.0](https://github.com/CopterExpress/clover_vm/releases/tag/v1.0).
|
||||
* The course is located on a public platform (e.g., Coursera).
|
||||
* The course can be either paid or free of charge. One public lesson from the course is submitted for the competition;
|
||||
* The lesson submitted for the contest should be publicly accessible.
|
||||
* The language of the lesson is any. The video contains subtitles in English in case the language is made neither of English nor Russian (if there is a video in the lesson).
|
||||
* The duration of the course and lesson is not limited.
|
||||
|
||||
### Requirements for the participants
|
||||
|
||||
* The participant must be the author of the course.
|
||||
* Third parties can provide technical support for preparing a course.
|
||||
* The status of the participant is unlimited (student, representative of a general education institution, representative of the industry, amateur).
|
||||
|
||||
### How to apply?
|
||||
|
||||
The application to the contest is performed via the [Google Form](https://docs.google.com/forms/d/e/1FAIpQLSdf2Q68X4hPnFE9f3EP95AxPNnzHKqIsFHtTRT6EBKiH93wzg/viewform) where the link to the video course should be attached.
|
||||
|
||||
Applications deadline: September 1, 2022.
|
||||
|
||||
### Prizes
|
||||
|
||||
Based on the results of the submitted application, the members of the Commission select the winners of the competition. The quality of the material, the format of the presentation of the material, the total volume and content of the course are assessed.
|
||||
|
||||
* 1st place: $1000.
|
||||
* 2nd place: $800.
|
||||
* 3rd place: $600.
|
||||
* 4th place: $400.
|
||||
* 5th place: $200.
|
||||
@@ -4,10 +4,10 @@ Main article is available at https://docs.px4.io/master/en/config/safety.html.
|
||||
|
||||
The *Safety* panel allows you to configure actions that should be performed when a failsafe is triggered. You should at the very least configure the RC Loss failsafe, which is triggered when the RC transmitter link is lost:
|
||||
|
||||
1. Open the *Safety* panel.
|
||||
1. In QGroundControl software, go to the *Vehicle Setup* panel and choose the *Safety* menu.
|
||||
2. Select one of the following actions in the *RC Loss Failsafe Trigger* option:
|
||||
* *Land mode* – transition to automatic land mode;
|
||||
* *Terminate* – set all outputs to their failsafe values.
|
||||
3. Set the timeout value before RC Loss triggers in the *RC Loss Timeout* field. We recommend setting it to 0.5 s.
|
||||
3. Set the timeout value before RC Loss triggers in the *RC Loss Timeout* field. We recommend setting it to 2 s.
|
||||
|
||||
<img src="../assets/qgc-failsafe.png" alt="QGroundControl failsafe" class="zoom">
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
# Flight
|
||||
|
||||
> **Info** See also official PX4 flying guide: https://docs.px4.io/v1.9.0/en/flying/.
|
||||
> **Info** See also official PX4 flying guide: https://docs.px4.io/master/en/flying/.
|
||||
|
||||
This section explains the basics of manual controlling the quadcopter in different modes using radio remote control (for autonomous flying see "[Programming](programming.md)") section.
|
||||
|
||||
|
||||
@@ -9,7 +9,8 @@ Main frames in the `clover` package:
|
||||
* `base_link` is rigidly bound to the drone. It is shown by the simplified drone model on the image above;
|
||||
* `body` is bound to the drone, but its Z axis points up regardless of the drone's pitch and roll. It is shown by the red, blue and green lines in the illustration;
|
||||
* <a name="navigate_target"></a>`navigate_target` is bound to the current navigation target (as set by the [navigate](simple_offboard.md#navigate) service);
|
||||
* `setpoint` is current position setpoint.
|
||||
* `setpoint` is current position setpoint;
|
||||
* `main_camera_optical` is the coordinate system, [linked to the main camera](camera_setup.md#frame);
|
||||
|
||||
Additional frames become available when [ArUco positioning system](aruco.md) is active:
|
||||
|
||||
|
||||
@@ -38,7 +38,7 @@ rostopic echo /rangefinder/range
|
||||
|
||||
> **Hint** We recommend using our [custom PX4 firmware for Clover](firmware.md#modified-firmware-for-clover) for best laser rangefinder support.
|
||||
|
||||
PX4 should be properly [configured](px4_parameters.md) to use the rangefinder data.
|
||||
PX4 should be properly [configured](parameters.md) to use the rangefinder data.
|
||||
|
||||
Set the following parameters when EKF2 is used (`SYS_MC_EST_GROUP` = `ekf2`):
|
||||
|
||||
|
||||
@@ -29,7 +29,7 @@ Examples of MAVLink messages:
|
||||
* `GLOBAL_POSITION_INT` – global position of the quadcopter (latitude/longitude/altitude);
|
||||
* `COMMAND_LONG` – a command to the quadcopter (take off, land, toggle modes, etc).
|
||||
|
||||
A complete list of MAVLink messages is available in [MAVLink documentation] (http://mavlink.org/messages/common).
|
||||
A complete list of MAVLink messages is available in [MAVLink documentation](https://mavlink.io/en/messages/common.html).
|
||||
|
||||
### System, system component
|
||||
|
||||
|
||||
@@ -4,10 +4,11 @@ PX4 **mode** determines how the vehicle should react to commands and RC signals.
|
||||
|
||||
In order to configure flight modes:
|
||||
|
||||
1. Open the *Vehicle Setup* tab in QGroundControl.
|
||||
1. Open the *Vehicle Setup* panel in QGroundControl.
|
||||
2. Select the *Flight Modes* menu.
|
||||
3. Choose SwC (Channel 6) as mode selection switch.
|
||||
4. Set desired flight modes.
|
||||
3. Set the *Mode Channel* to the SwC switch (*Channel 6*).
|
||||
4. Optionally, set the *Emergency Kill Switch Channel* to SwA switch (*Channel 5*).
|
||||
5. Set desired flight modes.
|
||||
|
||||
The following flight modes are recommended:
|
||||
|
||||
@@ -15,8 +16,8 @@ In order to configure flight modes:
|
||||
* Flight Mode 4: *Altitude*.
|
||||
* Flight Mode 6: *Position*.
|
||||
|
||||
5. Check mode switching by changing the switch position.
|
||||
6. Choose SwA (Channel 5) as emergency motor stop (*Kill switch*).
|
||||
6. Check mode switching by changing the switch position.
|
||||
7. Choose SwA (Channel 5) as emergency motor stop (*Kill switch*).
|
||||
|
||||
<img src="../assets/qgc-modes.png" class="zoom" alt="QGroundControl modes">
|
||||
|
||||
|
||||
@@ -1,12 +1,10 @@
|
||||
# Use of Optical Flow
|
||||
|
||||
Running the technology "Optical Flow" offers the possibility of POSCTL flight mode, and autonomous flight operating on a camera pointed downwards that detects changes of ground texture.
|
||||
Running the "Optical Flow" function offers the possibility of POSCTL flight mode, and autonomous flight operating on a camera pointed downwards that detects changes of ground texture.
|
||||
|
||||
## Enabling
|
||||
|
||||
> **Hint** It is recommended to use [special PX4 firmware for Clover](firmware.md).
|
||||
|
||||
The use of a rangefinder is essential. [Connect and setup laser-ranging sensor VL53L1X](laser.md), according to the manual.
|
||||
> **Hint** For Optical Flow to work it's required that the laser rangefinder is [connected and configured](laser.md).
|
||||
|
||||
Enable Optical Flow in the file `~/catkin_ws/src/clover/clover/launch/clover.launch`:
|
||||
|
||||
@@ -14,7 +12,7 @@ Enable Optical Flow in the file `~/catkin_ws/src/clover/clover/launch/clover.lau
|
||||
<arg name="optical_flow" default="true"/>
|
||||
```
|
||||
|
||||
Optical Flow publishes data in `mavros/px4flow/raw/send` topic. In the topic `optical_flow/debug` is also published a visualization, that can be viewed with [web_video_server](web_video_server.md).
|
||||
Optical Flow publishes data in `/mavros/px4flow/raw/send` topic. In the topic `/optical_flow/debug` is also published a visualization, that can be viewed with [web_video_server](web_video_server.md).
|
||||
|
||||
> **Info** Correct connection and [setup](camera.md) of the camera module is needed for proper functioning.
|
||||
|
||||
|
||||
112
docs/en/parameters.md
Normal file
112
docs/en/parameters.md
Normal file
@@ -0,0 +1,112 @@
|
||||
# PX4 Parameters
|
||||
|
||||
Full documentation on PX4 parameters: https://docs.px4.io/master/en/advanced_config/parameter_reference.html.
|
||||
|
||||
For changing PX4 parameters, use QGroundControl software, [connect to Clover over Wi-Fi](gcs_bridge.md) or USB. Go to *Vehicle Setup* panel (click on the QGroundControl logo in the top-left corner) and choose *Parameters* menu.
|
||||
|
||||
## Recommended values
|
||||
|
||||
### Common parameters
|
||||
|
||||
|Parameter|Value|Comment|
|
||||
|-|-|-|
|
||||
|`SENS_FLOW_ROT`|0 (*No rotation*)|If using *PX4Flow* hardware, keep the default value|
|
||||
|`SENS_FLOW_MINHGT`|0.01|For [VL53L1X](laser.md) rangefinder|
|
||||
|`SENS_FLOW_MAXHGT`|4.0|For [VL53L1X](laser.md) rangefinder|
|
||||
|`SENS_FLOW_MAXR`|10.0||
|
||||
|`SYS_HAS_MAG`|0|If impossible to run the magnetometer (*No mags found* error)|
|
||||
|
||||
### Estimator subsystem parameters
|
||||
|
||||
In case of using LPE ([COEX patched firmware](firmware.md)):
|
||||
|
||||
|Parameter|Value|Comment|
|
||||
|-|-|-|
|
||||
|`LPE_FUSION`|86|Checkboxes: *flow* + *vis* + *land Detector* + *gyro comp*. If flying over horizontal floor *pub agl as lpos down* checkbox is allowed.<br>Details: [Optical Flow](optical_flow.md), [ArUco markers](aruco_map.md), [GPS](gps.md).|
|
||||
|`LPE_VIS_DELAY`|0.0||
|
||||
|`LPE_VIS_Z`|0.1||
|
||||
|`LPE_FLW_SCALE`|1.0||
|
||||
|`LPE_FLW_R`|0.2||
|
||||
|`LPE_FLW_RR`|0.0||
|
||||
|`LPE_FLW_QMIN`|10||
|
||||
|`ATT_W_EXT_HDG`|0.5|Enabling usage of external yaw angle (when navigating using [markers map](aruco_map.md))|
|
||||
|`ATT_EXT_HDG_M`|1 (*Vision*)||
|
||||
|`ATT_W_MAG`|0|Disabling usage of the magnetometer (when navigating indoor)|
|
||||
|
||||
In case of using EKF2 (official firmware):
|
||||
|
||||
<!-- markdownlint-disable MD044 -->
|
||||
|
||||
|Parameter|Value|Comment|
|
||||
|-|-|-|
|
||||
|`EKF2_AID_MASK`|27|Checkboxes: (optionally) *gps* + *flow* + *vision position* + *vision yaw*.<br>Details: [Optical Flow](optical_flow.md), [ArUco markers](aruco_map.md), [GPS](gps.md).|
|
||||
|`EKF2_OF_DELAY`|0||
|
||||
|`EKF2_OF_QMIN`|10||
|
||||
|`EKF2_OF_N_MIN`|0.05||
|
||||
|`EKF2_OF_N_MAX`|0.2||
|
||||
|`EKF2_HGT_MODE`|2 (*Range sensor*)|If the [rangefinder](laser.md) is present and flying over horizontal floor|
|
||||
|`EKF2_EVA_NOISE`|0.1||
|
||||
|`EKF2_EVP_NOISE`|0.1||
|
||||
|`EKF2_EV_DELAY`|0||
|
||||
|`EKF2_MAG_TYPE`|5 (*None*)|Disabling usage of the magnetometer (when navigating indoor)|
|
||||
|
||||
<!-- markdownlint-enable MD031 -->
|
||||
|
||||
> **Info** See also: list of default parameters of the [Clover simulator](simulation.md): https://github.com/CopterExpress/clover/blob/master/clover_simulation/airframes/4500_clover.
|
||||
|
||||
## Additional information
|
||||
|
||||
The `SYS_MC_EST_GROUP` parameter defines the estimator subsystem to use.
|
||||
|
||||
Estimator subsystem is a group of modules that calculates the current state of the copter using readings from the sensors. The copter state includes:
|
||||
|
||||
* Angle rate of the copter – pitch_rate, roll_rate, yaw_rate;
|
||||
* Copter orientation (in the local coordinate system) – pitch, roll, yaw (one of presentations);
|
||||
* Copter position (in the local coordinate system) – x, y, z;
|
||||
* Copter speed (in the local coordinate system) – vx, vy, vz;
|
||||
* Global coordinates of the copter – latitude, longitude, altitude;
|
||||
* Altitude above the surface;
|
||||
* Other parameters (the drift of gyroscopes, wind speed, etc.).
|
||||
|
||||
`SYS_AUTOCONFIG` — resets all parameters (sets to 1).
|
||||
|
||||
## EKF2
|
||||
|
||||
`EKF2_AID_MASK` — selects sensors that are used by EKF2 to calculate the copter state.
|
||||
|
||||
`EKF2_HGT_MODE` is the main source of height data (z in the local coordinate system):
|
||||
|
||||
* 0 – pressure reading on the barometer.
|
||||
* 1 – GPS.
|
||||
* 2 – distance meter (for example, vl53l1x).
|
||||
* 3 – data from VPE.
|
||||
|
||||
Variant 2 is the most accurate; however, it is correct to use it only if the surface the copter flies over is flat. Otherwise, the Z axis origin will move up and down with the altitude of the surface.
|
||||
|
||||
## Multicopter Position Control
|
||||
|
||||
These parameters adjust the flight of the copter by position (POSCTL, OFFBOARD, AUTO modes).
|
||||
|
||||
`MPC_THR_HOVER` — hovering throttle. This option is to set to the approximate percentage of throttle needed to make the copter maintain its altitude. If copter has a tendency to gain or lose altitude during the hovering mode, reduce or increase this value.
|
||||
|
||||
`MPC_XY_P` – position factor *P* of the ESC. This parameter affects how sharply the copter will react to the position commands. A too high value may cause overshoots.
|
||||
|
||||
`MPC_XY_VEL_P` – speed factor *P* of the ESC. This parameter also affects the accuracy and sharpness of copter execution of the given position. A too high value may cause overshoots.
|
||||
|
||||
`MPC_XY_VEL_MAX` — the maximum horizontal speed in POSCTL, OFFBOARD, AUTO modes.
|
||||
|
||||
`MPC_Z_P`, `MPC_Z_VEL_P` – vertical position and speed factors *P* of the ESCs they determine the copter's ability to maintain the desired altitude.
|
||||
|
||||
`MPC_LAND_SPEED` is the vertical velocity of landing in the LAND mode.
|
||||
|
||||
## LPE + Q attitude estimator
|
||||
|
||||
These parameters configure the behavior of the `lpe` and `q` modules, which compute the state (orientation, position) of the copter. These parameters apply **only** if the `SYS_MC_EST_GROUP` parameter is set to `1` (local_position_estimator, attitude_estimator_q).
|
||||
|
||||
## Commander
|
||||
|
||||
Prearm checks, switching the modes and states of the copter.
|
||||
|
||||
## Sensors
|
||||
|
||||
Enabling, disabling and configuring various sensors.
|
||||
@@ -6,15 +6,16 @@ Open the *Vehicle Setup* tab and select the *Power* menu.
|
||||
|
||||
> **Note** Power sensor calibration should be done with the battery pack connected to the drone.
|
||||
|
||||
If there is no voltage indicator or manual calibration is not possible, set the average value of the voltage divider for the Clover 4 kit (*Voltage divider* = 11).
|
||||
|
||||
1. Set the *Number of cells* parameter according to the number of cells in your battery (*3* for the Clover 4 drone).
|
||||
2. Calculate the voltage divider:
|
||||
1. In QGroundControl software, go the *Vehicle Setup* panel and choose the *Power* menu.
|
||||
2. Set the *Number of cells* parameter according to the number of cells in your battery (*3* for the Clover 4 drone).
|
||||
3. Calculate the voltage divider:
|
||||
* Measure voltage across the battery (you may use a battery voltage tester for that).
|
||||
* Press the *Calculate* button next to the *Voltage divider* label.
|
||||
* Put the battery voltage into the prompt and click *Calculate*.
|
||||
* Press *Close* to save the calculated value.
|
||||
|
||||
If there is no voltage indicator or manual calibration is not possible, set the average value of the voltage divider for the Clover 4 kit (*Voltage divider* = 11).
|
||||
|
||||
<img src="../assets/qgc-voltage-divider.png" class="zoom">
|
||||
|
||||
Further reading: https://docs.qgroundcontrol.com/en/SetupView/Power.html.
|
||||
@@ -30,6 +31,6 @@ Further reading: https://docs.qgroundcontrol.com/en/SetupView/Power.html.
|
||||
|
||||
<img src="../assets/qgc-power.png" class="zoom">
|
||||
|
||||
Further reading: https://docs.px4.io/v1.9.0/en/advanced_config/esc_calibration.html.
|
||||
Further reading: https://docs.px4.io/master/en/advanced_config/esc_calibration.html.
|
||||
|
||||
**Next**: [Failsafe configuration](failsafe.md)
|
||||
|
||||
@@ -1,72 +0,0 @@
|
||||
# PX4 Parameters
|
||||
|
||||
Main article: https://dev.px4.io/en/advanced/parameter_reference.html
|
||||
|
||||
> **Note** This is a description some of the most important PX4 parameters as of version 1.8.0. The full list is available at the link above.
|
||||
|
||||
To change PX4 parameters, you can use the QGroundControl application [by connecting to Clover via Wi-Fi](gcs_bridge.md):
|
||||
|
||||

|
||||
|
||||
## Main parameters
|
||||
|
||||
The most important parameters are listed in this paragraph.
|
||||
|
||||
`SYS_MC_EST_GROUP` – select the estimator module.
|
||||
|
||||
This is a group of modules that calculates the current state of the copter using readings from the sensors. The copter state includes:
|
||||
|
||||
* Angle rate of the copter – pitch_rate, roll_rate, yaw_rate;
|
||||
* Copter orientation (in the local coordinate system) – pitch, roll, yaw (one of presentations);
|
||||
* Copter position (in the local coordinate system) – x, y, z;
|
||||
* Copter speed (in the local coordinate system) – vx, vy, vz;
|
||||
* Global coordinates of the copter – latitude, longitude, altitude;
|
||||
* Altitude above the surface;
|
||||
* Other parameters (the drift of gyroscopes, wind speed, etc.).
|
||||
|
||||
`SYS_AUTOCONFIG` — resets all parameters (sets to 1).
|
||||
|
||||
## EKF2
|
||||
|
||||
`EKF2_AID_MASK` — selects sensors that are used by EKF2 to calculate the copter state.
|
||||
|
||||
`EKF2_HGT_MODE` is the main source of height data (z in the local coordinate system):
|
||||
|
||||
* 0 – pressure reading on the barometer.
|
||||
* 1 – GPS.
|
||||
* 2 – distance meter (for example, vl53l1x).
|
||||
* 3 – data from VPE.
|
||||
|
||||
Variant 2 is the most accurate; however, it is correct to use it only if the surface the copter flies over is flat. Otherwise, the Z axis origin will move up and down with the altitude of the surface.
|
||||
|
||||
## Multicopter Position Control
|
||||
|
||||
These parameters adjust the flight of the copter by position (POSCTL, OFFBOARD, AUTO modes).
|
||||
|
||||
`MPC_THR_HOVER` — hovering throttle. This option is to set to the approximate percentage of throttle needed to make the copter maintain its altitude. If copter has a tendency to gain or lose altitude during the hovering mode, reduce or increase this value.
|
||||
|
||||
`MPC_XY_P` – position factor *P* of the ESC. This parameter affects how sharply the copter will react to the position commands. A too high value may cause overshoots.
|
||||
|
||||
`MPC_XY_VEL_P` – speed factor *P* of the ESC. This parameter also affects the accuracy and sharpness of copter execution of the given position. A too high value may cause overshoots.
|
||||
|
||||
`MPC_XY_VEL_MAX` — the maximum horizontal speed in POSCTL, OFFBOARD, AUTO modes.
|
||||
|
||||
`MPC_Z_P`, `MPC_Z_VEL_P` – vertical position and speed factors *P* of the ESCs they determine the copter's ability to maintain the desired altitude.
|
||||
|
||||
`MPC_LAND_SPEED` is the vertical velocity of landing in the LAND mode.
|
||||
|
||||
## LPE + Q attitude estimator
|
||||
|
||||
These parameters configure the behavior of the `lpe` and `q` modules, which compute the state (orientation, position) of the copter. These parameters apply **only** if the `SYS_MC_EST_GROUP` parameter is set to `1` (local_position_estimator, attitude_estimator_q)
|
||||
|
||||
TODO
|
||||
|
||||
## Commander
|
||||
|
||||
Prearm checks, switching the modes and states of the copter.
|
||||
|
||||
## Sensors
|
||||
|
||||
Enabling, disabling and configuring various sensors.
|
||||
|
||||
TODO
|
||||
@@ -9,7 +9,7 @@ Before connecting and calibrating the RC, make sure that:
|
||||
|
||||
## Connecting the RC transmitter
|
||||
|
||||
1. Open the *Vehicle Setup* tab and select the *Radio* menu.
|
||||
1. In QGroundControl software, go the *Vehicle Setup* panel and choose the *Radio* menu.
|
||||
2. Power on the transmitter by sliding the **POWER** slider up.
|
||||
3. Make sure the transmitter-receiver link is working.
|
||||
|
||||
|
||||
@@ -49,7 +49,7 @@ Each topic has the a of messages it passes. ROS include a lot of standard messag
|
||||
|Message type|Description|
|
||||
|-|-|
|
||||
|[`std_msgs/Int64`](https://docs.ros.org/api/std_msgs/html/msg/Int64.html)|Integer number.|
|
||||
|[`std_msgs/Float64`](https://docs.ros.org/api/std_msgs/html/msg/Float64.html)|Double-precision floating-point number|
|
||||
|[`std_msgs/Float64`](https://docs.ros.org/api/std_msgs/html/msg/Float64.html)|Double-precision floating-point number.|
|
||||
|[`std_msgs/String`](https://docs.ros.org/api/std_msgs/html/msg/String.html)|String.|
|
||||
|[`geometry_msgs/PoseStamped`](https://docs.ros.org/api/geometry_msgs/html/msg/PoseStamped.html)|Position and orientation of an object in a given [coordinate system](frames.md) and a time stamp (widely used for passing the robot pose or some robot's part pose).|
|
||||
|[`geometry_msgs/TwistStamped`](https://docs.ros.org/api/geometry_msgs/html/msg/TwistStamped.html)|Linear and angular velocity of an object in a given coordinate system and a time stamp.|
|
||||
|
||||
@@ -43,7 +43,7 @@ Axis or Grid configured to frame `aruco_map` will visualize the location [on the
|
||||
|
||||
### jsk_rviz_plugins
|
||||
|
||||
It is also recommended to install additional useful plugins for rviz [jsk_rviz_plugins](https://jsk-docs.readthedocs.io/en/latest/jsk_visualization/doc/jsk_rviz_plugins/index.html). This kit allows visualizing topics like `TwistStamped` (velocity) `CameraInfo`, `PolygonArray`, and many more. To install, use command:
|
||||
It is also recommended to install additional useful plugins for rviz [jsk_rviz_plugins](https://jsk-visualization.readthedocs.io/en/latest/jsk_rviz_plugins/index.html). This kit allows visualizing topics like `TwistStamped` (velocity) `CameraInfo`, `PolygonArray`, and many more. To install, use command:
|
||||
|
||||
```(bash)
|
||||
sudo apt-get install ros-melodic-jsk-visualization
|
||||
|
||||
@@ -27,28 +27,29 @@ Main article: https://docs.qgroundcontrol.com/en/SetupView/Firmware.html
|
||||
|
||||
> **Note** Do not connect your flight controller prior to flashing.
|
||||
|
||||
We recommend using the modified version of PX4 by CopterExpress for the Clover drone, especially for autonomous flights. Download the latest stable version **<a class="latest-firmware v4" href="https://github.com/CopterExpress/Firmware/releases">from our GitHub</a>**.
|
||||
We recommend using the modified version of [PX4 with COEX patches](firmware.md) for the Clover drone, especially for autonomous flights. Download the latest stable version **<a class="latest-firmware v4" href="https://github.com/CopterExpress/Firmware/releases">from our GitHub</a>**.
|
||||
|
||||
> **Info** For Pixhawk-based quadcopters there is a separate firmware version. See details in "[Pixhawk / Pixracer firmware flashing](firmware.md)" article.
|
||||
To use all the most recent PX4 functions you also can use the latest official firmware version (experimentally).
|
||||
|
||||
Flash the flight controller with this firmware:
|
||||
|
||||
<img src="../assets/qgc-firmware.png" alt="QGroundControl firmware upload" class="zoom">
|
||||
|
||||
1. Launch QGroundControl software.
|
||||
2. Open the *Vehicle Setup* tab.
|
||||
3. Select the *Firmware* menu.
|
||||
1. Disconnect the flight controller from computer (if connected).
|
||||
2. Launch QGroundControl software.
|
||||
3. Go to *Vehicle Setup* panel (click on the QGroundControl logo in the top-left corner) and select *Firmware* menu.
|
||||
4. Connect your flight controller to your PC over USB.
|
||||
5. Wait for the flight controller to connect to QGroundControl.
|
||||
6. Select *PX4 Flight Stack* in the right bar.
|
||||
5. Select *PX4 Flight Stack* in the right bar appeared.
|
||||
|
||||
To use the recommended Copter Express firmware:
|
||||
<img src="../assets/qgc-firmware.png" alt="QGroundControl firmware upload" class="zoom">
|
||||
|
||||
* Check *Advanced Settings* checkbox.
|
||||
* Select *Custom firmware file...* from the dropdown list.
|
||||
* Press *OK* and select the file that you've downloaded.
|
||||
6. To use **COEX patched firmware**:
|
||||
|
||||
To use the latest official stable firmware just press *OK*.
|
||||
* Check *Advanced Settings* checkbox.
|
||||
* Select *Custom firmware file...* from the dropdown list.
|
||||
* Press *OK* and select the file that you've downloaded.
|
||||
|
||||
To use the latest **official stable firmware** just press *OK*.
|
||||
|
||||
Wait for QGroundControl to finish flashing the flight controller.
|
||||
|
||||
@@ -82,7 +83,7 @@ This is how the main QGroundControl settings window will look like:
|
||||
|
||||
### Setting parameters
|
||||
|
||||
Open the *Vehicle Setup* tab and select the *Parameters* menu. You can use the *Search* field to find parameters by name.
|
||||
Open the *Vehicle Setup* tab and select the *Parameters* menu. You can use the *Search* field to find parameters by name. Recommended parameters values are given in the further documentation and also in the [parameters summary article](parameters.md).
|
||||
|
||||
<img src="../assets/qgc-parameters.png" alt="QGroundControl parameters" class="zoom">
|
||||
|
||||
|
||||
@@ -1,11 +1,4 @@
|
||||
Autonomous flight (OFFBOARD)
|
||||
===
|
||||
|
||||
> **Note** In the image version **0.20** `clever` package was renamed to `clover`. See [previous version of the article](https://github.com/CopterExpress/clover/blob/v0.19/docs/en/simple_offboard.md) for older images.
|
||||
|
||||
<!-- -->
|
||||
|
||||
> **Hint** We recommend using our [custom PX4 firmware for Clover](firmware.md#modified-firmware-for-clover) for autonomous flights.
|
||||
# Autonomous flight
|
||||
|
||||
The `simple_offboard` module of the `clover` package is intended for simplified programming of the autonomous drone flight (`OFFBOARD` [flight mode](modes.md)). It allows setting the desired flight tasks, and automatically transforms [coordinates between frames](frames.md).
|
||||
|
||||
@@ -13,8 +6,7 @@ The `simple_offboard` module of the `clover` package is intended for simplified
|
||||
|
||||
Main services are [`get_telemetry`](#gettelemetry) (receive telemetry data), [`navigate`](#navigate) (fly to a given point along a straight line), [`navigate_global`](#navigateglobal) (fly to a point specified as latitude and longitude along a straight line), [`land`](#land) (switch to landing mode).
|
||||
|
||||
Python examples
|
||||
---
|
||||
## Python usage
|
||||
|
||||
You need to create proxies for services before calling them. Use the following template for your programs:
|
||||
|
||||
@@ -37,8 +29,7 @@ land = rospy.ServiceProxy('land', Trigger)
|
||||
|
||||
Unused proxy functions may be removed from the code.
|
||||
|
||||
API description
|
||||
---
|
||||
## API description
|
||||
|
||||
> **Note** Omitted numeric parameters are set to 0.
|
||||
|
||||
@@ -295,7 +286,7 @@ The positive direction of `yaw_rate` rotation (when viewed from the top) is coun
|
||||
|
||||
Switch the drone to landing [mode](modes.md) (`AUTO.LAND` or similar).
|
||||
|
||||
> **Note** Set the `COM_DISARM_LAND` [PX4 parameter](px4_parameters.md) to a value greater than 0 to enable automatic disarm after landing.
|
||||
> **Note** Set the `COM_DISARM_LAND` [PX4 parameter](parameters.md) to a value greater than 0 to enable automatic disarm after landing.
|
||||
|
||||
Landing the drone:
|
||||
|
||||
@@ -312,14 +303,9 @@ Landing the drone (command line):
|
||||
rosservice call /land "{}"
|
||||
```
|
||||
|
||||
<!--
|
||||
### release
|
||||
> **Caution** In recent PX4 versions, the vehicle will be switched out of LAND mode to manual mode, if the remote control sticks are moved significantly.
|
||||
|
||||
Stop publishing setpoints to the drone (release control). Required to continue monitoring by means of [MAVROS](mavros.md).
|
||||
-->
|
||||
|
||||
Additional materials
|
||||
------------------------
|
||||
## Additional materials
|
||||
|
||||
* [ArUco-based position estimation and navigation](aruco.md).
|
||||
* [Program samples and snippets](snippets.md).
|
||||
|
||||
@@ -75,7 +75,7 @@ The plugin will collect publishing rate statistics and slow the simulation down
|
||||
|
||||
### Set simulation speed
|
||||
|
||||
Since v1.9 the PX4 SITL setup supports [setting the simulation speed](https://dev.px4.io/v1.9.0/en/simulation/#simulation_speed) by setting the `PX4_SIM_SPEED_FACTOR` environment variable. Its value is picked up by PX4 startup scripts, which in turn reconfigure it to expect a certain speedup/slowdown.
|
||||
Since v1.9 the PX4 SITL setup supports [setting the simulation speed](https://docs.px4.io/master/en/simulation/#run-simulation-faster-than-realtime) by setting the `PX4_SIM_SPEED_FACTOR` environment variable. Its value is picked up by PX4 startup scripts, which in turn reconfigure it to expect a certain speedup/slowdown.
|
||||
|
||||
You should set its value to the actual real time factor that you get with `throttling_camera`. The real time factor may be found in the Gazebo GUI window at the bottom:
|
||||
|
||||
|
||||
@@ -5,7 +5,7 @@ PX4 Simulation
|
||||
|
||||
Main article: https://dev.px4.io/en/simulation/
|
||||
|
||||
PX4 simulation is possible in Linux and macOS with the use of physical environment simulation systems [jMAVSim](https://pixhawk.org/dev/hil/jmavsim) and [the Gazebo](http://gazebosim.org).
|
||||
PX4 simulation is possible in Linux and macOS with the use of physical environment simulation systems [jMAVSim](https://docs.px4.io/master/en/simulation/jmavsim.html) and [the Gazebo](http://gazebosim.org).
|
||||
|
||||
jMAVSim is a lightweight environment intended only for testing multi-rotor aircraft systems; Gazebo is a versatile environment for all types of robots.
|
||||
|
||||
|
||||
@@ -8,13 +8,11 @@
|
||||
|
||||
<a name="block-takeoff"></a><!-- old name of anchor -->
|
||||
|
||||
Fly towards a point and wait for copter's arrival:
|
||||
Function to fly to a point and wait for copter's arrival:
|
||||
|
||||
```python
|
||||
import math
|
||||
|
||||
#...
|
||||
|
||||
def navigate_wait(x=0, y=0, z=0, yaw=float('nan'), speed=0.5, frame_id='', auto_arm=False, tolerance=0.2):
|
||||
navigate(x=x, y=y, z=z, yaw=yaw, speed=speed, frame_id=frame_id, auto_arm=auto_arm)
|
||||
|
||||
@@ -64,8 +62,6 @@ Wait for copter's arrival to the [navigate](simple_offboard.md#navigate) target:
|
||||
```python
|
||||
import math
|
||||
|
||||
# ...
|
||||
|
||||
def wait_arrival(tolerance=0.2):
|
||||
while not rospy.is_shutdown():
|
||||
telem = get_telemetry(frame_id='navigate_target')
|
||||
@@ -79,6 +75,8 @@ def wait_arrival(tolerance=0.2):
|
||||
Calculate the distance between two points (**important**: the points are to be in the same [coordinate system](frames.md)):
|
||||
|
||||
```python
|
||||
import math
|
||||
|
||||
def get_distance(x1, y1, z1, x2, y2, z2):
|
||||
return math.sqrt((x1 - x2) ** 2 + (y1 - y2) ** 2 + (z1 - z2) ** 2)
|
||||
```
|
||||
@@ -88,6 +86,8 @@ def get_distance(x1, y1, z1, x2, y2, z2):
|
||||
Approximation of distance (in meters) between two global coordinates (latitude/longitude):
|
||||
|
||||
```python
|
||||
import math
|
||||
|
||||
def get_distance_global(lat1, lon1, lat2, lon2):
|
||||
return math.hypot(lat1 - lat2, lon1 - lon2) * 1.113195e5
|
||||
```
|
||||
@@ -203,19 +203,16 @@ from geometry_msgs.msg import PoseStamped, TwistStamped
|
||||
from sensor_msgs.msg import BatteryState
|
||||
from mavros_msgs.msg import RCIn
|
||||
|
||||
# ...
|
||||
|
||||
def pose_update(pose):
|
||||
# Processing new data of copter's position
|
||||
pass
|
||||
|
||||
# Other handler functions
|
||||
# ...
|
||||
|
||||
rospy.Subscriber('/mavros/local_position/pose', PoseStamped, pose_update)
|
||||
rospy.Subscriber('/mavros/local_position/velocity', TwistStamped, velocity_update)
|
||||
rospy.Subscriber('/mavros/battery', BatteryState, battery_update)
|
||||
rospy.Subscriber('mavros/rc/in', RCIn, rc_callback)
|
||||
|
||||
rospy.spin()
|
||||
```
|
||||
|
||||
Information about MAVROS topics is available at [the link](mavros.md).
|
||||
@@ -229,18 +226,13 @@ Information about MAVROS topics is available at [the link](mavros.md).
|
||||
Send an arbitrary [MAVLink message](mavlink.md) to the copter:
|
||||
|
||||
```python
|
||||
# ...
|
||||
|
||||
from mavros_msgs.msg import Mavlink
|
||||
from mavros import mavlink
|
||||
from pymavlink import mavutil
|
||||
|
||||
# ...
|
||||
|
||||
mavlink_pub = rospy.Publisher('mavlink/to', Mavlink, queue_size=1)
|
||||
|
||||
# Sending a HEARTBEAT message:
|
||||
|
||||
msg = mavutil.mavlink.MAVLink_heartbeat_message(mavutil.mavlink.MAV_TYPE_GCS, 0, 0, 0, 0, 0)
|
||||
msg.pack(mavutil.mavlink.MAVLink('', 2, 1))
|
||||
ros_msg = mavlink.convert_to_rosmsg(msg)
|
||||
@@ -281,8 +273,6 @@ Change the [flight mode](modes.md) to arbitrary one:
|
||||
```python
|
||||
from mavros_msgs.srv import SetMode
|
||||
|
||||
# ...
|
||||
|
||||
set_mode = rospy.ServiceProxy('mavros/set_mode', SetMode)
|
||||
|
||||
# ...
|
||||
@@ -297,8 +287,6 @@ Flip:
|
||||
```python
|
||||
import math
|
||||
|
||||
# ...
|
||||
|
||||
PI_2 = math.pi / 2
|
||||
|
||||
def flip():
|
||||
@@ -337,8 +325,6 @@ from pymavlink import mavutil
|
||||
from mavros_msgs.srv import CommandLong
|
||||
from mavros_msgs.msg import State
|
||||
|
||||
# ...
|
||||
|
||||
send_command = rospy.ServiceProxy('/mavros/cmd/command', CommandLong)
|
||||
|
||||
def calibrate_gyro():
|
||||
@@ -372,8 +358,6 @@ Enable and disable [ArUco markers recognition](aruco_marker.md) dynamically (for
|
||||
import rospy
|
||||
import dynamic_reconfigure.client
|
||||
|
||||
# ...
|
||||
|
||||
client = dynamic_reconfigure.client.Client('aruco_detect')
|
||||
|
||||
# Turn markers recognition off
|
||||
@@ -392,8 +376,6 @@ Wait for global position to appear (finishing [GPS receiver](gps.md) initializat
|
||||
```python
|
||||
import math
|
||||
|
||||
# ...
|
||||
|
||||
while not rospy.is_shutdown():
|
||||
if math.isfinite(get_telemetry().lat):
|
||||
break
|
||||
@@ -408,12 +390,8 @@ Read flight controller's parameter:
|
||||
from mavros_msgs.srv import ParamGet
|
||||
from mavros_msgs.msg import ParamValue
|
||||
|
||||
# ...
|
||||
|
||||
param_get = rospy.ServiceProxy('mavros/param/get', ParamGet)
|
||||
|
||||
# ...
|
||||
|
||||
# Read parameter of type INT
|
||||
value = param_get(param_id='COM_FLTMODE1').value.integer
|
||||
|
||||
@@ -429,12 +407,8 @@ Set flight controller's parameter:
|
||||
from mavros_msgs.srv import ParamSet
|
||||
from mavros_msgs.msg import ParamValue
|
||||
|
||||
# ...
|
||||
|
||||
param_set = rospy.ServiceProxy('mavros/param/set', ParamSet)
|
||||
|
||||
# ...
|
||||
|
||||
# Set parameter of type INT:
|
||||
param_set(param_id='COM_FLTMODE1', value=ParamValue(integer=8))
|
||||
|
||||
|
||||
@@ -89,7 +89,7 @@ while True:
|
||||
|
||||
### Filtering the data
|
||||
|
||||
To filter (smooth out) the data and delete [outliers](https://en.wikipedia.org/wiki/Outlier), [Kalman filter](https://en.wikipedia.org/wiki/Kalman_filter) or a simple [median filter](https://ru.wikipedia.org/wiki/Median_filter) can be used. An example of median filtering implementation:
|
||||
To filter (smooth out) the data and delete [outliers](https://en.wikipedia.org/wiki/Outlier), [Kalman filter](https://en.wikipedia.org/wiki/Kalman_filter) or a simple [median filter](https://en.wikipedia.org/wiki/Median_filter) can be used. An example of median filtering implementation:
|
||||
|
||||
```python
|
||||
import collections
|
||||
|
||||
@@ -75,7 +75,7 @@
|
||||
* [Пилотирование со смартфона](rc.md)
|
||||
* [Настройка сети RPi](network.md)
|
||||
* [Интерфейс UART](uart.md)
|
||||
* [Параметры PX4](px4_parameters.md)
|
||||
* [Параметры PX4](parameters.md)
|
||||
* [Работа с логами PX4](flight_logs.md)
|
||||
* [Прошивка PX4](firmware.md)
|
||||
* [Протокол MAVLink](mavlink.md)
|
||||
@@ -115,6 +115,7 @@
|
||||
* [CopterHack-2018](copterhack2018.md)
|
||||
* [CopterHack-2017](copterhack2017.md)
|
||||
* [Конкурс видео](video_contest.md)
|
||||
* [Образовательные конкурсы](educational_contests.md)
|
||||
* [Проекты на базе Клевера](projects.md)
|
||||
* [Система автоматической посадки (AMLS)](amls.md)
|
||||
* [Разработка системы для управления БПЛА с помощью шлема виртуальной реальности](remote-control-with-oculusvr.md)
|
||||
|
||||
@@ -93,7 +93,7 @@ rosrun aruco_pose genmap.py 0.33 2 4 1 1 0 -o test_map.txt
|
||||
|
||||
## Настройка VPE
|
||||
|
||||
Для работы механизма Vision Position Estimation необходимы следующие [настройки PX4](px4_parameters.md).
|
||||
Для работы механизма Vision Position Estimation необходимы следующие [настройки PX4](parameters.md).
|
||||
|
||||
При использовании **LPE** (параметр `SYS_MC_EST_GROUP` = `local_position_estimator, attitude_estimator_q`):
|
||||
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
systemd
|
||||
---
|
||||
|
||||
Основная документация: [https://wiki.archlinux.org/index.php/Systemd_(Русский)](https://wiki.archlinux.org/index.php/Systemd_(Русский)).
|
||||
Основная документация: https://wiki.archlinux.org/index.php/Systemd_(Русский).
|
||||
|
||||
Все автоматически стартуемое ПО Клевера запускается в виде systemd-сервиса `clover.service`.
|
||||
|
||||
@@ -54,8 +54,8 @@ roslaunch
|
||||
chmod +x my_program.py
|
||||
```
|
||||
|
||||
При использовании скриптовых языков вначале файла должен стоять [shebang](https://ru.wikipedia.org/wiki/Шебанг_(Unix)), например:
|
||||
При использовании скриптовых языков вначале файла должен стоять <a href="https://ru.wikipedia.org/wiki/Шебанг_(Unix)">shebang</a>, например:
|
||||
|
||||
```bash
|
||||
#!/usr/bin/env python
|
||||
#!/usr/bin/env python3
|
||||
```
|
||||
|
||||
@@ -42,4 +42,4 @@ sudo systemctl start clever-blocks.service
|
||||
python main.py
|
||||
```
|
||||
|
||||
После запуска Вы можете открыть веб-интерфейс для блочного программирования по адресу [192.168.11.1:5000](192.168.11.1:5000).
|
||||
После запуска Вы можете открыть веб-интерфейс для блочного программирования по адресу [192.168.11.1:5000](http://192.168.11.1:5000).
|
||||
|
||||
@@ -16,7 +16,7 @@
|
||||
|
||||
Поле `connected` должно содержать значение `True`.
|
||||
|
||||
> **Hint** Для корректной работы подключения Raspberry Pi и Pixhawk по USB необходимо установить значение [параметра](px4_parameters.md) `CBRK_USB_CHK` на 197848.
|
||||
> **Hint** Для корректной работы подключения Raspberry Pi и Pixhawk по USB необходимо установить значение [параметра](parameters.md) `CBRK_USB_CHK` на 197848.
|
||||
|
||||
## Подключение по UART
|
||||
|
||||
|
||||
@@ -13,27 +13,27 @@ CopterHack 2022 — это международный конкурс по ра
|
||||
|Место|Команда|Проект|Балл|
|
||||
|:-:|-|-|-|
|
||||
||🇰🇬 Alatoo University Team|[Облачная платформа для симулятора Клевера](https://github.com/pteacher/clover/blob/clover_simulator/docs/ru/clover-development-studio.md)||
|
||||
||🇧🇾 FTL|[Advanced Clover 2](https://github.com/FTL-team/clover/blob/FTL-advancedClover2/docs/ru/advancedclover2.md)||
|
||||
||🇻🇳 Dragon&Tanker|[Dragon&Tanker](https://github.com/uml4/clover/blob/drone_observe_autonomous_car/docs/en/dragon_and_tanker_team.md)||
|
||||
||🇧🇾 FTL|[Advanced Clover 2](https://github.com/FTL-team/clover/blob/FTL-advancedClover2/docs/ru/advanced_clover_simulator.md)||
|
||||
||🇷🇺 Stereo|[Neural obstacle avoidance](https://github.com/den250400/clover/blob/neural-obstacle-avoidance/docs/en/neural-obstacle-avoidance.md)||
|
||||
||🇷🇺 Space clowns|[Copter For Space](https://github.com/slavikyd/clover/blob/patch-3/docs/ru/c4s.md)||
|
||||
||🇷🇺 R.S.|[Drone Hawk](https://github.com/slavaroot/clover/blob/droneHawkSecurity/docs/ru/drone-hawk-security.md)||
|
||||
||🇲🇾 Moopt|[IoT Water Monitoring & Optimization](https://github.com/kafechew/clover/blob/master/docs/en/moopt-uav.md)||
|
||||
||🇧🇷 Atena - Grupo SEMEAR|[Swarm in Blocks](https://github.com/Grupo-SEMEAR-USP/clover/blob/Swarm_in_Blocks/docs/en/Swarm_in_Blocks.md)||
|
||||
||🇧🇷 Atena - Grupo SEMEAR|[Swarm in Blocks](https://github.com/Grupo-SEMEAR-USP/clover/blob/Swarm_in_Blocks/docs/en/swarm_in_blocks.md)||
|
||||
||🇷🇺 Clevertron|[Clevertron](https://github.com/Daniel-drone/clover/blob/Clevertron-1/docs/ru/clevertron.md)||
|
||||
||🇷🇺 Clover Rescue Team|[Rescue Clover](https://github.com/DevMBS/clover/blob/CloverRescueTeam/docs/ru/clover-rescue-team.md)||
|
||||
||🇵🇱 Edgenoon|[Neural and vision-based landing method](https://github.com/edgenoon-ai/clover/blob/neural_vision_based_landing_method/docs/en/neural_vision_based_landing_method.md)||
|
||||
||🇷🇺 CopterCat|[CopterCat](https://github.com/matveylapin/clover/blob/CopterCat/docs/ru/сopter_сat.md)||
|
||||
||🇷🇺 Дрой Ронов|[Clover Swarm](https://github.com/stinger000/clever/blob/clover_swarm_request/docs/ru/clover-swarm.md)||
|
||||
||🇩🇪 Inondro|[Inondro Pix](https://github.com/Inondro/clover/blob/inondro-pix/docs/en/inondro_copterhack22_pix.md)||
|
||||
||🇷🇺 V-NAV|[Visual Navigation](https://github.com/v-nav/clover/blob/v-nav_article/docs/ru/v-nav.md)||
|
||||
||🇮🇳 DJS Phoenix|[Autonomous valet parking drone assistance](https://github.com/DJSPhoenix/clover/blob/DJSPhoenix-Ikshana/docs/en/djs_phoenix_ikshana.md)||
|
||||
||🇷🇺 Джедаи 1581|[Ретранслятор на базе Клевера](https://github.com/JJNIK/clover/blob/patch-1/docs/ru/1581.md)||
|
||||
||🇷🇺 SPECTRE|[SPECTRE](https://github.com/alakhmenev/clover/blob/spectre_team/docs/ru/spectre_team.md)||
|
||||
||🇷🇺 Lucky flight|[Swarm of Improved Clover](https://github.com/bessiaka/clover/blob/Lucky-flight/docs/ru/lucky_flight.md)||
|
||||
||🇷🇺 SolidEye|[Разработка лидара без движущихся частей](https://github.com/feanorgg/clover/blob/solideye/docs/ru/solid_eye.md)||
|
||||
||🇰🇬 AI_U_CLOVER|[AIU_CLOVER](https://github.com/zhibekm/clover/blob/zhibekm-patch-1/docs/en/aiu-article.md)||
|
||||
||🇷🇺 С305|[Система мониторинга воздуха](https://github.com/Ruslan2288/clover/blob/master/docs/ru/air_monitor.md)| |
|
||||
|✕|🇻🇳 Dragon&Tanker|[Dragon&Tanker](https://github.com/uml4/clover/blob/drone_observe_autonomous_car/docs/en/dragon_and_tanker_team.md)||
|
||||
|✕|🇷🇺 V-NAV|[Visual Navigation](https://github.com/v-nav/clover/blob/v-nav_article/docs/ru/v-nav.md)||
|
||||
|✕|🇷🇺 Джедаи 1581|[Ретранслятор на базе Клевера](https://github.com/JJNIK/clover/blob/patch-1/docs/ru/1581.md)||
|
||||
|✕|🇷🇺 Lucky flight|[Swarm of Improved Clover](https://github.com/bessiaka/clover/blob/Lucky-flight/docs/ru/lucky_flight.md)||
|
||||
|✕|🇺🇸 EnviroFleet|[EnviroFleet](https://github.com/gueyman/clover/blob/envirofleet/docs/en/enviro_fleet.md)||
|
||||
|✕|🇷🇺 Бизнес-гуси|[Drone Rover Climbing System](https://github.com/HexaHEX/clover/blob/CopterHack2022_Business_Geese-1/docs/ru/business_geese.md)||
|
||||
|✕|🇷🇺 fuall|[Доставка дронами](https://github.com/Silly4s/clover/blob/master/docs/ru/dostavka.md)||
|
||||
|
||||
119
docs/ru/educational_contests.md
Normal file
119
docs/ru/educational_contests.md
Normal file
@@ -0,0 +1,119 @@
|
||||
# Образовательные конкурсы
|
||||
|
||||
## 1. Конкурс на лучшую образовательную лекцию {#lecture}
|
||||
|
||||
Компания «Коптер Экспресс» объявляет конкурс на лучшую образовательную лекцию с использованием конструктора программируемого квадрокоптера «COEX Клевер 4».
|
||||
|
||||
Основной целью конкурса является популяризация летающей робототехники и развитие сообщества данного направления.
|
||||
|
||||
### Требования к лекции
|
||||
|
||||
* Тематика лекции - открытая, на выбор участника (пример: сборка, настройка, программирование, лекция интегрированная в школьную программу и т.п.).
|
||||
* Основной инструмент лекции - «Конструктор программируемого квадрокоптера «COEX Клевер 4» и/или «Симуляционная среда программируемого квадрокоптера Клевер».
|
||||
> **Note** *Версия «COEX Клевер» не ранее [4 версии](https://clover.coex.tech/ru/assemble_4.html). «Симуляционная среда программируемого квадрокоптера Клевер» - не ранее [версии 1.0](https://github.com/CopterExpress/clover_vm/releases/tag/v1.0).
|
||||
* Видео загружено на YouTube или иную общедоступную платформу, и находится в открытом доступе для любых пользователей;
|
||||
* Язык лекции - на выбор участника. Если язык лекции не русский/английский - наличие субтитров к видео на английском языке.
|
||||
* Продолжительность лекции - от 15 мин. до 3 часов.
|
||||
* Лекция может являться частью курса или серии лекций, но должна раскрывать заданную участником тематику и быть завершенной.
|
||||
|
||||
### Требования к участникам
|
||||
|
||||
* Участник должен быть автором лекции.
|
||||
* Техническую поддержку при записи лекции могут оказывать сторонние лица.
|
||||
* Статус участника - без ограничений (школьник, студент, представитель общеобразовательного учреждения, представитель ДПО, представитель ВПО, представитель СПО, представитель отрасли, любитель).
|
||||
|
||||
### Подача заявки
|
||||
|
||||
Прием заявок осуществляется через [Google Форму](https://docs.google.com/forms/d/e/1FAIpQLScE2kN5dO2OYNSM8hOYzOa5Qvh2uDdd9Fjx8OnL1W93bfEBgw/viewform).
|
||||
|
||||
Дедлайн подачи заявок: 1 сентября 2022 года.
|
||||
|
||||
### Призы
|
||||
|
||||
По итогам представленной заявки жюри определяет победителей конкурса. При определении победителей учитываются качество видео, содержание и показатели вовлечения аудитории.
|
||||
|
||||
* 1 место: $500.
|
||||
* 2 место: $400.
|
||||
* 3 место: $300.
|
||||
* 4 место: $200.
|
||||
* 5 место: $100.
|
||||
|
||||
## 2. Конкурс на лучший школьный урок {#lesson}
|
||||
|
||||
Компания «Коптер Экспресс» объявляет конкурс на лучший школьный урок с использованием конструктора программируемого квадрокоптера «COEX Клевер 4».
|
||||
|
||||
Основной целью конкурса является популяризация летающей робототехники и развитие сообщества данного направления.
|
||||
|
||||
### Требования к уроку
|
||||
|
||||
* Основной инструмент урока - «Конструктор программируемого квадрокоптера «COEX Клевер 4».
|
||||
> **Note** *Версия «COEX Клевер» не ранее [4 версии](https://clover.coex.tech/ru/assemble_4.html).
|
||||
* Интеграция квадрокоптера в любую из общеобразовательных дисциплин (физика, математика, информатика, урок технологии и т.д.).
|
||||
* Практическое использование основного инструмента на уроке.
|
||||
* Класс - без ограничений (начальная, основная школа).
|
||||
* Продолжительность урока - 30-45 минут.
|
||||
* Формат урока - оффлайн.
|
||||
* Видео урока снято в классе общеобразовательного учреждения.
|
||||
|
||||
### Требования к участникам
|
||||
|
||||
* Участник должен быть автором урока.
|
||||
* Участник должен являться преподавателем общеобразовательного учреждения.
|
||||
|
||||
### Подача заявки
|
||||
|
||||
Прием заявок осуществляется через [Google Форму](https://docs.google.com/forms/d/e/1FAIpQLSdelVy6yQ1iN6u88KeiEIKGj7gGaM0xccSt2tiYKB46ICmjkQ/viewform).
|
||||
|
||||
Дедлайн подачи заявок: 1 сентября 2022 года.
|
||||
|
||||
### Призы
|
||||
|
||||
По итогам представленной заявки жюри определяет победителей конкурса. При определении победителей учитываются качество видео и материала.
|
||||
|
||||
* 1 место: $500.
|
||||
* 2 место: $400.
|
||||
* 3 место: $300.
|
||||
* 4 место: $200.
|
||||
* 5 место: $100.
|
||||
|
||||
## 3. Конкурс на лучший онлайн-курс {#course}
|
||||
|
||||
Компания «Коптер Экспресс» объявляет конкурс на лучший онлайн-курс с использованием конструктора программируемого квадрокоптера «COEX Клевер 4».
|
||||
|
||||
Основной целью конкурса является популяризация летающей робототехники и развитие сообщества данного направления.
|
||||
|
||||
Оценка курса производится по заявленному на конкурс отдельному, общедоступному уроку.
|
||||
|
||||
### Требования к курсу
|
||||
|
||||
* Направление курса - «Летающая робототехника».
|
||||
* Основной инструмент курса - «Конструктор программируемого квадрокоптера «COEX Клевер 4» и/или «Симуляционная среда программируемого квадрокоптера Клевер».
|
||||
> **Note** *Версия «COEX Клевер» не ранее [4 версии](https://clover.coex.tech/ru/assemble_4.html). «Симуляционная среда программируемого квадрокоптера Клевер» - не ранее [версии 1.0](https://github.com/CopterExpress/clover_vm/releases/tag/v1.0).
|
||||
* Курс расположен на общедоступной платформе (Stepik, Coursera и т.п.).
|
||||
* Доступ к курсу может быть как платный, так и бесплатный, на конкурс принимается один бесплатный и общедоступный урок заявленного курса.
|
||||
* Заявленный на конкурс урок должен быть в открытом доступе.
|
||||
* Язык курса - на выбор участника. Если язык урока не русский/английский - наличие субтитров к видео (в случае наличия видео) на английском языке.
|
||||
* Продолжительность курса и заявленного урока - не ограничена.
|
||||
* Участники вправе подать на конкурс курс разработанный ранее, и применявшийся в системе образования, с сохранением всех вышеперечисленных требований.
|
||||
|
||||
### Требования к участникам
|
||||
|
||||
* Участник должен быть автором курса.
|
||||
* Техническую поддержку при подготовке курса могут оказывать сторонние лица.
|
||||
* Статус участника - без ограничений (школьник, студент, представитель Общеобразовательного учреждения, представитель ДПО, представитель ВПО, представитель СПО, представитель отрасли, любитель).
|
||||
|
||||
### Подача заявки
|
||||
|
||||
Прием заявок осуществляется через [Google Форму](https://docs.google.com/forms/d/e/1FAIpQLSdf2Q68X4hPnFE9f3EP95AxPNnzHKqIsFHtTRT6EBKiH93wzg/viewform).
|
||||
|
||||
Дедлайн подачи заявок: 1 сентября 2022 года
|
||||
|
||||
### Призы
|
||||
|
||||
По итогам представленной заявки жюри определяет победителей конкурса. Оценка производится по заявленному на конкурс уроку, при определении победителей учитываются качество материала (формат подачи материала, общий объем и содержание курса).
|
||||
|
||||
* 1 место: $1000.
|
||||
* 2 место: $800.
|
||||
* 3 место: $600.
|
||||
* 4 место: $400.
|
||||
* 5 место: $200.
|
||||
@@ -11,7 +11,8 @@
|
||||
* `base_link` — координаты относительно квадрокоптера: схематичное изображение квадрокоптера на иллюстрации;
|
||||
* `body` — координаты относительно квадрокоптера без учета наклонов по тангажу и крену: красная, синяя и зеленая линии на иллюстрации;
|
||||
* <a name="navigate_target"></a>`navigate_target` – координаты точки, в которую сейчас летит дрон (с использованием [navigate](simple_offboard.md#navigate));
|
||||
* `setpoint` – текущий setpoint по позиции.
|
||||
* `setpoint` – текущий setpoint по позиции;
|
||||
* `main_camera_optical` – система координат, [связанная с основной камерой](camera_setup.md#frame).
|
||||
|
||||
При использовании [системы позиционирования по ArUco-маркерам](aruco.md) появляются дополнительные фреймы:
|
||||
|
||||
|
||||
@@ -38,7 +38,7 @@ rostopic echo /rangefinder/range
|
||||
|
||||
> **Hint** Для корректной работы лазерного дальномера с полетным контроллером рекомендуется использование [специальной сборки PX4 для Клевера](firmware.md#прошивка-для-клевера).
|
||||
|
||||
Для использования данных с дальномера в [PX4 должен быть сконфигурирован](px4_parameters.md).
|
||||
Для использования данных с дальномера в [PX4 должен быть сконфигурирован](parameters.md).
|
||||
|
||||
При использовании EKF2 (`SYS_MC_EST_GROUP` = `ekf2`):
|
||||
|
||||
|
||||
@@ -29,7 +29,7 @@ MAVLink-сообщение это отдельная "порция" данных
|
||||
* `GLOBAL_POSITION_INT` – глобальная позиция квадрокоптера (широта/долгота/высота);
|
||||
* `COMMAND_LONG` – команда для квадрокоптера (взлететь, сесть, переключить режим и т. д.).
|
||||
|
||||
Полный список MAVLink-сообщений можно посмотреть в [документации MAVLink](http://mavlink.org/messages/common).
|
||||
Полный список MAVLink-сообщений можно посмотреть в [документации MAVLink](https://mavlink.io/en/messages/common.html).
|
||||
|
||||
### Система, компонент системы
|
||||
|
||||
|
||||
@@ -1,20 +1,64 @@
|
||||
# Параметры PX4
|
||||
|
||||
Основная статья: https://dev.px4.io/en/advanced/parameter_reference.html
|
||||
Полная документация по параметрам PX4: https://docs.px4.io/master/en/advanced_config/parameter_reference.html.
|
||||
|
||||
> **Note** Это описание некоторых, наиболее важных параметров PX4 по состоянию на версию 1.8.0. Полный список см. по ссылке выше.
|
||||
Для изменения параметров PX4 используйте программу QGroundControl, [подключившись к Клеверу по Wi-Fi](gcs_bridge.md) или USB. Перейдите в панель *Vehicle Setup* (кликнув на логотип QGroundControl в левом верхнем углу и выберите меню *Parameters*.
|
||||
|
||||
Для изменения параметров PX4 можно воспользоваться программой QGroundControl, [подключившись к Клеверу по Wi-Fi](gcs_bridge.md):
|
||||
## Рекомендованные значения
|
||||
|
||||

|
||||
### Общие параметры
|
||||
|
||||
## Основные параметры
|
||||
|Параметр|Значение|Примечание|
|
||||
|-|-|-|
|
||||
|`SENS_FLOW_ROT`|0 (*No rotation*)|В случае использования "железного" [PX4Flow](px4flow.md), оставьте значение по умолчанию|
|
||||
|`SENS_FLOW_MINHGT`|0.01|Для [дальномера VL53L1X](laser.md)|
|
||||
|`SENS_FLOW_MAXHGT`|4.0|Для [дальномера VL53L1X](laser.md)|
|
||||
|`SENS_FLOW_MAXR`|10.0||
|
||||
|`SYS_HAS_MAG`|0|При невозможности запуска магнитометра (ошибка *No mags found*)|
|
||||
|
||||
Наиболее важные параметры вынесены в этот параграф.
|
||||
### Настройки подсистемы Estimator
|
||||
|
||||
`SYS_MC_EST_GROUP` – выбор модуля estimator'а.
|
||||
В случае использования LPE ([прошивка COEX](firmware.md)):
|
||||
|
||||
Это группа модулей, которая вычисляет текущее состояние (state) коптера, используя показания с датчиков. В состояние коптера входит:
|
||||
|Параметр|Значение|Примечание|
|
||||
|-|-|-|
|
||||
|`LPE_FUSION`|86|Чекбоксы: *flow* + *vis* + *land Detector* + *gyro comp*. При полете над ровным полом возможно включение *pub agl as lpos down*. <br>Подробнее: [Optical Flow](optical_flow.md), [ArUco-маркеры](aruco_map.md), [GPS](gps.md).|
|
||||
|`LPE_VIS_DELAY`|0.0||
|
||||
|`LPE_VIS_Z`|0.1||
|
||||
|`LPE_FLW_SCALE`|1.0||
|
||||
|`LPE_FLW_R`|0.2||
|
||||
|`LPE_FLW_RR`|0.0||
|
||||
|`LPE_FLW_QMIN`|10||
|
||||
|`ATT_W_EXT_HDG`|0.5|Включение использования внешнего угла по рысканью (при навигации по [карте маркеров](aruco_map.md))|
|
||||
|`ATT_EXT_HDG_M`|1 (*Vision*)||
|
||||
|`ATT_W_MAG`|0|Выключение магнитометра (при навигации внутри помещения)|
|
||||
|
||||
В случае использования EKF2 (официальная прошивка):
|
||||
|
||||
<!-- markdownlint-disable MD044 -->
|
||||
|
||||
|Параметр|Значение|Примечание|
|
||||
|-|-|-|
|
||||
|`EKF2_AID_MASK`|27|Чекбоксы: (опционально) *gps* + *flow* + *vision position* + *vision yaw*.<br>Подробнее: [Optical Flow](optical_flow.md), [ArUco-маркеры](aruco_map.md), [GPS](gps.md).|
|
||||
|`EKF2_OF_DELAY`|0||
|
||||
|`EKF2_OF_QMIN`|10||
|
||||
|`EKF2_OF_N_MIN`|0.05||
|
||||
|`EKF2_OF_N_MAX`|0.2||
|
||||
|`EKF2_HGT_MODE`|2 (*Range sensor*)|При наличии [дальномера](laser.md) и полете над ровным полом|
|
||||
|`EKF2_EVA_NOISE`|0.1||
|
||||
|`EKF2_EVP_NOISE`|0.1||
|
||||
|`EKF2_EV_DELAY`|0||
|
||||
|`EKF2_MAG_TYPE`|5 (*None*)|Выключение магнитометра (при навигации внутри помещения)|
|
||||
|
||||
<!-- markdownlint-enable MD031 -->
|
||||
|
||||
> **Info** См. также: список параметров по умолчанию в [симуляторе](simulation.md): https://github.com/CopterExpress/clover/blob/master/clover_simulation/airframes/4500_clover.
|
||||
|
||||
## Дополнительная информация
|
||||
|
||||
Параметр `SYS_MC_EST_GROUP` отвечает за выбор Estimator'а.
|
||||
|
||||
Estimator это подсистема, которая вычисляет текущее состояние (state) коптера, используя показания с датчиков. В состояние коптера входит:
|
||||
|
||||
* угловая скорость коптера – pitch_rate, roll_rate, yaw_rate;
|
||||
* ориентация коптера (в локальной системе координат) – pitch (тангаж), roll (крен), yaw (рысканье) (одно из представлений);
|
||||
@@ -57,9 +101,7 @@
|
||||
|
||||
## LPE + Q attitude estimator
|
||||
|
||||
Данные параметры настраивают поведение модулей `lpe` и `q`, которые вычисляют состояние (ориентацию, позицию) коптера. Эти параметры применяются **только** если параметр `SYS_MC_EST_GROUP` установлен в значение `1` (local_position_estimator, attitude_estimator_q)
|
||||
|
||||
TODO
|
||||
Данные параметры настраивают поведение модулей `lpe` и `q`, которые вычисляют состояние (ориентацию, позицию) коптера. Эти параметры применяются **только** если параметр `SYS_MC_EST_GROUP` установлен в значение `1` (local_position_estimator, attitude_estimator_q).
|
||||
|
||||
## Commander
|
||||
|
||||
@@ -68,5 +110,3 @@ TODO
|
||||
## Sensors
|
||||
|
||||
Включение, выключение и настройка различных датчиков.
|
||||
|
||||
TODO
|
||||
@@ -2,7 +2,7 @@
|
||||
|
||||
<img src="../assets/programming.png" width=250 align=right>
|
||||
|
||||
Платформа Клевера позволяет использовать [Raspberry Pi](raspberry.md) для того, чтобы запрограммировать автономный полет дрона. Чаще всего программа для автономного полета пишется на языке Python. Программа может [получать телеметрию](simple_offboard.md#get_telemetry) (заряд батареи, ориентацию, расположение и т. д.) и отправлять команды: [полететь в точку](simple_offboard.md#navigate), [установить ориентацию](simple_offboard.md#set_attitude), [угловую скорость](simple_offboard.md#set_rates) и т. д.
|
||||
Платформа Клевера позволяет использовать [Raspberry Pi](raspberry.md) для того, чтобы запрограммировать автономный полет дрона. Чаще всего программа для автономного полета пишется на языке Python. Программа может [получать телеметрию](simple_offboard.md#get_telemetry) (заряд батареи, ориентацию, положение, скорости) и отправлять команды, например: [полететь в точку](simple_offboard.md#navigate), [установить ориентацию](simple_offboard.md#set_attitude), [установить угловую скорость](simple_offboard.md#set_rates).
|
||||
|
||||
Платформа основывается на [фреймворке ROS](ros.md), который обеспечивает связь между пользовательской программой и сервисами Клевера, которые запущены в фоне в виде systemd-демона `clover`. Для связи с полетным контроллером используется пакет [MAVROS](mavros.md).
|
||||
|
||||
@@ -10,7 +10,7 @@
|
||||
|
||||
## Система позиционирования {#positioning}
|
||||
|
||||
Для того, чтобы дрон мог зависать на месте или летать между точками, необходимо использование системы позиционирования. Такая система должна вычислять и сообщать дрону, где он находится. Клевер предполагает использование нескольких систем позиционирования: [optical flow](optical_flow.md) (используется [камера](camera.md) и [лазерный дальномер](laser.md)), [визуальные маркеры](aruco.md) (используется камера и маркеры, наклеенные на пол или потолок), GPS и других.
|
||||
Для того, чтобы дрон мог зависать на месте или летать между точками, необходимо использование системы позиционирования. Такая система вычисляет и сообщает дрону, где он находится. Клевер предполагает использование нескольких систем позиционирования: [optical flow](optical_flow.md) (используется [камера](camera.md) и [лазерный дальномер](laser.md)), [визуальные маркеры](aruco.md) (используется камера и маркеры, наклеенные на пол или потолок), GPS и других.
|
||||
|
||||
### Optical flow
|
||||
|
||||
@@ -32,7 +32,7 @@
|
||||
|
||||
## Автономный полет {#flight}
|
||||
|
||||
> **Info** Для изучения языка программирования Python вы можете обратиться к [самоучителю](https://pythonworld.ru/samouchitel-python).
|
||||
> **Info** Для изучения языка программирования Python можно обратиться к [самоучителю](https://pythonworld.ru/samouchitel-python).
|
||||
|
||||
После настройки системы позиционирования становится возможным написание скриптов для автономных полетов. Для выполнения скриптов [подключитесь в Raspberry Pi по SSH](ssh.md).
|
||||
|
||||
|
||||
@@ -43,7 +43,7 @@ Axis или Grid настроенный на фрейм `aruco_map` будут
|
||||
|
||||
### jsk_rviz_plugins
|
||||
|
||||
Рекомендуется также установка набора дополнительных полезных плагинов для rviz [jsk_rviz_plugins](https://jsk-docs.readthedocs.io/en/latest/jsk_visualization/doc/jsk_rviz_plugins/index.html). Это набор позволяет визуализировать топики типа `TwistStamped` (скорость), `CameraInfo`, `PolygonArray` и многое другое. Для установки используйте команду:
|
||||
Рекомендуется также установка набора дополнительных полезных плагинов для rviz [jsk_rviz_plugins](https://jsk-visualization.readthedocs.io/en/latest/jsk_rviz_plugins/index.html). Это набор позволяет визуализировать топики типа `TwistStamped` (скорость), `CameraInfo`, `PolygonArray` и многое другое. Для установки используйте команду:
|
||||
|
||||
```bash
|
||||
sudo apt-get install ros-melodic-jsk-visualization
|
||||
|
||||
@@ -23,9 +23,9 @@
|
||||
|
||||
## Загрузка прошивки в полетный контроллер
|
||||
|
||||
Для использования всех наиболее актуальных функций PX4 используйте последнюю версию прошивки PX4 (*1.12+*).
|
||||
Наиболее оттестированной, в особенности для осуществления автономных полетов, является [версия прошивки с патчами COEX](firmware.md). Скачайте актуальную версию прошивки на GitHub — **<a class="latest-firmware v4" href="https://github.com/CopterExpress/Firmware/releases">скачать</a>**.
|
||||
|
||||
> **Note** Альтернативой является использование более старой прошивки (*1.8.2*) [с патчами COEX](firmware.md). В этой прошивке функциональность автономных полетов является более оттестированной и отлаженной. Прошивка может быть скачана с GitHub — **<a class="latest-firmware v4" href="https://github.com/CopterExpress/Firmware/releases">Скачать</a>**.
|
||||
Для использования всех наиболее актуальных функций PX4 вы также можете использовать последнюю официальную версию прошивки (в экспериментальном режиме).
|
||||
|
||||
1. Отключите полетный контроллер от компьютера (если он подключен).
|
||||
2. Запустите программу QGroundControl.
|
||||
@@ -33,15 +33,15 @@
|
||||
4. Подключите полетный контроллер к компьютеру по USB.
|
||||
5. Выберите в появившемся меню справа *PX4 Flight Stack*.
|
||||
|
||||
<img src="../assets/qgc-firmware.png" alt="QGroundControl firmware upload" class="zoom">
|
||||
<img src="../assets/qgc-firmware.png" alt="QGroundControl firmware upload" class="zoom">
|
||||
|
||||
Для загрузки прошивки COEX:
|
||||
6. Для загрузки **прошивки COEX**:
|
||||
|
||||
* Выберите *Advanced settings*.
|
||||
* В выпадающем меню выберите *Custom firmware file...*
|
||||
* Нажмите *OK* и выберите скаченный файл прошивки.
|
||||
* Выберите *Advanced settings*.
|
||||
* В выпадающем меню выберите *Custom firmware file...*
|
||||
* Нажмите *OK* и выберите скаченный файл прошивки.
|
||||
|
||||
Для загрузки последней версии стандартной прошивки сразу нажмите *OK*.
|
||||
Для загрузки последней версии **стандартной прошивки** сразу нажмите *OK*.
|
||||
|
||||
Дождитесь, пока QGroundControl загрузит прошивку и выполнит перезагрузку полетного контроллера.
|
||||
|
||||
@@ -75,7 +75,7 @@
|
||||
|
||||
### Параметры
|
||||
|
||||
Для настройки параметров полетного контроллера войдите во вкладку *Vehicle Setup* и выберите меню *Parameters*. Вы можете использовать поле *Search* для поиска параметров по имени.
|
||||
Для настройки параметров полетного контроллера войдите во вкладку *Vehicle Setup* и выберите меню *Parameters*. Вы можете использовать поле *Search* для поиска параметров по имени. Рекомендуемые параметры для Клевера приведены в дальнейшей документации а также в соответствующей [сводной статье](parameters.md).
|
||||
|
||||
<img src="../assets/qgc-parameters.png" alt="QGroundControl parameters" class="zoom">
|
||||
|
||||
|
||||
@@ -1,11 +1,4 @@
|
||||
Автономный полет (OFFBOARD)
|
||||
===
|
||||
|
||||
> **Note** В версии образа **0.20** пакет `clever` был переименован в `clover`. Для более ранних версий см. документацию для версии [**0.19**](https://github.com/CopterExpress/clover/blob/v0.19/docs/ru/simple_offboard.md).
|
||||
|
||||
<!-- -->
|
||||
|
||||
> **Hint** Для автономных полетов рекомендуется использование [специальной сборки PX4 для Клевера](firmware.md#прошивка-для-клевера).
|
||||
# Автономный полет
|
||||
|
||||
Модуль `simple_offboard` пакета `clover` предназначен для упрощенного программирования автономного полета дрона ([режим](modes.md) `OFFBOARD`). Он позволяет устанавливать желаемые полетные задачи и автоматически трансформирует [систему координат](frames.md).
|
||||
|
||||
@@ -13,8 +6,7 @@
|
||||
|
||||
Основные сервисы – [`get_telemetry`](#gettelemetry) (получение телеметрии), [`navigate`](#navigate) (полет в заданную точку по прямой), [`navigate_global`](#navigateglobal) (полет в глобальную точку по прямой), [`land`](#land) (переход в режим посадки).
|
||||
|
||||
Использование из языка Python
|
||||
---
|
||||
## Использование из языка Python
|
||||
|
||||
Для использования сервисов, необходимо создать объекты-прокси к ним. Используйте этот шаблон для вашей программы:
|
||||
|
||||
@@ -37,8 +29,7 @@ land = rospy.ServiceProxy('land', Trigger)
|
||||
|
||||
Неиспользуемые функции-прокси можно удалить из кода.
|
||||
|
||||
Описание API
|
||||
---
|
||||
## Описание API
|
||||
|
||||
> **Note** Незаполненные числовые параметры устанавливаются в значение 0.
|
||||
|
||||
@@ -295,7 +286,7 @@ set_velocity(vx=1, vy=0.0, vz=0, frame_id='body')
|
||||
|
||||
Перевести коптер в [режим](modes.md) посадки (`AUTO.LAND` или аналогичный).
|
||||
|
||||
> **Note** Для автоматического отключения винтов после посадки [параметр PX4](px4_parameters.md) `COM_DISARM_LAND` должен быть установлен в значение > 0.
|
||||
> **Note** Для автоматического отключения винтов после посадки [параметр PX4](parameters.md) `COM_DISARM_LAND` должен быть установлен в значение > 0.
|
||||
|
||||
Посадка коптера:
|
||||
|
||||
@@ -312,14 +303,9 @@ if res.success:
|
||||
rosservice call /land "{}"
|
||||
```
|
||||
|
||||
<!--
|
||||
### release
|
||||
> **Caution** В более новых версиях PX4 коптер выйдет из режима LAND в ручной режим, если сильно перемещать стики.
|
||||
|
||||
Перестать публиковать setpoint'ы коптеру (отпустить управление). Необходим для продолжения контроля средствами [MAVROS](mavros.md).
|
||||
-->
|
||||
|
||||
Дополнительные материалы
|
||||
------------------------
|
||||
## Дополнительные материалы
|
||||
|
||||
* [Полеты в поле ArUco-маркеров](aruco.md).
|
||||
* [Примеры программ и сниппеты](snippets.md).
|
||||
|
||||
@@ -77,7 +77,7 @@ GPS датчик необходим полетов с использование
|
||||
|
||||
### Выставление скорости симуляции
|
||||
|
||||
PX4, начиная с версии 1.9, поддерживает [принудительную установку скорости симуляции](https://dev.px4.io/v1.9.0/en/simulation/#simulation_speed) с помощью переменной окружения `PX4_SIM_SPEED_FACTOR`. Выставление этой переменной подготавливает все компоненты симулятора к соответствующему ускорению/замедлению.
|
||||
PX4, начиная с версии 1.9, поддерживает [принудительную установку скорости симуляции](https://docs.px4.io/master/en/simulation/#run-simulation-faster-than-realtime) с помощью переменной окружения `PX4_SIM_SPEED_FACTOR`. Выставление этой переменной подготавливает все компоненты симулятора к соответствующему ускорению/замедлению.
|
||||
|
||||
Значение этой переменной должно соответствовать величине Real Time Factor (скорости симуляции по отношению к реальному времени), получаемой при использовании `throttling_camera`. Величина Real Time Factor отображается в окне Gazebo на нижней панели:
|
||||
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
|
||||
Основная статья: https://dev.px4.io/en/simulation/
|
||||
|
||||
Симуляция PX4 возможна в ОС GNU/Linux и macOS с использованием систем симуляции физической среды [jMAVSim](https://pixhawk.org/dev/hil/jmavsim) и [Gazebo](http://gazebosim.org).
|
||||
Симуляция PX4 возможна в ОС GNU/Linux и macOS с использованием систем симуляции физической среды [jMAVSim](https://docs.px4.io/master/en/simulation/jmavsim.html) и [Gazebo](http://gazebosim.org).
|
||||
|
||||
jMAVSim является легковесной средой, предназначенной только для тестирование мультироторных летательных систем; Gazebo – универсальная среда для любых типов роботов.
|
||||
|
||||
|
||||
@@ -14,7 +14,7 @@
|
||||
* Пакеты [ROS](http://www.ros.org/), требуемые для запуска нод Клевера
|
||||
* Собранный для симулятора PX4
|
||||
* Легковесный web-интерфейс для Gazebo [Gzweb](http://gazebosim.org/gzweb.html)
|
||||
* Web-терминал [Butterfly](http://paradoxxxzero.github.io/2014/02/28/butterfly.html)
|
||||
* Web-терминал [Butterfly](https://github.com/paradoxxxzero/butterfly)
|
||||
|
||||
## Предварительная настройка
|
||||
|
||||
|
||||
@@ -17,13 +17,11 @@
|
||||
|
||||
<a name="block-takeoff"></a><!-- old name of anchor -->
|
||||
|
||||
Полет в точку и ожидание окончания полета:
|
||||
Функция для полета в точку и ожидание окончания полета:
|
||||
|
||||
```python
|
||||
import math
|
||||
|
||||
# ...
|
||||
|
||||
def navigate_wait(x=0, y=0, z=0, yaw=float('nan'), speed=0.5, frame_id='', auto_arm=False, tolerance=0.2):
|
||||
navigate(x=x, y=y, z=z, yaw=yaw, speed=speed, frame_id=frame_id, auto_arm=auto_arm)
|
||||
|
||||
@@ -74,8 +72,6 @@ land_wait()
|
||||
```python
|
||||
import math
|
||||
|
||||
# ...
|
||||
|
||||
def wait_arrival(tolerance=0.2):
|
||||
while not rospy.is_shutdown():
|
||||
telem = get_telemetry(frame_id='navigate_target')
|
||||
@@ -91,8 +87,6 @@ def wait_arrival(tolerance=0.2):
|
||||
```python
|
||||
import math
|
||||
|
||||
# ...
|
||||
|
||||
def get_distance(x1, y1, z1, x2, y2, z2):
|
||||
return math.sqrt((x1 - x2) ** 2 + (y1 - y2) ** 2 + (z1 - z2) ** 2)
|
||||
```
|
||||
@@ -104,8 +98,6 @@ def get_distance(x1, y1, z1, x2, y2, z2):
|
||||
```python
|
||||
import math
|
||||
|
||||
# ...
|
||||
|
||||
def get_distance_global(lat1, lon1, lat2, lon2):
|
||||
return math.hypot(lat1 - lat2, lon1 - lon2) * 1.113195e5
|
||||
```
|
||||
@@ -221,19 +213,16 @@ from geometry_msgs.msg import PoseStamped, TwistStamped
|
||||
from sensor_msgs.msg import BatteryState
|
||||
from mavros_msgs.msg import RCIn
|
||||
|
||||
# ...
|
||||
|
||||
def pose_update(pose):
|
||||
# Обработка новых данных о позиции коптера
|
||||
pass
|
||||
|
||||
# Остальные функции-обработчики
|
||||
# ...
|
||||
|
||||
rospy.Subscriber('/mavros/local_position/pose', PoseStamped, pose_update)
|
||||
rospy.Subscriber('/mavros/local_position/velocity', TwistStamped, velocity_update)
|
||||
rospy.Subscriber('/mavros/battery', BatteryState, battery_update)
|
||||
rospy.Subscriber('mavros/rc/in', RCIn, rc_callback)
|
||||
|
||||
rospy.spin()
|
||||
```
|
||||
|
||||
Информацию по топикам MAVROS см. по [ссылке](mavros.md).
|
||||
@@ -247,14 +236,10 @@ rospy.Subscriber('mavros/rc/in', RCIn, rc_callback)
|
||||
Пример отправки произвольного [MAVLink-сообщения](mavlink.md) коптеру:
|
||||
|
||||
```python
|
||||
# ...
|
||||
|
||||
from mavros_msgs.msg import Mavlink
|
||||
from mavros import mavlink
|
||||
from pymavlink import mavutil
|
||||
|
||||
# ...
|
||||
|
||||
mavlink_pub = rospy.Publisher('mavlink/to', Mavlink, queue_size=1)
|
||||
|
||||
# Отправка сообщения HEARTBEAT:
|
||||
@@ -299,8 +284,6 @@ rospy.spin()
|
||||
```python
|
||||
from mavros_msgs.srv import SetMode
|
||||
|
||||
# ...
|
||||
|
||||
set_mode = rospy.ServiceProxy('mavros/set_mode', SetMode)
|
||||
|
||||
# ...
|
||||
@@ -315,8 +298,6 @@ set_mode(custom_mode='STABILIZED')
|
||||
```python
|
||||
import math
|
||||
|
||||
# ...
|
||||
|
||||
PI_2 = math.pi / 2
|
||||
|
||||
def flip():
|
||||
@@ -355,8 +336,6 @@ from pymavlink import mavutil
|
||||
from mavros_msgs.srv import CommandLong
|
||||
from mavros_msgs.msg import State
|
||||
|
||||
# ...
|
||||
|
||||
send_command = rospy.ServiceProxy('/mavros/cmd/command', CommandLong)
|
||||
|
||||
def calibrate_gyro():
|
||||
@@ -390,16 +369,14 @@ calibrate_gyro()
|
||||
import rospy
|
||||
import dynamic_reconfigure.client
|
||||
|
||||
# ...
|
||||
|
||||
client = dynamic_reconfigure.client.Client('aruco_detect')
|
||||
|
||||
# Turn markers recognition off
|
||||
# Включить распознавание маркеров
|
||||
client.update_configuration({'enabled': False})
|
||||
|
||||
rospy.sleep(5)
|
||||
|
||||
# Turn markers recognition on
|
||||
# Выключить распознавание маркеров
|
||||
client.update_configuration({'enabled': True})
|
||||
```
|
||||
|
||||
@@ -410,8 +387,6 @@ client.update_configuration({'enabled': True})
|
||||
```python
|
||||
import math
|
||||
|
||||
# ...
|
||||
|
||||
while not rospy.is_shutdown():
|
||||
if math.isfinite(get_telemetry().lat):
|
||||
break
|
||||
@@ -426,12 +401,8 @@ while not rospy.is_shutdown():
|
||||
from mavros_msgs.srv import ParamGet
|
||||
from mavros_msgs.msg import ParamValue
|
||||
|
||||
# ...
|
||||
|
||||
param_get = rospy.ServiceProxy('mavros/param/get', ParamGet)
|
||||
|
||||
# ...
|
||||
|
||||
# Считать параметр типа INT
|
||||
value = param_get(param_id='COM_FLTMODE1').value.integer
|
||||
|
||||
@@ -447,12 +418,8 @@ value = param_get(param_id='MPC_Z_P').value.float
|
||||
from mavros_msgs.srv import ParamSet
|
||||
from mavros_msgs.msg import ParamValue
|
||||
|
||||
# ...
|
||||
|
||||
param_set = rospy.ServiceProxy('mavros/param/set', ParamSet)
|
||||
|
||||
# ...
|
||||
|
||||
# Изменить параметр типа INT:
|
||||
param_set(param_id='COM_FLTMODE1', value=ParamValue(integer=8))
|
||||
|
||||
|
||||
@@ -66,6 +66,8 @@
|
||||
{ "from": "gpio/", "to": "en/gpio.html" },
|
||||
|
||||
{ "from": "ru/microsd_images.html", "to": "image.html" },
|
||||
{ "from": "en/microsd_images.html", "to": "image.html" }
|
||||
{ "from": "en/microsd_images.html", "to": "image.html" },
|
||||
{ "from": "ru/px4_parameters.html", "to": "parameters.html" },
|
||||
{ "from": "en/px4_parameters.html", "to": "parameters.html" }
|
||||
]
|
||||
}
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>roswww_static</name>
|
||||
<version>0.21.1</version>
|
||||
<version>0.23.0</version>
|
||||
<description>Static web pages for ROS packages</description>
|
||||
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>
|
||||
<license>MIT</license>
|
||||
|
||||
Reference in New Issue
Block a user