Compare commits

..

1 Commits

Author SHA1 Message Date
Oleg Kalachev
a72bf9cbad Add tests for pigpio 2021-11-22 17:45:39 +03:00
92 changed files with 428 additions and 976 deletions

View File

@@ -7,13 +7,13 @@ on:
branches: [ master ] branches: [ master ]
jobs: jobs:
# melodic: melodic:
# runs-on: ubuntu-latest runs-on: ubuntu-latest
# steps: steps:
# - uses: actions/checkout@v2 - uses: actions/checkout@v2
# - name: Native Melodic build - name: Native Melodic build
# run: | run: |
# docker run --rm -v $(pwd):/root/catkin_ws/src/clover ros:melodic-ros-base /root/catkin_ws/src/clover/builder/standalone-install.sh docker run --rm -v $(pwd):/root/catkin_ws/src/clover ros:melodic-ros-base /root/catkin_ws/src/clover/builder/standalone-install.sh
noetic: noetic:
runs-on: ubuntu-latest runs-on: ubuntu-latest
steps: steps:

View File

@@ -10,10 +10,6 @@ jobs:
docs: docs:
runs-on: ubuntu-18.04 runs-on: ubuntu-18.04
steps: steps:
- name: Cancel previous runs
uses: styfle/cancel-workflow-action@0.9.1
with:
access_token: ${{ github.token }}
- uses: actions/checkout@v2 - uses: actions/checkout@v2
- name: Use Node.js - name: Use Node.js
uses: actions/setup-node@v1 uses: actions/setup-node@v1

View File

@@ -1,7 +1,7 @@
<?xml version="1.0"?> <?xml version="1.0"?>
<package format="2"> <package format="2">
<name>aruco_pose</name> <name>aruco_pose</name>
<version>0.23.0</version> <version>0.21.1</version>
<description>Positioning with ArUco markers</description> <description>Positioning with ArUco markers</description>
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer> <maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>

View File

@@ -30,7 +30,7 @@ Options:
-o <filename> Output map file name in the 'map' subdirectory of aruco_pose package -o <filename> Output map file name in the 'map' subdirectory of aruco_pose package
Example: Example:
rosrun aruco_pose genmap.py 0.33 2 4 1 1 0 -o test_map.txt rosrun aruco_pose genmap.py 0.33 2 4 1 1 0 > $(catkin_find aruco_pose map)/test_map.txt
""" """
from __future__ import print_function from __future__ import print_function

View File

@@ -90,7 +90,7 @@ echo_stamp "Installing OpenCV 4.2-compatible ROS packages"
apt install -y --no-install-recommends \ apt install -y --no-install-recommends \
ros-${ROS_DISTRO}-compressed-image-transport=1.14.0-0buster \ ros-${ROS_DISTRO}-compressed-image-transport=1.14.0-0buster \
ros-${ROS_DISTRO}-cv-bridge=1.15.0-0buster \ ros-${ROS_DISTRO}-cv-bridge=1.15.0-0buster \
ros-${ROS_DISTRO}-cv-camera=0.5.1-0buster \ ros-${ROS_DISTRO}-cv-camera=0.5.0-0buster \
ros-${ROS_DISTRO}-image-publisher=1.15.3-0buster \ ros-${ROS_DISTRO}-image-publisher=1.15.3-0buster \
ros-${ROS_DISTRO}-web-video-server=0.2.1-0buster ros-${ROS_DISTRO}-web-video-server=0.2.1-0buster
apt-mark hold \ apt-mark hold \
@@ -112,7 +112,7 @@ my_travis_retry pip3 install wheel
my_travis_retry pip3 install -r /home/pi/catkin_ws/src/clover/clover/requirements.txt my_travis_retry pip3 install -r /home/pi/catkin_ws/src/clover/clover/requirements.txt
source /opt/ros/${ROS_DISTRO}/setup.bash source /opt/ros/${ROS_DISTRO}/setup.bash
# Don't build simulation plugins for actual drone # Don't build simulation plugins for actual drone
catkin_make -j2 -DCMAKE_BUILD_TYPE=RelWithDebInfo catkin_make -j2 -DCMAKE_BUILD_TYPE=RelWithDebInfo -DCATKIN_BLACKLIST_PACKAGES=clover_gazebo_plugins
source devel/setup.bash source devel/setup.bash
echo_stamp "Install clever package (for backwards compatibility)" echo_stamp "Install clever package (for backwards compatibility)"

View File

@@ -138,7 +138,6 @@ echo_stamp "Install and enable Butterfly (web terminal)"
echo_stamp "Workaround for tornado >= 6.0 breaking butterfly" echo_stamp "Workaround for tornado >= 6.0 breaking butterfly"
export CRYPTOGRAPHY_DONT_BUILD_RUST=1 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 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 tornado==5.1.1
my_travis_retry pip3 install butterfly my_travis_retry pip3 install butterfly
my_travis_retry pip3 install butterfly[systemd] my_travis_retry pip3 install butterfly[systemd]

View File

@@ -26,6 +26,7 @@ cd /home/pi/catkin_ws/src/clover/builder/test/
./tests.sh ./tests.sh
./tests.py ./tests.py
./tests_py3.py ./tests_py3.py
./test_pigpio.py
[[ $(./test_qr.py) == "Found QRCODE with data Проверка Unicode with center at x=66.0, y=66.0" ]] [[ $(./test_qr.py) == "Found QRCODE with data Проверка Unicode with center at x=66.0, y=66.0" ]]
[[ $(./tests_clever.py) == "Warning: clever package is renamed to clover" ]] # test backwards compatibility [[ $(./tests_clever.py) == "Warning: clever package is renamed to clover" ]] # test backwards compatibility

View File

@@ -0,0 +1,6 @@
#!/usr/bin/env python3
import pigpio
pi = pigpio.pi()
pi.set_mode(24, pigpio.OUTPUT)
pi.write(24, True)

View File

@@ -58,9 +58,5 @@ rosversion rosshow
rosversion nodelet rosversion nodelet
rosversion image_view 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 # validate examples are present
[[ $(ls /home/pi/examples/*) ]] [[ $(ls /home/pi/examples/*) ]]

View File

@@ -8,11 +8,8 @@
<!-- For additional help go to https://clover.coex.tech/aruco --> <!-- 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 --> <!-- aruco_detect: detect aruco markers, estimate poses -->
<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"> <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">
<remap from="image_raw" to="main_camera/image_raw"/> <remap from="image_raw" to="main_camera/image_raw"/>
<remap from="camera_info" to="main_camera/camera_info"/> <remap from="camera_info" to="main_camera/camera_info"/>
<remap from="map_markers" to="aruco_map/markers"/> <remap from="map_markers" to="aruco_map/markers"/>
@@ -29,7 +26,7 @@
</node> </node>
<!-- aruco_map: estimate aruco map pose --> <!-- aruco_map: estimate aruco map pose -->
<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"> <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">
<remap from="image_raw" to="main_camera/image_raw"/> <remap from="image_raw" to="main_camera/image_raw"/>
<remap from="camera_info" to="main_camera/camera_info"/> <remap from="camera_info" to="main_camera/camera_info"/>
<remap from="markers" to="aruco_detect/markers"/> <remap from="markers" to="aruco_detect/markers"/>
@@ -44,11 +41,11 @@
</node> </node>
<!-- vpe publisher from aruco markers --> <!-- vpe publisher from aruco markers -->
<node name="vpe_publisher" pkg="clover" type="vpe_publisher" if="$(eval aruco_vpe or force_init)" output="screen" clear_params="true"> <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" if="$(arg aruco_vpe)"/> <remap from="~pose_cov" to="aruco_map/pose"/>
<remap from="~vpe" to="mavros/vision_pose/pose"/> <remap from="~vpe" to="mavros/vision_pose/pose"/>
<param name="frame_id" value="aruco_map_detected" if="$(arg aruco_vpe)"/> <param name="frame_id" value="aruco_map_detected"/>
<param name="force_init" value="$(arg force_init)"/> <param name="publish_zero" value="true"/>
<param name="offset_frame_id" value="aruco_map"/> <param name="offset_frame_id" value="aruco_map"/>
</node> </node>
</launch> </launch>

View File

@@ -12,7 +12,6 @@
<arg name="led" default="true"/> <arg name="led" default="true"/>
<arg name="blocks" default="false"/> <arg name="blocks" default="false"/>
<arg name="rc" 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 --> <arg name="simulator" default="false"/> <!-- flag that we are operating on a simulated drone -->
@@ -34,10 +33,7 @@
</node> </node>
<!-- aruco markers --> <!-- aruco markers -->
<include file="$(find clover)/launch/aruco.launch" if="$(eval aruco or force_init)"> <include file="$(find clover)/launch/aruco.launch" if="$(arg aruco)"/>
<arg name="force_init" value="$(arg force_init)"/>
<arg name="disable" value="$(eval not aruco)"/>
</include>
<!-- optical flow --> <!-- 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"> <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">
@@ -51,6 +47,9 @@
<!-- simplified offboard control --> <!-- simplified offboard control -->
<node name="simple_offboard" pkg="clover" type="simple_offboard" output="screen" clear_params="true"> <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"/> <param name="reference_frames/main_camera_optical" value="map"/>
</node> </node>

View File

@@ -1,11 +1,11 @@
# Config file for mavros # Config file for mavros
# Based on https://raw.githubusercontent.com/mavlink/mavros/master/mavros/launch/px4_config.yaml # Based on https://raw.githubusercontent.com/mavlink/mavros/master/mavros/launch/px4_config.yaml
startup_px4_usb_quirk: false startup_px4_usb_quirk: true
conn: conn:
heartbeat_rate: 1.0 # send heartbeat rate in Hertz heartbeat_rate: 1.0 # send hertbeat rate in Hertz
timeout: 10.0 # heartbeat timeout in seconds timeout: 10.0 # hertbeat timeout in seconds
timesync_rate: 10.0 # TIMESYNC rate in Hertz (feature disabled if 0.0) 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) system_time_rate: 1.0 # send system time to FCU rate in Hertz (disabled if 0.0)
@@ -13,7 +13,6 @@ time:
time_ref_source: "fcu" # time_reference source time_ref_source: "fcu" # time_reference source
timesync_mode: MAVLINK timesync_mode: MAVLINK
timesync_avg_alpha: 0.6 # timesync averaging factor timesync_avg_alpha: 0.6 # timesync averaging factor
publish_sim_time: false # don't publish /clock
global_position: global_position:
frame_id: "map" # origin frame frame_id: "map" # origin frame

View File

@@ -1,7 +1,7 @@
<?xml version="1.0"?> <?xml version="1.0"?>
<package format="3"> <package format="3">
<name>clover</name> <name>clover</name>
<version>0.23.0</version> <version>0.21.1</version>
<description>The Clover package</description> <description>The Clover package</description>
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer> <maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>

View File

@@ -53,7 +53,6 @@ private:
std::unique_ptr<tf2_ros::Buffer> tf_buffer_; std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
std::unique_ptr<tf2_ros::TransformListener> tf_listener_; std::unique_ptr<tf2_ros::TransformListener> tf_listener_;
bool calc_flow_gyro_; bool calc_flow_gyro_;
float flow_gyro_default_;
void onInit() void onInit()
{ {
@@ -70,7 +69,6 @@ private:
roi_px_ = nh_priv.param("roi", 128); roi_px_ = nh_priv.param("roi", 128);
roi_rad_ = nh_priv.param("roi_rad", 0.0); roi_rad_ = nh_priv.param("roi_rad", 0.0);
calc_flow_gyro_ = nh_priv.param("calc_flow_gyro", false); calc_flow_gyro_ = nh_priv.param("calc_flow_gyro", false);
flow_gyro_default_ = nh_priv.param("flow_gyro_default", NAN);
img_pub_ = it_priv.advertise("debug", 1); img_pub_ = it_priv.advertise("debug", 1);
flow_pub_ = nh.advertise<mavros_msgs::OpticalFlowRad>("mavros/px4flow/raw/send", 1); flow_pub_ = nh.advertise<mavros_msgs::OpticalFlowRad>("mavros/px4flow/raw/send", 1);
@@ -196,9 +194,9 @@ private:
uint32_t integration_time_us = integration_time.toSec() * 1.0e6; uint32_t integration_time_us = integration_time.toSec() * 1.0e6;
// Calculate flow gyro // Calculate flow gyro
flow_.integrated_xgyro = flow_gyro_default_; flow_.integrated_xgyro = NAN;
flow_.integrated_ygyro = flow_gyro_default_; flow_.integrated_ygyro = NAN;
flow_.integrated_zgyro = flow_gyro_default_; flow_.integrated_zgyro = NAN;
if (calc_flow_gyro_) { if (calc_flow_gyro_) {
try { try {

View File

@@ -195,27 +195,24 @@ def check_fcu():
failure('no connection to the FCU (check wiring)') failure('no connection to the FCU (check wiring)')
return return
clover_tag = re.compile(r'-cl[oe]ver\.\d+$')
clover_fw = False
# Make sure the console is available to us # Make sure the console is available to us
mavlink_exec('\n') mavlink_exec('\n')
version_str = mavlink_exec('ver all') version_str = mavlink_exec('ver all')
if version_str == '': if version_str == '':
info('no version data available from SITL') info('no version data available from SITL')
for line in version_str.split('\n'): r = re.compile(r'^FW (git tag|version): (v?\d\.\d\.\d.*)$')
if line.startswith('FW version: '): is_clover_firmware = False
info(line[len('FW version: '):]) for ver_line in version_str.split('\n'):
elif line.startswith('FW git tag: '): # only Clover's firmware match = r.search(ver_line)
tag = line[len('FW git tag: '):] if match is not None:
clover_fw = clover_tag.search(tag) field, version = match.groups()
info(tag) info('firmware %s: %s' % (field, version))
elif line.startswith('HW arch: '): if 'clover' in version or 'clever' in version:
info(line[len('HW arch: '):]) is_clover_firmware = True
if not clover_fw: if not is_clover_firmware:
info('not Clover PX4 firmware, check https://clover.coex.tech/firmware') failure('not running Clover PX4 firmware, https://clover.coex.tech/firmware')
est = get_param('SYS_MC_EST_GROUP') est = get_param('SYS_MC_EST_GROUP')
if est == 1: if est == 1:
@@ -488,12 +485,6 @@ def check_local_position():
failure('roll is %.2f deg; place copter horizontally or redo level horizon calib', failure('roll is %.2f deg; place copter horizontally or redo level horizon calib',
math.degrees(roll)) 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: except rospy.ROSException:
failure('no local position') failure('no local position')
@@ -623,7 +614,7 @@ def check_boot_duration():
output = subprocess.check_output('systemd-analyze').decode() output = subprocess.check_output('systemd-analyze').decode()
r = re.compile(r'([\d\.]+)s\s*$', flags=re.MULTILINE) r = re.compile(r'([\d\.]+)s\s*$', flags=re.MULTILINE)
duration = float(r.search(output).groups()[0]) duration = float(r.search(output).groups()[0])
if duration > 20: if duration > 15:
failure('long Raspbian boot duration: %ss (systemd-analyze for analyzing)', duration) failure('long Raspbian boot duration: %ss (systemd-analyze for analyzing)', duration)
@@ -657,22 +648,13 @@ def check_clover_service():
elif 'failed' in output: elif 'failed' in output:
failure('service failed to run, check your launch-files') failure('service failed to run, check your launch-files')
BLACKLIST = 'Unexpected command 520', 'Time jump detected', 'different index:' r = re.compile(r'^(.*)\[(FATAL|ERROR)\] \[\d+.\d+\]: (.*?)(\x1b(.*))?$')
r = re.compile(r'^(.*)\[(FATAL|ERROR| WARN)\] \[\d+.\d+\]: (.*?)(\x1b(.*))?$')
error_count = OrderedDict() error_count = OrderedDict()
try: try:
for line in open('/tmp/clover.err', 'r'): for line in open('/tmp/clover.err', 'r'):
skip = False
for substr in BLACKLIST:
if substr in line:
skip = True
if skip:
continue
node_error = r.search(line) node_error = r.search(line)
if node_error: if node_error:
msg = node_error.groups()[1].strip() + ': ' + node_error.groups()[2] msg = node_error.groups()[1] + ': ' + node_error.groups()[2]
if msg in error_count: if msg in error_count:
error_count[msg] += 1 error_count[msg] += 1
else: else:

View File

@@ -181,7 +181,6 @@ inline bool waitTransform(const string& target, const string& source,
ros::spinOnce(); ros::spinOnce();
r.sleep(); r.sleep();
} }
return false;
} }
#define TIMEOUT(msg, timeout) (msg.header.stamp.isZero() || (ros::Time::now() - msg.header.stamp > timeout)) #define TIMEOUT(msg, timeout) (msg.header.stamp.isZero() || (ros::Time::now() - msg.header.stamp > timeout))
@@ -848,7 +847,6 @@ bool land(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
busy = false; busy = false;
return true; return true;
} }
return false;
} }
int main(int argc, char **argv) int main(int argc, char **argv)
@@ -873,13 +871,6 @@ int main(int argc, char **argv)
nh_priv.param<string>("body_frame", body.child_frame_id, "body"); nh_priv.param<string>("body_frame", body.child_frame_id, "body");
nh_priv.getParam("reference_frames", reference_frames); 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)); state_timeout = ros::Duration(nh_priv.param("state_timeout", 3.0));
local_position_timeout = ros::Duration(nh_priv.param("local_position_timeout", 2.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)); velocity_timeout = ros::Duration(nh_priv.param("velocity_timeout", 2.0));

View File

@@ -141,11 +141,11 @@ int main(int argc, char **argv) {
vpe_pub = nh_priv.advertise<PoseStamped>("vpe", 1); vpe_pub = nh_priv.advertise<PoseStamped>("vpe", 1);
//vpe_cov_pub = nh_priv_.advertise<PoseStamped>("pose_cov_pub", 1); //vpe_cov_pub = nh_priv_.advertise<PoseStamped>("pose_cov_pub", 1);
if (nh_priv.param("force_init", false) || nh_priv.param("publish_zero", false)) { // publish_zero is old name if (nh_priv.param("publish_zero", false)) {
// publish zero to initialize the local position // publish zero to initialize the local position
zero_timer = nh.createTimer(ros::Duration(0.1), &publishZero); zero_timer = nh.createTimer(ros::Duration(0.1), &publishZero);
publish_zero_timout = ros::Duration(nh_priv.param("force_init_timeout", 5.0)); publish_zero_timout = ros::Duration(nh_priv.param("publish_zero_timout", 5.0));
publish_zero_duration = ros::Duration(nh_priv.param("force_init_duration", 5.0)); publish_zero_duration = ros::Duration(nh_priv.param("publish_zero_duration", 5.0));
local_position_sub = nh.subscribe("mavros/local_position/pose", 1, &localPositionCallback); local_position_sub = nh.subscribe("mavros/local_position/pose", 1, &localPositionCallback);
} }

View File

@@ -1,23 +0,0 @@
<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>

View File

@@ -9,7 +9,7 @@
<li><a href="" id="butterfly">Open web terminal</a> (<code>Butterfly</code>)</li> <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>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_blocks/">Blocks programming</a> (<code>Blockly</code>)</li>
<li><a href="console.html">Clover console</a> (<code>/var/log/clover.log</code>)</li> <li><a href="clover.log">Clover console</a> (<code>/var/log/clover.log</code>)</li>
</ul> </ul>
<div class="version"></div> <div class="version"></div>

View File

@@ -1,16 +1,13 @@
const url = 'ws://' + location.hostname + ':9090'; const url = 'ws://' + location.hostname + ':9090';
const ros = new ROSLIB.Ros({ url: url }); const ros = new ROSLIB.Ros({ url: url });
const params = Object.fromEntries(new URLSearchParams(window.location.search).entries());
ros.on('connection', function () { ros.on('connection', function () {
document.body.classList.add('connected'); document.body.classList.add('connected');
document.body.classList.remove('closed');
init(); init();
}); });
ros.on('close', function () { ros.on('close', function () {
document.body.classList.remove('connected'); document.body.classList.remove('connected');
document.body.classList.add('closed');
setTimeout(function() { setTimeout(function() {
// reconnect // reconnect
ros.connect(url); ros.connect(url);
@@ -40,28 +37,18 @@ function viewTopicsList() {
let rosdistro; let rosdistro;
function viewTopic(topic) { function viewTopic(topic) {
let index = '<a href=topics.html>Topics</a>'; title.innerHTML = topic;
title.innerHTML = `${index}: ${topic}`;
topicMessage.style.display = 'block'; topicMessage.style.display = 'block';
ros.getTopicType(topic, function(typeStr) { ros.getTopicType(topic, function(typeStr) {
const [pack, type] = typeStr.split('/'); const [pack, type] = typeStr.split('/');
let href = `https://docs.ros.org/en/${rosdistro}/api/${pack}/html/msg/${type}.html`; let href = `https://docs.ros.org/en/${rosdistro}/api/${pack}/html/msg/${type}.html`;
title.innerHTML = `${index}: ${topic} <a id="topic-type" href=${href} target="_blank">${typeStr}</a>`; title.innerHTML = `${topic} <a id="topic-type" href=${href} target="_blank">${typeStr}</a>`;
}); });
new ROSLIB.Topic({ ros: ros, name: topic }).subscribe(function(msg) { new ROSLIB.Topic({ ros: ros, name: topic }).subscribe(function(msg) {
document.title = topic; document.title = topic;
if (mouseDown) return; 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); topicMessage.innerHTML = yamlStringify(msg); // JSON.stringify(msg, null, 4);
}); });
} }
@@ -72,6 +59,8 @@ topicMessage.addEventListener('mousedown', function() { mouseDown = true; });
topicMessage.addEventListener('mouseup', function() { mouseDown = false; }); topicMessage.addEventListener('mouseup', function() { mouseDown = false; });
function init() { function init() {
const params = Object.fromEntries(new URLSearchParams(window.location.search).entries());
if (!params.topic) { if (!params.topic) {
viewTopicsList(); viewTopicsList();
} else { } else {

View File

@@ -17,12 +17,11 @@
} }
#topic-type { font-family: monospace; font-size: 0.5em; vertical-align: super; font-weight: normal; } #topic-type { font-family: monospace; font-size: 0.5em; vertical-align: super; font-weight: normal; }
.topic { font-family: monospace; } .topic { font-family: monospace; }
body.closed { background-color: rgb(207, 207, 207); }
</style> </style>
</head> </head>
<body> <body>
<h1>&nbsp;</h1> <h1>&nbsp;</h1>
<ul id="topics"></ul> <ul id="topics"></ul>
<code id="topic-message">No messages received</code> <code id="topic-message" title="Hold mouse button to pause">No messages received</code>
</body> </body>
</html> </html>

View File

@@ -1,7 +1,7 @@
<?xml version="1.0"?> <?xml version="1.0"?>
<package format="2"> <package format="2">
<name>clover_blocks</name> <name>clover_blocks</name>
<version>0.23.0</version> <version>0.21.1</version>
<description>Blockly programming support for Clover</description> <description>Blockly programming support for Clover</description>
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer> <maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>
<license>MIT</license> <license>MIT</license>

View File

@@ -464,7 +464,7 @@ Blockly.Python.led_count = function(block) {
function pigpio() { function pigpio() {
Blockly.Python.definitions_['import_pigpio'] = 'import pigpio'; Blockly.Python.definitions_['import_pigpio'] = 'import pigpio';
Blockly.Python.definitions_['init_pigpio'] = 'pi = pigpio.pi()\nif not pi.connected: raise Exception(\'Cannot connect to pigpiod\')'; Blockly.Python.definitions_['init_pigpio'] = 'pi = pigpio.pi()';
} }
const GPIO_READ = `\ndef gpio_read(pin): const GPIO_READ = `\ndef gpio_read(pin):

View File

@@ -1,6 +1,6 @@
<package format="2"> <package format="2">
<name>clover_description</name> <name>clover_description</name>
<version>0.23.0</version> <version>0.21.1</version>
<description>The clover_description package provides URDF models of the Clover series of quadcopters.</description> <description>The clover_description package provides URDF models of the Clover series of quadcopters.</description>
<maintainer email="sfalexrog@gmail.com">Alexey Rogachevskiy</maintainer> <maintainer email="sfalexrog@gmail.com">Alexey Rogachevskiy</maintainer>

View File

@@ -1,6 +1,6 @@
<package format="2"> <package format="2">
<name>clover_simulation</name> <name>clover_simulation</name>
<version>0.23.0</version> <version>0.21.1</version>
<description>The clover_simulation package provides worlds and launch files for Gazebo.</description> <description>The clover_simulation package provides worlds and launch files for Gazebo.</description>
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer> <maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>

Binary file not shown.

Before

Width:  |  Height:  |  Size: 220 KiB

After

Width:  |  Height:  |  Size: 695 KiB

BIN
docs/assets/qgc-params.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 972 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 381 KiB

After

Width:  |  Height:  |  Size: 1.2 MiB

View File

@@ -70,7 +70,7 @@
* [Remote control app](rc.md) * [Remote control app](rc.md)
* [Wi-Fi Configuration](network.md) * [Wi-Fi Configuration](network.md)
* [UART settings](uart.md) * [UART settings](uart.md)
* [PX4 Parameters](parameters.md) * [PX4 Parameters](px4_parameters.md)
* [PX4 Logs and Topics](flight_logs.md) * [PX4 Logs and Topics](flight_logs.md)
* [PX4 Firmware](firmware.md) * [PX4 Firmware](firmware.md)
* [MAVLink](mavlink.md) * [MAVLink](mavlink.md)
@@ -100,8 +100,6 @@
* [CopterHack-2019](copterhack2019.md) * [CopterHack-2019](copterhack2019.md)
* [CopterHack-2018](copterhack2018.md) * [CopterHack-2018](copterhack2018.md)
* [CopterHack-2017](copterhack2017.md) * [CopterHack-2017](copterhack2017.md)
* [Video contest](video_contest.md)
* [Educational contests](educational_contests.md)
* [Clover-based projects](projects.md) * [Clover-based projects](projects.md)
* [Autonomous Multirotor Landing System (AMLS)](amls.md) * [Autonomous Multirotor Landing System (AMLS)](amls.md)
* [Drone show](clever-show.md) * [Drone show](clever-show.md)

View File

@@ -75,9 +75,9 @@ else:
shape = 'undefined' shape = 'undefined'
color = 'undefined' color = 'undefined'
if shape == 'brown': if shape = 'brown':
culture = "greshiha" culture = "greshiha"
if shape == 'yellow_orange': if shape = 'yellow_orange':
culture = "pshenitsa" culture = "pshenitsa"
image_sub = rospy.Subscriber('main_camera/image_raw', Image, image_colback_color) image_sub = rospy.Subscriber('main_camera/image_raw', Image, image_colback_color)

View File

@@ -1,5 +1,7 @@
# ArUco markers # 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. [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: Examples of ArUco markers:

View File

@@ -93,7 +93,7 @@ The marker map adheres to the [ROS coordinate system convention](http://www.ros.
## VPE setup ## VPE setup
In order to enable vision position estimation you should use the following [PX4 parameters](parameters.md). In order to enable vision position estimation you should use the following [PX4 parameters](px4_parameters.md).
If you're using **LPE** (`SYS_MC_EST_GROUP` parameter is set to `local_position_estimator,attitude_estimator_q`): If you're using **LPE** (`SYS_MC_EST_GROUP` parameter is set to `local_position_estimator,attitude_estimator_q`):

View File

@@ -6,7 +6,7 @@ Software autorun
systemd systemd
--- ---
Main documentation: https://wiki.archlinux.org/title/Systemd. Main documentation: [https://wiki.archlinux.org/index.php/Systemd_(Russian)](https://wiki.archlinux.org/index.php/Systemd_(Russian)).
All automatically started Clover software is launched as a `clover.service` systemd service. 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: The started file must have *permission* to run:
```bash ```(bash)
chmod +x my_program.py chmod +x my_program.py
``` ```
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: When scripting languages are used, [shebang] should be placed at the beginning of the file (https://ru.wikipedia.org/wiki/Shebang_(Unix)), for example:
```bash ```(bash)
#!/usr/bin/env python3 #!/usr/bin/env python
``` ```

View File

@@ -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. 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. 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/master/en/config/compass.html. Read more in the PX4 docs: https://docs.px4.io/v1.9.0/en/config/compass.html.
## Gyroscope ## Gyroscope
@@ -27,7 +27,7 @@ Read more in the PX4 docs: https://docs.px4.io/master/en/config/compass.html.
> **Warning** The drone should stay completely still during the calibration. > **Warning** The drone should stay completely still during the calibration.
Read more in the PX4 docs: https://docs.px4.io/master/en/config/gyroscope.html. Read more in the PX4 docs: https://docs.px4.io/v1.9.0/en/config/gyroscope.html.
## Accelerometer ## Accelerometer
@@ -38,7 +38,7 @@ Read more in the PX4 docs: https://docs.px4.io/master/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. 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. 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/master/en/config/accelerometer.html. Read more in the PX4 docs: https://docs.px4.io/v1.9.0/en/config/accelerometer.html.
## Level horizon ## Level horizon
@@ -50,6 +50,6 @@ Read more in the PX4 docs: https://docs.px4.io/master/en/config/accelerometer.ht
4. Press *OK*. 4. Press *OK*.
5. Wait for the calibration to finish. 5. Wait for the calibration to finish.
Read more in the PX4 docs: https://docs.px4.io/master/en/config/level_horizon_calibration.html. Read more in the PX4 docs: https://docs.px4.io/v1.9.0/en/config/level_horizon_calibration.html.
**Next**: [RC setup](radio.md). **Next**: [RC setup](radio.md).

View File

@@ -1,6 +1,6 @@
# COEX Pix # COEX Pix
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. 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.
> **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. > **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.

View File

@@ -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 The `connected` field should have the `True` value.s
> **Hint** You need to set the `CBRK_USB_CHK` [parameter](parameters.md) to 197848 for the USB connection to work. > **Hint** You need to set the `CBRK_USB_CHK` [parameter](px4_parameters.md) to 197848 for the USB connection to work.
## UART connection ## UART connection

View File

@@ -11,35 +11,33 @@ The proposed projects have to be open-source and be compatible with the Clover q
## Projects of the contest's participants {#participants} ## Projects of the contest's participants {#participants}
|Place|Team|Project|Points| |Place|Team|Project|Points|
|:-:|-|-|-| |-|-|-|-|
||🇰🇬 Alatoo University Team|[Облачная платформа для симулятора Клевера](https://github.com/pteacher/clover/blob/clover_simulator/docs/ru/clover-development-studio.md)|| ||🇰🇬 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/advanced_clover_simulator.md)|| ||🇧🇾 FTL|[Advanced Clover 2](https://github.com/FTL-team/clover/blob/FTL-advancedClover2/docs/ru/advancedclover2.md)||
||🇺🇸 EnviroFleet|[EnviroFleet](https://github.com/gueyman/clover/blob/envirofleet/docs/en/enviro_fleet.md)||
||🇻🇳 Dragon&Tanker|[Dragon&Tanker](https://github.com/uml4/clover/blob/drone_observe_autonomous_car/docs/en/dragon_and_tanker_team.md)||
||🇷🇺 Stereo|[Neural obstacle avoidance](https://github.com/den250400/clover/blob/neural-obstacle-avoidance/docs/en/neural-obstacle-avoidance.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)|| ||🇷🇺 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)|| ||🇷🇺 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)|| ||🇲🇾 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)|| ||🇷🇺 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)|| ||🇷🇺 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)|| ||🇵🇱 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)|| ||🇷🇺 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)|| ||🇷🇺 Дрой Ронов|[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)|| ||🇩🇪 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)||
||🇷🇺 Бизнес-гуси|[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)||
||🇮🇳 DJS Phoenix|[Autonomous valet parking drone assistance](https://github.com/DJSPhoenix/clover/blob/DJSPhoenix-Ikshana/docs/en/djs_phoenix_ikshana.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)|| ||🇷🇺 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)|| ||🇷🇺 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)|| ||🇰🇬 AI_U_CLOVER|[AIU_CLOVER](https://github.com/zhibekm/clover/blob/zhibekm-patch-1/docs/en/aiu-article.md)||
||🇷🇺 Scout_Drone|[Создание поисково-спасательного беспилотного летательного аппарата](https://github.com/MustafaNatur/clover/blob/Scout_Drone.md/docs/ru/scout_drone.md)||
||🇷🇺 С305|[Система мониторинга воздуха](https://github.com/Ruslan2288/clover/blob/master/docs/ru/air_monitor.md)|&nbsp;| ||🇷🇺 С305|[Система мониторинга воздуха](https://github.com/Ruslan2288/clover/blob/master/docs/ru/air_monitor.md)|&nbsp;|
|✕|🇻🇳 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)||
|✕|🇷🇺 Scout_Drone|[Создание поисково-спасательного беспилотного летательного аппарата](https://github.com/MustafaNatur/clover/blob/Scout_Drone.md/docs/ru/scout_drone.md)|&nbsp;|
teams which haven't qualified for the Final.
## Company case competition ## Company case competition

View File

@@ -1,118 +0,0 @@
# 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.

View File

@@ -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: 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. In QGroundControl software, go to the *Vehicle Setup* panel and choose the *Safety* menu. 1. Open the *Safety* panel.
2. Select one of the following actions in the *RC Loss Failsafe Trigger* option: 2. Select one of the following actions in the *RC Loss Failsafe Trigger* option:
* *Land mode* transition to automatic land mode; * *Land mode* transition to automatic land mode;
* *Terminate* set all outputs to their failsafe values. * *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 2 s. 3. Set the timeout value before RC Loss triggers in the *RC Loss Timeout* field. We recommend setting it to 0.5 s.
<img src="../assets/qgc-failsafe.png" alt="QGroundControl failsafe" class="zoom"> <img src="../assets/qgc-failsafe.png" alt="QGroundControl failsafe" class="zoom">

View File

@@ -1,6 +1,6 @@
# Flight # Flight
> **Info** See also official PX4 flying guide: https://docs.px4.io/master/en/flying/. > **Info** See also official PX4 flying guide: https://docs.px4.io/v1.9.0/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. 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.

View File

@@ -9,8 +9,7 @@ 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; * `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; * `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); * <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: Additional frames become available when [ArUco positioning system](aruco.md) is active:

View File

@@ -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. > **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](parameters.md) to use the rangefinder data. PX4 should be properly [configured](px4_parameters.md) to use the rangefinder data.
Set the following parameters when EKF2 is used (`SYS_MC_EST_GROUP` = `ekf2`): Set the following parameters when EKF2 is used (`SYS_MC_EST_GROUP` = `ekf2`):

View File

@@ -29,7 +29,7 @@ Examples of MAVLink messages:
* `GLOBAL_POSITION_INT` global position of the quadcopter (latitude/longitude/altitude); * `GLOBAL_POSITION_INT` global position of the quadcopter (latitude/longitude/altitude);
* `COMMAND_LONG` a command to the quadcopter (take off, land, toggle modes, etc). * `COMMAND_LONG` a command to the quadcopter (take off, land, toggle modes, etc).
A complete list of MAVLink messages is available in [MAVLink documentation](https://mavlink.io/en/messages/common.html). A complete list of MAVLink messages is available in [MAVLink documentation] (http://mavlink.org/messages/common).
### System, system component ### System, system component

View File

@@ -4,11 +4,10 @@ PX4 **mode** determines how the vehicle should react to commands and RC signals.
In order to configure flight modes: In order to configure flight modes:
1. Open the *Vehicle Setup* panel in QGroundControl. 1. Open the *Vehicle Setup* tab in QGroundControl.
2. Select the *Flight Modes* menu. 2. Select the *Flight Modes* menu.
3. Set the *Mode Channel* to the SwC switch (*Channel 6*). 3. Choose SwC (Channel 6) as mode selection switch.
4. Optionally, set the *Emergency Kill Switch Channel* to SwA switch (*Channel 5*). 4. Set desired flight modes.
5. Set desired flight modes.
The following flight modes are recommended: The following flight modes are recommended:
@@ -16,8 +15,8 @@ In order to configure flight modes:
* Flight Mode 4: *Altitude*. * Flight Mode 4: *Altitude*.
* Flight Mode 6: *Position*. * Flight Mode 6: *Position*.
6. Check mode switching by changing the switch position. 5. Check mode switching by changing the switch position.
7. Choose SwA (Channel 5) as emergency motor stop (*Kill switch*). 6. Choose SwA (Channel 5) as emergency motor stop (*Kill switch*).
<img src="../assets/qgc-modes.png" class="zoom" alt="QGroundControl modes"> <img src="../assets/qgc-modes.png" class="zoom" alt="QGroundControl modes">

View File

@@ -1,10 +1,12 @@
# Use of Optical Flow # Use of Optical Flow
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. 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.
## Enabling ## Enabling
> **Hint** For Optical Flow to work it's required that the laser rangefinder is [connected and configured](laser.md). > **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.
Enable Optical Flow in the file `~/catkin_ws/src/clover/clover/launch/clover.launch`: Enable Optical Flow in the file `~/catkin_ws/src/clover/clover/launch/clover.launch`:
@@ -12,7 +14,7 @@ Enable Optical Flow in the file `~/catkin_ws/src/clover/clover/launch/clover.lau
<arg name="optical_flow" default="true"/> <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. > **Info** Correct connection and [setup](camera.md) of the camera module is needed for proper functioning.

View File

@@ -1,112 +0,0 @@
# 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.

View File

@@ -6,16 +6,15 @@ 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. > **Note** Power sensor calibration should be done with the battery pack connected to the drone.
1. In QGroundControl software, go the *Vehicle Setup* panel and choose the *Power* menu. 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).
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: 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:
* Measure voltage across the battery (you may use a battery voltage tester for that). * Measure voltage across the battery (you may use a battery voltage tester for that).
* Press the *Calculate* button next to the *Voltage divider* label. * Press the *Calculate* button next to the *Voltage divider* label.
* Put the battery voltage into the prompt and click *Calculate*. * Put the battery voltage into the prompt and click *Calculate*.
* Press *Close* to save the calculated value. * 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"> <img src="../assets/qgc-voltage-divider.png" class="zoom">
Further reading: https://docs.qgroundcontrol.com/en/SetupView/Power.html. Further reading: https://docs.qgroundcontrol.com/en/SetupView/Power.html.
@@ -31,6 +30,6 @@ Further reading: https://docs.qgroundcontrol.com/en/SetupView/Power.html.
<img src="../assets/qgc-power.png" class="zoom"> <img src="../assets/qgc-power.png" class="zoom">
Further reading: https://docs.px4.io/master/en/advanced_config/esc_calibration.html. Further reading: https://docs.px4.io/v1.9.0/en/advanced_config/esc_calibration.html.
**Next**: [Failsafe configuration](failsafe.md) **Next**: [Failsafe configuration](failsafe.md)

View File

@@ -51,6 +51,8 @@ python3 flight.py
Below is a complete flight program that performs a takeoff, flies forward and lands: Below is a complete flight program that performs a takeoff, flies forward and lands:
```python ```python
#coding: utf8
import rospy import rospy
from clover import srv from clover import srv
from std_srvs.srv import Trigger from std_srvs.srv import Trigger

72
docs/en/px4_parameters.md Normal file
View File

@@ -0,0 +1,72 @@
# 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):
![PX4 parameters in QGroundControl](../assets/qgc-params.png)
## 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

View File

@@ -9,7 +9,7 @@ Before connecting and calibrating the RC, make sure that:
## Connecting the RC transmitter ## Connecting the RC transmitter
1. In QGroundControl software, go the *Vehicle Setup* panel and choose the *Radio* menu. 1. Open the *Vehicle Setup* tab and select the *Radio* menu.
2. Power on the transmitter by sliding the **POWER** slider up. 2. Power on the transmitter by sliding the **POWER** slider up.
3. Make sure the transmitter-receiver link is working. 3. Make sure the transmitter-receiver link is working.

View File

@@ -1,7 +1,7 @@
Raspberry Pi Raspberry Pi
============ ============
**Raspberry Pi** is a single-board computer that fits in the palm, created on the basis of ARM mobile microprocessor. It features low energy consumption, and it can even run on solar panels. A Raspberry Pi is included in the kits for programmable quadcopters "Clover". **Raspberry Pi** is a single-board computer that fits in the palm, created on the basis of ARM mobile microprocessor. It features low energy consumption, and it can even run on solar panels. Raspberry Pi 3 is included in the kits for programmable quadcopters "Clover".
<img src="../assets/raspberry.png" class="center zoom" alt="Raspberry Pi 3" width="400"> <img src="../assets/raspberry.png" class="center zoom" alt="Raspberry Pi 3" width="400">

View File

@@ -49,7 +49,7 @@ Each topic has the a of messages it passes. ROS include a lot of standard messag
|Message type|Description| |Message type|Description|
|-|-| |-|-|
|[`std_msgs/Int64`](https://docs.ros.org/api/std_msgs/html/msg/Int64.html)|Integer number.| |[`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.| |[`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/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.| |[`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.|

View File

@@ -43,7 +43,7 @@ Axis or Grid configured to frame `aruco_map` will visualize the location [on the
### jsk_rviz_plugins ### jsk_rviz_plugins
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: 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:
```(bash) ```(bash)
sudo apt-get install ros-melodic-jsk-visualization sudo apt-get install ros-melodic-jsk-visualization

View File

@@ -27,29 +27,28 @@ Main article: https://docs.qgroundcontrol.com/en/SetupView/Firmware.html
> **Note** Do not connect your flight controller prior to flashing. > **Note** Do not connect your flight controller prior to flashing.
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>**. 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>**.
To use all the most recent PX4 functions you also can use the latest official firmware version (experimentally). > **Info** For Pixhawk-based quadcopters there is a separate firmware version. See details in "[Pixhawk / Pixracer firmware flashing](firmware.md)" article.
Flash the flight controller with this firmware: Flash the flight controller with this firmware:
<img src="../assets/qgc-firmware.png" alt="QGroundControl firmware upload" class="zoom"> <img src="../assets/qgc-firmware.png" alt="QGroundControl firmware upload" class="zoom">
1. Disconnect the flight controller from computer (if connected). 1. Launch QGroundControl software.
2. Launch QGroundControl software. 2. Open the *Vehicle Setup* tab.
3. Go to *Vehicle Setup* panel (click on the QGroundControl logo in the top-left corner) and select *Firmware* menu. 3. Select the *Firmware* menu.
4. Connect your flight controller to your PC over USB. 4. Connect your flight controller to your PC over USB.
5. Select *PX4 Flight Stack* in the right bar appeared. 5. Wait for the flight controller to connect to QGroundControl.
6. Select *PX4 Flight Stack* in the right bar.
<img src="../assets/qgc-firmware.png" alt="QGroundControl firmware upload" class="zoom"> To use the recommended Copter Express firmware:
6. To use **COEX patched firmware**: * Check *Advanced Settings* checkbox.
* Select *Custom firmware file...* from the dropdown list.
* Press *OK* and select the file that you've downloaded.
* Check *Advanced Settings* checkbox. To use the latest official stable firmware just press *OK*.
* 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. Wait for QGroundControl to finish flashing the flight controller.
@@ -83,7 +82,7 @@ This is how the main QGroundControl settings window will look like:
### Setting parameters ### Setting parameters
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). Open the *Vehicle Setup* tab and select the *Parameters* menu. You can use the *Search* field to find parameters by name.
<img src="../assets/qgc-parameters.png" alt="QGroundControl parameters" class="zoom"> <img src="../assets/qgc-parameters.png" alt="QGroundControl parameters" class="zoom">

View File

@@ -1,4 +1,11 @@
# Autonomous flight 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.
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). 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).
@@ -6,7 +13,8 @@ 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). 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 usage Python examples
---
You need to create proxies for services before calling them. Use the following template for your programs: You need to create proxies for services before calling them. Use the following template for your programs:
@@ -29,7 +37,8 @@ land = rospy.ServiceProxy('land', Trigger)
Unused proxy functions may be removed from the code. Unused proxy functions may be removed from the code.
## API description API description
---
> **Note** Omitted numeric parameters are set to 0. > **Note** Omitted numeric parameters are set to 0.
@@ -286,7 +295,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). Switch the drone to landing [mode](modes.md) (`AUTO.LAND` or similar).
> **Note** Set the `COM_DISARM_LAND` [PX4 parameter](parameters.md) to a value greater than 0 to enable automatic disarm after landing. > **Note** Set the `COM_DISARM_LAND` [PX4 parameter](px4_parameters.md) to a value greater than 0 to enable automatic disarm after landing.
Landing the drone: Landing the drone:
@@ -303,9 +312,14 @@ Landing the drone (command line):
rosservice call /land "{}" rosservice call /land "{}"
``` ```
> **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. <!--
### release
## Additional materials Stop publishing setpoints to the drone (release control). Required to continue monitoring by means of [MAVROS](mavros.md).
-->
Additional materials
------------------------
* [ArUco-based position estimation and navigation](aruco.md). * [ArUco-based position estimation and navigation](aruco.md).
* [Program samples and snippets](snippets.md). * [Program samples and snippets](snippets.md).

View File

@@ -4,56 +4,31 @@ Setting up the simulation environment from scratch requires some effort, but res
> **Hint** See up-to-date commands set for installation Clover simulation software in the script, that builds the virtual machine image with the simulator: [`install_software.sh`](https://github.com/CopterExpress/clover_vm/blob/master/scripts/install_software.sh). > **Hint** See up-to-date commands set for installation Clover simulation software in the script, that builds the virtual machine image with the simulator: [`install_software.sh`](https://github.com/CopterExpress/clover_vm/blob/master/scripts/install_software.sh).
Prerequisites: **Ubuntu 20.04**. Prerequisites: Ubuntu 20.04 and [ROS Noetic](http://wiki.ros.org/noetic/Installation/Ubuntu).
## Install ROS
Install ROS Noetic using the [official installation manual](http://wiki.ros.org/noetic/Installation/Ubuntu) (Desktop or Full install).
Add sourcing ROS' `setup.bash` initialization script to your `.bashrc`:
```bash
echo "source /opt/ros/noetic/setup.bash" >> ~/.bashrc
source ~/.bashrc
```
Install required tools:
```bash
sudo apt install build-essential git python3-pip python3-rosdep
```
## Create a workspace for the simulation ## Create a workspace for the simulation
Create a workspace for the simulation: Throughout this guide we will be using the `catkin_ws` as the workspace name. Feel free to change it in your setup. We will be creating it in the home directory of the current user (`~`).
Create the workspace and clone Clover sources:
```bash ```bash
mkdir -p ~/catkin_ws/src mkdir -p ~/catkin_ws/src
cd ~/catkin_ws
catkin_make
echo "source ~/catkin_ws/devel/setup.bash" >> ~/.bashrc
source ~/.bashrc
```
Clone Clover sources:
```bash
cd ~/catkin_ws/src cd ~/catkin_ws/src
git clone --depth 1 https://github.com/CopterExpress/clover git clone --depth 1 https://github.com/CopterExpress/clover
git clone --depth 1 https://github.com/CopterExpress/ros_led git clone --depth 1 https://github.com/CopterExpress/ros_led
git clone --depth 1 https://github.com/ethz-asl/mav_comm git clone --depth 1 https://github.com/ethz-asl/mav_comm
``` ```
Install all dependencies using `rosdep`: Install all prerequisites using `rosdep`:
```bash ```bash
cd ~/catkin_ws cd ~/catkin_ws
sudo rosdep init
rosdep update rosdep update
rosdep install --from-paths src --ignore-src -y rosdep install --from-paths src --ignore-src -y
``` ```
Install Python dependencies: Install Python-dependencies:
```bash ```bash
sudo /usr/bin/python3 -m pip install -r ~/catkin_ws/src/clover/clover/requirements.txt sudo /usr/bin/python3 -m pip install -r ~/catkin_ws/src/clover/clover/requirements.txt
@@ -61,19 +36,15 @@ sudo /usr/bin/python3 -m pip install -r ~/catkin_ws/src/clover/clover/requiremen
## Get PX4 sources ## Get PX4 sources
PX4 will be built along with the other packages in our workspace. You may clone it directly into the workspace or put it somewhere and symlink to `~/catkin_ws/src`. We will need to put its `sitl_gazebo` and `mavlink` submodules into `~/catkin_ws/src` as well. PX4 will be built along with the other packages in our workspace. You may clone it directly into the workspace or put it somewhere and symlink to `~/catkin_ws/src`. We will need to put its `sitl_gazebo` submodule in `~/catkin_ws/src` as well. For simplicity's sake we will clone the firmware directly to the workspace:
Clone PX4 sources and make the required symlinks:
```bash ```bash
cd ~/catkin_ws/src
git clone --recursive --depth 1 --branch v1.12.0 https://github.com/PX4/PX4-Autopilot.git ~/PX4-Autopilot git clone --recursive --depth 1 --branch v1.12.0 https://github.com/PX4/PX4-Autopilot.git ~/PX4-Autopilot
ln -s ~/PX4-Autopilot ~/catkin_ws/src/ ln -s ~/PX4-Autopilot ~/catkin_ws/src/PX4-Autopilot
ln -s ~/PX4-Autopilot/Tools/sitl_gazebo ~/catkin_ws/src/ ln -s ~/PX4-Autopilot/Tools/sitl_gazebo ~/catkin_ws/src/sitl_gazebo
ln -s ~/PX4-Autopilot/mavlink ~/catkin_ws/src/
``` ```
> **Hint** You may use more recent PX4 version, but there would be more risk of something would not be working.
## Install PX4 prerequisites ## Install PX4 prerequisites
PX4 comes with its own script for dependency installation. We may as well leverage it: PX4 comes with its own script for dependency installation. We may as well leverage it:
@@ -85,12 +56,10 @@ sudo ./ubuntu.sh
This will install everything required to build PX4 and its SITL environment. This will install everything required to build PX4 and its SITL environment.
> **Hint** You may want to skip installing the ARM toolchain if you're not planning on compiling PX4 for your flight controller. To do this, use the `--no-nuttx` flag: `sudo ./ubuntu.sh --no-nuttx`. You may want to skip installing the ARM toolchain if you're not planning on compiling PX4 for your flight controller. To do this, use the `--no-nuttx` flag:
Install more required Python packages: ```
sudo ./ubuntu.sh --no-nuttx
```bash
pip3 install --user toml
``` ```
## Add the Clover airframe ## Add the Clover airframe
@@ -98,7 +67,7 @@ pip3 install --user toml
Add the Clover airframe to PX4 using the command: Add the Clover airframe to PX4 using the command:
```bash ```bash
ln -s ~/catkin_ws/src/clover/clover_simulation/airframes/* ~/PX4-Autopilot/ROMFS/px4fmu_common/init.d-posix/airframes/ ln -s "$(catkin_find clover_simulation airframes)"/* ~/PX4-Autopilot/ROMFS/px4fmu_common/init.d-posix/airframes/
``` ```
## Install geographiclib datasets ## Install geographiclib datasets
@@ -111,44 +80,20 @@ sudo /opt/ros/noetic/lib/mavros/install_geographiclib_datasets.sh
## Build the simulator ## Build the simulator
Build your workspace: With all dependencies installed, you can build your workspace:
```bash ```bash
cd ~/catkin_ws cd ~/catkin_ws
catkin_make catkin_make
``` ```
> **Note** If building fails with RAM issues (`c++: fatal error: Killed signal terminated program cc1plus`), reduce the number of parallel jobs using `-j` key. For example, to use only two parallel jobs use `catkin_make -j2` command. > **Note** Some of the files - particularly Gazebo plugins - require large amounts of RAM to be built. You may wish to reduce the number of parallel jobs; the number of parallel jobs should be equal to the amount of RAM in gigabytes divided by 2 - so a 16GB machine should use no more than 8 jobs. You can specify the number of jobs using the `-j` flag: `catkin_make -j8`
## Run the simulator ## Run the simulator
In order to be sure that everything was built correctly, try running the simulator for the first time: In order to be sure that everything was built correctly, try running the simulator for the first time:
```bash ```bash
source ~/catkin_ws/devel/setup.bash
roslaunch clover_simulation simulator.launch roslaunch clover_simulation simulator.launch
``` ```
You can test autonomous flight using example scripts in `~/catkin_ws/src/clover/clover/examples` directory.
## Additional steps
Optionally, install roscore systemd service to have roscore running in background:
```bash
sed -i "s/pi/$USER/g" ~/catkin_ws/src/clover/builder/assets/roscore.service
sudo cp ~/catkin_ws/src/clover/builder/assets/roscore.service /etc/systemd/system
sudo systemctl enable roscore
sudo systemctl start roscore
```
Install any web server to serve Clover's web tools (`~/.ros/www` directory), e. g. Monkey:
```bash
wget https://github.com/CopterExpress/clover_vm/raw/master/assets/packages/monkey_1.6.9-1_amd64.deb -O /tmp/monkey_1.6.9-1_amd64.deb
sudo apt-get install -y /tmp/monkey_1.6.9-1_amd64.deb
sed "s/pi/$USER/g" ~/catkin_ws/src/clover/builder/assets/monkey | sudo tee /etc/monkey/sites/default
sudo -E sh -c "sed -i 's/SymLink Off/SymLink On/' /etc/monkey/monkey.conf"
sudo cp ~/catkin_ws/src/clover/builder/assets/monkey.service /etc/systemd/system/monkey.service
sudo systemctl enable monkey
sudo systemctl start monkey
```

View File

@@ -75,7 +75,7 @@ The plugin will collect publishing rate statistics and slow the simulation down
### Set simulation speed ### Set simulation speed
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. 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.
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: 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:

View File

@@ -5,7 +5,7 @@ PX4 Simulation
Main article: https://dev.px4.io/en/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://docs.px4.io/master/en/simulation/jmavsim.html) and [the Gazebo](http://gazebosim.org). 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).
jMAVSim is a lightweight environment intended only for testing multi-rotor aircraft systems; Gazebo is a versatile environment for all types of robots. jMAVSim is a lightweight environment intended only for testing multi-rotor aircraft systems; Gazebo is a versatile environment for all types of robots.

View File

@@ -8,11 +8,13 @@
<a name="block-takeoff"></a><!-- old name of anchor --> <a name="block-takeoff"></a><!-- old name of anchor -->
Function to fly to a point and wait for copter's arrival: Fly towards a point and wait for copter's arrival:
```python ```python
import math 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): 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) navigate(x=x, y=y, z=z, yaw=yaw, speed=speed, frame_id=frame_id, auto_arm=auto_arm)
@@ -62,6 +64,8 @@ Wait for copter's arrival to the [navigate](simple_offboard.md#navigate) target:
```python ```python
import math import math
# ...
def wait_arrival(tolerance=0.2): def wait_arrival(tolerance=0.2):
while not rospy.is_shutdown(): while not rospy.is_shutdown():
telem = get_telemetry(frame_id='navigate_target') telem = get_telemetry(frame_id='navigate_target')
@@ -75,8 +79,6 @@ 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)): Calculate the distance between two points (**important**: the points are to be in the same [coordinate system](frames.md)):
```python ```python
import math
def get_distance(x1, y1, z1, x2, y2, z2): def get_distance(x1, y1, z1, x2, y2, z2):
return math.sqrt((x1 - x2) ** 2 + (y1 - y2) ** 2 + (z1 - z2) ** 2) return math.sqrt((x1 - x2) ** 2 + (y1 - y2) ** 2 + (z1 - z2) ** 2)
``` ```
@@ -86,8 +88,6 @@ def get_distance(x1, y1, z1, x2, y2, z2):
Approximation of distance (in meters) between two global coordinates (latitude/longitude): Approximation of distance (in meters) between two global coordinates (latitude/longitude):
```python ```python
import math
def get_distance_global(lat1, lon1, lat2, lon2): def get_distance_global(lat1, lon1, lat2, lon2):
return math.hypot(lat1 - lat2, lon1 - lon2) * 1.113195e5 return math.hypot(lat1 - lat2, lon1 - lon2) * 1.113195e5
``` ```
@@ -203,16 +203,19 @@ from geometry_msgs.msg import PoseStamped, TwistStamped
from sensor_msgs.msg import BatteryState from sensor_msgs.msg import BatteryState
from mavros_msgs.msg import RCIn from mavros_msgs.msg import RCIn
# ...
def pose_update(pose): def pose_update(pose):
# Processing new data of copter's position # Processing new data of copter's position
pass pass
# Other handler functions
# ...
rospy.Subscriber('/mavros/local_position/pose', PoseStamped, pose_update) rospy.Subscriber('/mavros/local_position/pose', PoseStamped, pose_update)
rospy.Subscriber('/mavros/local_position/velocity', TwistStamped, velocity_update) rospy.Subscriber('/mavros/local_position/velocity', TwistStamped, velocity_update)
rospy.Subscriber('/mavros/battery', BatteryState, battery_update) rospy.Subscriber('/mavros/battery', BatteryState, battery_update)
rospy.Subscriber('mavros/rc/in', RCIn, rc_callback) rospy.Subscriber('mavros/rc/in', RCIn, rc_callback)
rospy.spin()
``` ```
Information about MAVROS topics is available at [the link](mavros.md). Information about MAVROS topics is available at [the link](mavros.md).
@@ -226,13 +229,18 @@ Information about MAVROS topics is available at [the link](mavros.md).
Send an arbitrary [MAVLink message](mavlink.md) to the copter: Send an arbitrary [MAVLink message](mavlink.md) to the copter:
```python ```python
# ...
from mavros_msgs.msg import Mavlink from mavros_msgs.msg import Mavlink
from mavros import mavlink from mavros import mavlink
from pymavlink import mavutil from pymavlink import mavutil
# ...
mavlink_pub = rospy.Publisher('mavlink/to', Mavlink, queue_size=1) mavlink_pub = rospy.Publisher('mavlink/to', Mavlink, queue_size=1)
# Sending a HEARTBEAT message: # Sending a HEARTBEAT message:
msg = mavutil.mavlink.MAVLink_heartbeat_message(mavutil.mavlink.MAV_TYPE_GCS, 0, 0, 0, 0, 0) msg = mavutil.mavlink.MAVLink_heartbeat_message(mavutil.mavlink.MAV_TYPE_GCS, 0, 0, 0, 0, 0)
msg.pack(mavutil.mavlink.MAVLink('', 2, 1)) msg.pack(mavutil.mavlink.MAVLink('', 2, 1))
ros_msg = mavlink.convert_to_rosmsg(msg) ros_msg = mavlink.convert_to_rosmsg(msg)
@@ -273,6 +281,8 @@ Change the [flight mode](modes.md) to arbitrary one:
```python ```python
from mavros_msgs.srv import SetMode from mavros_msgs.srv import SetMode
# ...
set_mode = rospy.ServiceProxy('mavros/set_mode', SetMode) set_mode = rospy.ServiceProxy('mavros/set_mode', SetMode)
# ... # ...
@@ -287,6 +297,8 @@ Flip:
```python ```python
import math import math
# ...
PI_2 = math.pi / 2 PI_2 = math.pi / 2
def flip(): def flip():
@@ -325,6 +337,8 @@ from pymavlink import mavutil
from mavros_msgs.srv import CommandLong from mavros_msgs.srv import CommandLong
from mavros_msgs.msg import State from mavros_msgs.msg import State
# ...
send_command = rospy.ServiceProxy('/mavros/cmd/command', CommandLong) send_command = rospy.ServiceProxy('/mavros/cmd/command', CommandLong)
def calibrate_gyro(): def calibrate_gyro():
@@ -358,6 +372,8 @@ Enable and disable [ArUco markers recognition](aruco_marker.md) dynamically (for
import rospy import rospy
import dynamic_reconfigure.client import dynamic_reconfigure.client
# ...
client = dynamic_reconfigure.client.Client('aruco_detect') client = dynamic_reconfigure.client.Client('aruco_detect')
# Turn markers recognition off # Turn markers recognition off
@@ -376,42 +392,10 @@ Wait for global position to appear (finishing [GPS receiver](gps.md) initializat
```python ```python
import math import math
# ...
while not rospy.is_shutdown(): while not rospy.is_shutdown():
if math.isfinite(get_telemetry().lat): if math.isfinite(get_telemetry().lat):
break break
rospy.sleep(0.2) rospy.sleep(0.2)
``` ```
### # {#get-param}
Read flight controller's parameter:
```python
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
# Read parameter of type FLOAT
value = param_get(param_id='MPC_Z_P').value.float
```
### # {#set-param}
Set flight controller's parameter:
```python
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))
# Set parameter of type FLOAT:
param_set(param_id='MPC_Z_P', value=ParamValue(real=1.5))
```

View File

@@ -89,7 +89,7 @@ while True:
### Filtering the data ### 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://en.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://ru.wikipedia.org/wiki/Median_filter) can be used. An example of median filtering implementation:
```python ```python
import collections import collections

View File

@@ -1,25 +0,0 @@
# Contest for the best educational video on assembly and configuration
Requirements:
- the video contains the entire process of assembling and configuring the Clover 4.2 drone kit: from opening the box with components to flying the copter in Position mode using ArUco markers;
- the video is uploaded to YouTube and is public accessible;
- the video contains voice-over in English;
- the video lasts from 6 to 60 minutes.
Dates of the contest: February 12 December 13, 2021.
## Prizes
- 🥇 1st place: $500 (USD).
- 🥈 2nd place: $300 (USD).
- 🥉 3rd place: $200 (USD).
## Results
|Place|Participant|Link to the video|
|:-:|-|-|
|1|🇷🇺 Philipp Batalin|https://www.youtube.com/watch?v=f0rpdulOSEk|
|2|🇮🇹 Sara Pettinari|https://www.youtube.com/watch?v=PxxfyVH6RRA|
|3|🇲🇾 Kai Feng Chew|https://www.youtube.com/watch?v=skgSwFle6Ms|
|3|🇰🇿 Nikita Lobanov|https://www.youtube.com/watch?v=93b1epEM3SQ|

View File

@@ -17,7 +17,7 @@
* [Работа с FS-A8S](rc_flysky_a8s.md) * [Работа с FS-A8S](rc_flysky_a8s.md)
* [Полетные режимы](modes.md) * [Полетные режимы](modes.md)
* [Настройка питания](power.md) * [Настройка питания](power.md)
* [Настройка Failsafe](failsafe.md) * [Настройка failsafe](failsafe.md)
* [Ручной полет](flight.md) * [Ручной полет](flight.md)
* [Упражнения](flight_exercises.md) * [Упражнения](flight_exercises.md)
* [Работа с Raspberry Pi](raspberry.md) * [Работа с Raspberry Pi](raspberry.md)
@@ -75,7 +75,7 @@
* [Пилотирование со смартфона](rc.md) * [Пилотирование со смартфона](rc.md)
* [Настройка сети RPi](network.md) * [Настройка сети RPi](network.md)
* [Интерфейс UART](uart.md) * [Интерфейс UART](uart.md)
* [Параметры PX4](parameters.md) * [Параметры PX4](px4_parameters.md)
* [Работа с логами PX4](flight_logs.md) * [Работа с логами PX4](flight_logs.md)
* [Прошивка PX4](firmware.md) * [Прошивка PX4](firmware.md)
* [Протокол MAVLink](mavlink.md) * [Протокол MAVLink](mavlink.md)
@@ -114,8 +114,6 @@
* [Робокросс-2019](robocross2019.md) * [Робокросс-2019](robocross2019.md)
* [CopterHack-2018](copterhack2018.md) * [CopterHack-2018](copterhack2018.md)
* [CopterHack-2017](copterhack2017.md) * [CopterHack-2017](copterhack2017.md)
* [Конкурс видео](video_contest.md)
* [Образовательные конкурсы](educational_contests.md)
* [Проекты на базе Клевера](projects.md) * [Проекты на базе Клевера](projects.md)
* [Система автоматической посадки (AMLS)](amls.md) * [Система автоматической посадки (AMLS)](amls.md)
* [Разработка системы для управления БПЛА с помощью шлема виртуальной реальности](remote-control-with-oculusvr.md) * [Разработка системы для управления БПЛА с помощью шлема виртуальной реальности](remote-control-with-oculusvr.md)

View File

@@ -75,9 +75,9 @@ else:
shape = 'undefined' shape = 'undefined'
color = 'undefined' color = 'undefined'
if shape == 'brown': if shape = 'brown':
culture = "greshiha" culture = "greshiha"
if shape == 'yellow_orange': if shape = 'yellow_orange':
culture = "pshenitsa" culture = "pshenitsa"
image_sub = rospy.Subscriber('main_camera/image_raw', Image, image_colback_color) image_sub = rospy.Subscriber('main_camera/image_raw', Image, image_colback_color)

View File

@@ -93,7 +93,7 @@ rosrun aruco_pose genmap.py 0.33 2 4 1 1 0 -o test_map.txt
## Настройка VPE ## Настройка VPE
Для работы механизма Vision Position Estimation необходимы следующие [настройки PX4](parameters.md). Для работы механизма Vision Position Estimation необходимы следующие [настройки PX4](px4_parameters.md).
При использовании **LPE** (параметр `SYS_MC_EST_GROUP` = `local_position_estimator, attitude_estimator_q`): При использовании **LPE** (параметр `SYS_MC_EST_GROUP` = `local_position_estimator, attitude_estimator_q`):

View File

@@ -6,7 +6,7 @@
systemd 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`. Все автоматически стартуемое ПО Клевера запускается в виде systemd-сервиса `clover.service`.
@@ -54,8 +54,8 @@ roslaunch
chmod +x my_program.py chmod +x my_program.py
``` ```
При использовании скриптовых языков вначале файла должен стоять <a href="https://ru.wikipedia.org/wiki/Шебанг_(Unix)">shebang</a>, например: При использовании скриптовых языков вначале файла должен стоять [shebang](https://ru.wikipedia.org/wiki/Шебанг_(Unix)), например:
```bash ```bash
#!/usr/bin/env python3 #!/usr/bin/env python
``` ```

View File

@@ -14,9 +14,7 @@
4. Последовательно устанавливайте квадрокоптер в каждую из указанных ориентаций до появления желтой рамки. 4. Последовательно устанавливайте квадрокоптер в каждую из указанных ориентаций до появления желтой рамки.
5. Вращайте квадрокоптер по направлению стрелки до появления зеленой рамки. 5. Вращайте квадрокоптер по направлению стрелки до появления зеленой рамки.
> **Warning** Последние версии прошивки PX4 не поддерживают внутренний компас на полетном контроллере COEX Pix. При появлении ошибки *No mags found* перейдите во вкладку *Parameters*, установите параметры `SYS_HAS_MAG` в `0`, `EKF2_MAG_TYPE` в `None` и перезагрузите полетный контроллер (*Tools* => *Reboot Vehicle*). Дополнительная информация: https://docs.px4.io/v1.9.0/en/config/compass.html.
Дополнительная информация: https://docs.px4.io/master/en/config/compass.html.
## Гироскоп ## Гироскоп
@@ -29,7 +27,7 @@
> **Warning** Во время калибровки гироскопа квадрокоптер не должен менять своего положения, шататься и т. д. > **Warning** Во время калибровки гироскопа квадрокоптер не должен менять своего положения, шататься и т. д.
Дополнительная информация: https://docs.px4.io/master/en/config/gyroscope.html. Дополнительная информация: https://docs.px4.io/v1.9.0/en/config/gyroscope.html.
## Акселерометр ## Акселерометр
@@ -40,7 +38,7 @@
3. Последовательно устанавливайте квадрокоптер в каждую из указанных ориентаций до появления желтой рамки. 3. Последовательно устанавливайте квадрокоптер в каждую из указанных ориентаций до появления желтой рамки.
4. Держите квадрокоптер неподвижно до появления зеленой рамки. 4. Держите квадрокоптер неподвижно до появления зеленой рамки.
Дополнительная информация: https://docs.px4.io/master/en/config/accelerometer.html. Дополнительная информация: https://docs.px4.io/v1.9.0/en/config/accelerometer.html.
## Уровень горизонта ## Уровень горизонта
@@ -52,6 +50,6 @@
4. Нажмите *OK*. 4. Нажмите *OK*.
5. Дождитесь окончания калибровки. 5. Дождитесь окончания калибровки.
Дополнительная информация: https://docs.px4.io/master/en/config/level_horizon_calibration.html. Дополнительная информация: https://docs.px4.io/v1.9.0/en/config/level_horizon_calibration.html.
**Далее**: [Настройка пульта](radio.md). **Далее**: [Настройка пульта](radio.md).

View File

@@ -42,4 +42,4 @@ sudo systemctl start clever-blocks.service
python main.py python main.py
``` ```
После запуска Вы можете открыть веб-интерфейс для блочного программирования по адресу [192.168.11.1:5000](http://192.168.11.1:5000). После запуска Вы можете открыть веб-интерфейс для блочного программирования по адресу [192.168.11.1:5000](192.168.11.1:5000).

View File

@@ -16,7 +16,7 @@
Поле `connected` должно содержать значение `True`. Поле `connected` должно содержать значение `True`.
> **Hint** Для корректной работы подключения Raspberry Pi и Pixhawk по USB необходимо установить значение [параметра](parameters.md) `CBRK_USB_CHK` на 197848. > **Hint** Для корректной работы подключения Raspberry Pi и Pixhawk по USB необходимо установить значение [параметра](px4_parameters.md) `CBRK_USB_CHK` на 197848.
## Подключение по UART ## Подключение по UART

View File

@@ -11,35 +11,33 @@ CopterHack 2022 — это международный конкурс по ра
## Проекты участников конкурса {#participants} ## Проекты участников конкурса {#participants}
|Место|Команда|Проект|Балл| |Место|Команда|Проект|Балл|
|:-:|-|-|-| |-|-|-|-|
||🇰🇬 Alatoo University Team|[Облачная платформа для симулятора Клевера](https://github.com/pteacher/clover/blob/clover_simulator/docs/ru/clover-development-studio.md)|| ||🇰🇬 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/advanced_clover_simulator.md)|| ||🇧🇾 FTL|[Advanced Clover 2](https://github.com/FTL-team/clover/blob/FTL-advancedClover2/docs/ru/advancedclover2.md)||
||🇺🇸 EnviroFleet|[EnviroFleet](https://github.com/gueyman/clover/blob/envirofleet/docs/en/enviro_fleet.md)||
||🇻🇳 Dragon&Tanker|[Dragon&Tanker](https://github.com/uml4/clover/blob/drone_observe_autonomous_car/docs/en/dragon_and_tanker_team.md)||
||🇷🇺 Stereo|[Neural obstacle avoidance](https://github.com/den250400/clover/blob/neural-obstacle-avoidance/docs/en/neural-obstacle-avoidance.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)|| ||🇷🇺 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)|| ||🇷🇺 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)|| ||🇲🇾 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)|| ||🇷🇺 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)|| ||🇷🇺 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)|| ||🇵🇱 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)|| ||🇷🇺 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)|| ||🇷🇺 Дрой Ронов|[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)|| ||🇩🇪 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)||
||🇷🇺 Бизнес-гуси|[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)||
||🇮🇳 DJS Phoenix|[Autonomous valet parking drone assistance](https://github.com/DJSPhoenix/clover/blob/DJSPhoenix-Ikshana/docs/en/djs_phoenix_ikshana.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)|| ||🇷🇺 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)|| ||🇷🇺 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)|| ||🇰🇬 AI_U_CLOVER|[AIU_CLOVER](https://github.com/zhibekm/clover/blob/zhibekm-patch-1/docs/en/aiu-article.md)||
||🇷🇺 Scout_Drone|[Создание поисково-спасательного беспилотного летательного аппарата](https://github.com/MustafaNatur/clover/blob/Scout_Drone.md/docs/ru/scout_drone.md)||
||🇷🇺 С305|[Система мониторинга воздуха](https://github.com/Ruslan2288/clover/blob/master/docs/ru/air_monitor.md)|&nbsp;| ||🇷🇺 С305|[Система мониторинга воздуха](https://github.com/Ruslan2288/clover/blob/master/docs/ru/air_monitor.md)|&nbsp;|
|✕|🇻🇳 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)||
|✕|🇷🇺 Scout_Drone|[Создание поисково-спасательного беспилотного летательного аппарата](https://github.com/MustafaNatur/clover/blob/Scout_Drone.md/docs/ru/scout_drone.md)|&nbsp;|
команды, не дошедшие до финала.
## Направление "кейс компании" ## Направление "кейс компании"

View File

@@ -1,119 +0,0 @@
# Образовательные конкурсы
## 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.

View File

@@ -1,13 +1,13 @@
# Настройка Failsafe # Настройка failsafe
Основная статья: https://docs.px4.io/master/en/config/safety.html. Основная статья: https://docs.px4.io/master/en/config/safety.html.
Во вкладке *Safety* настраиваются реакции квадрокоптера на различные нештатные ситуации. Рекомендуется включить как минимум реакцию на потерю связи с пультом управления: Во вкладке *Safety* настраиваются реакции квадрокоптера на различные нештатные ситуации. Рекомендуется включить как минимум реакцию на потерю связи с пультом управления:
1. В программе QGroundControl перейдите в панель *Vehicle Setup* и выберите меню *Safety*. 1. Откройте вкладку *Safety*.
2. В блоке *RC Loss Failsafe Trigger* выберите один из рекомендуемых вариантов реакции на потерю связи с пультом: 2. В блоке *RC Loss Failsafe Trigger* выберите один из рекомендуемых вариантов реакции на потерю связи с пультом:
* *Land mode* – переход в режим посадки; * *Land mode* – переход в режим посадки;
* *Terminate* аварийное отключение моторов. * *Terminate* аварийное отключение моторов.
3. В поле *RC Loss Timeout* выберите значение таймаута, по истечении которого связь с пультом считается потерянной. Рекомендуемое значение  2 s. 3. В поле *RC Loss Timeout* выберите значение таймаута, по истечении которого связь с пультом считается потерянной. Рекомендуемое значение  0.5 s.
<img src="../assets/qgc-failsafe.png" alt="QGroundControl failsafe" class="zoom"> <img src="../assets/qgc-failsafe.png" alt="QGroundControl failsafe" class="zoom">

View File

@@ -11,8 +11,7 @@
* `base_link` — координаты относительно квадрокоптера: схематичное изображение квадрокоптера на иллюстрации; * `base_link` — координаты относительно квадрокоптера: схематичное изображение квадрокоптера на иллюстрации;
* `body` — координаты относительно квадрокоптера без учета наклонов по тангажу и крену: красная, синяя и зеленая линии на иллюстрации; * `body` — координаты относительно квадрокоптера без учета наклонов по тангажу и крену: красная, синяя и зеленая линии на иллюстрации;
* <a name="navigate_target"></a>`navigate_target` координаты точки, в которую сейчас летит дрон (с использованием [navigate](simple_offboard.md#navigate)); * <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) появляются дополнительные фреймы: При использовании [системы позиционирования по ArUco-маркерам](aruco.md) появляются дополнительные фреймы:

View File

@@ -38,7 +38,7 @@ rostopic echo /rangefinder/range
> **Hint** Для корректной работы лазерного дальномера с полетным контроллером рекомендуется использование [специальной сборки PX4 для Клевера](firmware.md#прошивка-для-клевера). > **Hint** Для корректной работы лазерного дальномера с полетным контроллером рекомендуется использование [специальной сборки PX4 для Клевера](firmware.md#прошивка-для-клевера).
Для использования данных с дальномера в [PX4 должен быть сконфигурирован](parameters.md). Для использования данных с дальномера в [PX4 должен быть сконфигурирован](px4_parameters.md).
При использовании EKF2 (`SYS_MC_EST_GROUP` = `ekf2`): При использовании EKF2 (`SYS_MC_EST_GROUP` = `ekf2`):

View File

@@ -29,7 +29,7 @@ MAVLink-сообщение это отдельная "порция" данных
* `GLOBAL_POSITION_INT` глобальная позиция квадрокоптера (широта/долгота/высота); * `GLOBAL_POSITION_INT` глобальная позиция квадрокоптера (широта/долгота/высота);
* `COMMAND_LONG` команда для квадрокоптера (взлететь, сесть, переключить режим и т. д.). * `COMMAND_LONG` команда для квадрокоптера (взлететь, сесть, переключить режим и т. д.).
Полный список MAVLink-сообщений можно посмотреть в [документации MAVLink](https://mavlink.io/en/messages/common.html). Полный список MAVLink-сообщений можно посмотреть в [документации MAVLink](http://mavlink.org/messages/common).
### Система, компонент системы ### Система, компонент системы

View File

@@ -1,14 +1,13 @@
# Полетные режимы # Полетные режимы
**Режим** полетного контроллера PX4 определяет, как именно квадрокоптер (или другой аппарат) должен себя вести: каким образом интерпретировать входящие команды и сигналы с пульта. Режим переключается одним из переключателей на пульте радиоуправления. **Режим** полетного контроллера PX4 определяет, как именно коптер (или другое ТС) должно себя вести: каким образом интерпретировать входящие команды и сигналы с пульта. Режим переключается одним из переключателей на пульте радиоуправления.
Чтобы настроить полетные режимы: Чтобы настроить полетные режимы:
1. В программе QGroundControl перейдите в панель *Vehicle Setup*. 1. Зайдите во вкладку *Vehicle Setup*.
2. Выберите меню *Flight Modes*. 2. Выберите меню *Flight Modes*.
3. Установите переключатель режимов (*Mode Channel*) на переключатель SwC (*Channel 6*). 3. Установите переключатель режимов на переключатель SwC (Channel 6).
4. Опционально, установите экстренное отключение пропеллеров (*Emergency Kill Switch Channel*) на переключатель SwA (*Channel 5*). 4. Выберите необходимые полетные режимы.
5. Выберите необходимые полетные режимы.
Рекомендуемые полетные режимы: Рекомендуемые полетные режимы:
@@ -16,8 +15,8 @@
* Flight Mode 4: *Altitude*. * Flight Mode 4: *Altitude*.
* Flight Mode 6: *Position*. * Flight Mode 6: *Position*.
6. Проверьте корректность переключения режимов, переключая переключатель на пульте. 5. Проверьте корректность переключения режимов, переключая переключатель на пульте.
7. Назначьте аварийное отключение моторов (*Kill switch*) на переключатель SwA (Channel 5). 6. Назначьте аварийное отключение моторов (*Kill switch*) на переключатель SwA (Channel 5).
<img src="../assets/qgc-modes.png" class="zoom" alt="QGroundControl modes"> <img src="../assets/qgc-modes.png" class="zoom" alt="QGroundControl modes">

View File

@@ -4,7 +4,9 @@
## Включение ## Включение
> **Hint** Для работы Optical Flow необходим [подключенный и настроенный лазерный дальномер](laser.md). > **Hint** Необходимо использование [специальной сборки PX4 для Клевера](firmware.md#прошивка-для-клевера).
Необходимо использование дальномера. [Подключите и настройте дальномер VL53L1X](laser.md), используя инструкцию.
Включите Optical Flow в файле `~/catkin_ws/src/clover/clover/launch/clover.launch`: Включите Optical Flow в файле `~/catkin_ws/src/clover/clover/launch/clover.launch`:
@@ -12,7 +14,7 @@
<arg name="optical_flow" default="true"/> <arg name="optical_flow" default="true"/>
``` ```
Optical Flow публикует данные в топик `/mavros/px4flow/raw/send`. Кроме того, в топик `/optical_flow/debug` публикуется визуализация, которую можно просмотреть с помощью [web_video_server](web_video_server.md). Optical Flow публикует данные в топик `mavros/px4flow/raw/send`. Кроме того, в топик `optical_flow/debug` публикуется визуализация, которую можно просмотреть с помощью [web_video_server](web_video_server.md).
> **Info** Для правильной работы модуль камеры должен быть корректно подключен и [сконфигурирован](camera.md). > **Info** Для правильной работы модуль камеры должен быть корректно подключен и [сконфигурирован](camera.md).

View File

@@ -1,6 +1,6 @@
# Настройка PID регуляторов # Настройка PID регуляторов
Основная статья: https://docs.px4.io/master/en/config_mc/pid_tuning_guide_multicopter.html. Основная статья: https://docs.px4.io/v1.9.0/en/config_mc/pid_tuning_guide_multicopter.html.
В этой статье описаны методы и основные технологии настройки каскадного ПИД-регулятора. Приведенные советы и методики подходят для любых видов рам (Квадрокоптеров, Гексакоптеров, Октокоптеров и т.д.). В этой статье описаны методы и основные технологии настройки каскадного ПИД-регулятора. Приведенные советы и методики подходят для любых видов рам (Квадрокоптеров, Гексакоптеров, Октокоптеров и т.д.).

View File

@@ -6,16 +6,15 @@
> **Note** Калибровка делителя напряжения должна выполняться с подключенным АКБ. > **Note** Калибровка делителя напряжения должна выполняться с подключенным АКБ.
1. В программе QGroundControl перейдите в панель *Vehicle Setup* и выберите меню *Power*. В случае отсутствия индикатора напряжения или невозможности ручной калибровки, установите усредненное значение делителя напряжения для комплекта Клевер 4 (*Voltage divider* = 11).
2. Установите параметр *Number of cells* в соответствии с количеством банок в АКБ (*3S* для Клевера 4).
3. Откалибруйте делитель напряжения: 1. Установите параметр *Number of cells* в соответствии с количеством банок в АКБ (*3S* для Клевера 4).
2. Откалибруйте делитель напряжения:
* Подключите индикатор напряжения к балансировочному разъему АКБ. * Подключите индикатор напряжения к балансировочному разъему АКБ.
* Нажмите кнопку *Calculate* напротив надписи *Voltage Divider*. * Нажмите кнопку *Calculate* напротив надписи *Voltage Divider*.
* Введите в открывшемся поле суммарное значение напряжения с индикатора напряжения. * Введите в открывшемся поле суммарное значение напряжения с индикатора напряжения.
* Нажмите *Close*, чтобы сохранить рассчитанное значение. * Нажмите *Close*, чтобы сохранить рассчитанное значение.
В случае отсутствия индикатора напряжения или невозможности ручной калибровки, установите усредненное значение делителя напряжения для комплекта Клевер 4 (*Voltage divider* = 11).
<img src="../assets/qgc-voltage-divider.png" class="zoom"> <img src="../assets/qgc-voltage-divider.png" class="zoom">
Дополнительная информация: https://docs.qgroundcontrol.com/en/SetupView/Power.html. Дополнительная информация: https://docs.qgroundcontrol.com/en/SetupView/Power.html.
@@ -31,6 +30,6 @@
<img src="../assets/qgc-power.png" class="zoom"> <img src="../assets/qgc-power.png" class="zoom">
Дополнительная информация: https://docs.px4.io/master/en/advanced_config/esc_calibration.html. Дополнительная информация: https://docs.px4.io/v1.9.0/en/advanced_config/esc_calibration.html.
**Далее**: [настройка Failsafe](failsafe.md). **Далее**: [настройка Failsafe](failsafe.md).

View File

@@ -2,7 +2,7 @@
<img src="../assets/programming.png" width=250 align=right> <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). Платформа основывается на [фреймворке ROS](ros.md), который обеспечивает связь между пользовательской программой и сервисами Клевера, которые запущены в фоне в виде systemd-демона `clover`. Для связи с полетным контроллером используется пакет [MAVROS](mavros.md).
@@ -10,7 +10,7 @@
## Система позиционирования {#positioning} ## Система позиционирования {#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 ### Optical flow
@@ -32,7 +32,7 @@
## Автономный полет {#flight} ## Автономный полет {#flight}
> **Info** Для изучения языка программирования Python можно обратиться к [самоучителю](https://pythonworld.ru/samouchitel-python). > **Info** Для изучения языка программирования Python вы можете обратиться к [самоучителю](https://pythonworld.ru/samouchitel-python).
После настройки системы позиционирования становится возможным написание скриптов для автономных полетов. Для выполнения скриптов [подключитесь в Raspberry Pi по SSH](ssh.md). После настройки системы позиционирования становится возможным написание скриптов для автономных полетов. Для выполнения скриптов [подключитесь в Raspberry Pi по SSH](ssh.md).
@@ -51,6 +51,8 @@ python3 flight.py
Пример программы для полета (взлет, пролет вперед, посадка): Пример программы для полета (взлет, пролет вперед, посадка):
```python ```python
# coding: utf8
import rospy import rospy
from clover import srv from clover import srv
from std_srvs.srv import Trigger from std_srvs.srv import Trigger

View File

@@ -1,64 +1,20 @@
# Параметры PX4 # Параметры PX4
Полная документация по параметрам PX4: https://docs.px4.io/master/en/advanced_config/parameter_reference.html. Основная статья: https://dev.px4.io/en/advanced/parameter_reference.html
Для изменения параметров PX4 используйте программу QGroundControl, [подключившись к Клеверу по Wi-Fi](gcs_bridge.md) или USB. Перейдите в панель *Vehicle Setup* (кликнув на логотип QGroundControl в левом верхнем углу и выберите меню *Parameters*. > **Note** Это описание некоторых, наиболее важных параметров PX4 по состоянию на версию 1.8.0. Полный список см. по ссылке выше.
## Рекомендованные значения Для изменения параметров PX4 можно воспользоваться программой QGroundControl, [подключившись к Клеверу по Wi-Fi](gcs_bridge.md):
### Общие параметры ![Параметры PX4 в QGroundControl](../assets/qgc-params.png)
|Параметр|Значение|Примечание| ## Основные параметры
|-|-|-|
|`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 Наиболее важные параметры вынесены в этот параграф.
В случае использования LPE ([прошивка COEX](firmware.md)): `SYS_MC_EST_GROUP`  выбор модуля estimator'а.
|Параметр|Значение|Примечание| Это группа модулей, которая вычисляет текущее состояние (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_rate, roll_rate, yaw_rate;
* ориентация коптера (в локальной системе координат) pitch (тангаж), roll (крен), yaw (рысканье) (одно из представлений); * ориентация коптера (в локальной системе координат) pitch (тангаж), roll (крен), yaw (рысканье) (одно из представлений);
@@ -101,7 +57,9 @@ Estimator это подсистема, которая вычисляет тек
## LPE + Q attitude estimator ## LPE + Q attitude estimator
Данные параметры настраивают поведение модулей `lpe` и `q`, которые вычисляют состояние (ориентацию, позицию) коптера. Эти параметры применяются **только** если параметр `SYS_MC_EST_GROUP` установлен в значение `1` (local_position_estimator, attitude_estimator_q). Данные параметры настраивают поведение модулей `lpe` и `q`, которые вычисляют состояние (ориентацию, позицию) коптера. Эти параметры применяются **только** если параметр `SYS_MC_EST_GROUP` установлен в значение `1` (local_position_estimator, attitude_estimator_q)
TODO
## Commander ## Commander
@@ -110,3 +68,5 @@ Estimator это подсистема, которая вычисляет тек
## Sensors ## Sensors
Включение, выключение и настройка различных датчиков. Включение, выключение и настройка различных датчиков.
TODO

View File

@@ -9,7 +9,7 @@
## Подключение пульта ## Подключение пульта
1. В программе QGroundControl перейдите в панель *Vehicle Setup* и выберите меню *Radio*. 1. Зайдите во вкладку *Vehicle Setup* и выберите меню *Radio*.
2. Включите пульт, переводя переключатель *POWER* в верхнее положение. 2. Включите пульт, переводя переключатель *POWER* в верхнее положение.
3. Убедитесь, что связь с приемником установлена. 3. Убедитесь, что связь с приемником установлена.

View File

@@ -43,7 +43,7 @@ Axis или Grid настроенный на фрейм `aruco_map` будут
### jsk_rviz_plugins ### jsk_rviz_plugins
Рекомендуется также установка набора дополнительных полезных плагинов для rviz [jsk_rviz_plugins](https://jsk-visualization.readthedocs.io/en/latest/jsk_rviz_plugins/index.html). Это набор позволяет визуализировать топики типа `TwistStamped` (скорость), `CameraInfo`, `PolygonArray` и многое другое. Для установки используйте команду: Рекомендуется также установка набора дополнительных полезных плагинов для rviz [jsk_rviz_plugins](https://jsk-docs.readthedocs.io/en/latest/jsk_visualization/doc/jsk_rviz_plugins/index.html). Это набор позволяет визуализировать топики типа `TwistStamped` (скорость), `CameraInfo`, `PolygonArray` и многое другое. Для установки используйте команду:
```bash ```bash
sudo apt-get install ros-melodic-jsk-visualization sudo apt-get install ros-melodic-jsk-visualization

View File

@@ -16,32 +16,39 @@
<img src="../assets/pix-sd.png" alt="Pixracer и MicroSD-карта" class="zoom center" width=400> <img src="../assets/pix-sd.png" alt="Pixracer и MicroSD-карта" class="zoom center" width=400>
1. Установите карту в компьютер (используйте адаптер при необходимости). * Установите карту в компьютер (используйте адаптер при необходимости).
2. Отформатируйте карту в файловую систему FAT32. Для этого кликните на значок SD-карты в "Проводнике" и нажмите "Форматирование" в Windows. Используйте "Дисковую утилиту" в macOS. * Отформатируйте карту в файловую систему FAT32. Для этого кликните на значок SD-карты в "Проводнике" и нажмите "Форматирование" в Windows. Используйте "Дисковую утилиту" в macOS.
3. Выполните "Безопасное извлечение" карты, извлеките карту. * Выполните "Безопасное извлечение" карты, извлеките карту.
4. Установите карту в полетный контроллер. * Установите карту в полетный контроллер.
## Загрузка прошивки в полетный контроллер ## Загрузка прошивки в полетный контроллер
Наиболее оттестированной, в особенности для осуществления автономных полетов, является [версия прошивки с патчами COEX](firmware.md). Скачайте актуальную версию прошивки на GitHub — **<a class="latest-firmware v4" href="https://github.com/CopterExpress/Firmware/releases">скачать</a>**. Основная статья: https://docs.qgroundcontrol.com/en/SetupView/Firmware.html.
Для использования всех наиболее актуальных функций PX4 вы также можете использовать последнюю официальную версию прошивки (в экспериментальном режиме). > **Note** Перед осуществлением перепрошивки Pixracer не должен быть подключен к компьютеру по USB.
1. Отключите полетный контроллер от компьютера (если он подключен). Для Клевера, в особенности для осуществления автономных полетов, рекомендуется использовать версию прошивки PX4 от Copter Express. Скачайте актуальную версию прошивки на GitHub — **<a class="latest-firmware v4" href="https://github.com/CopterExpress/Firmware/releases">скачать</a>**.
2. Запустите программу QGroundControl.
3. Перейдите в панель *Vehicle Setup* (кликнув на логотип QGroundControl в левом верхнем углу) и выберите меню *Firmware*.
4. Подключите полетный контроллер к компьютеру по USB.
5. Выберите в появившемся меню справа *PX4 Flight Stack*.
<img src="../assets/qgc-firmware.png" alt="QGroundControl firmware upload" class="zoom"> > **Info** Для квадрокоптеров с Pixhawk (Клевер 2) существует отдельная версия прошивки. Подробности смотрите в статье "[Прошивка полетного контроллера](firmware.md)".
6. Для загрузки **прошивки COEX**: Загрузите прошивку в полетный контролер:
* Выберите *Advanced settings*. <img src="../assets/qgc-firmware.png" alt="QGroundControl firmware upload" class="zoom">
* В выпадающем меню выберите *Custom firmware file...*
* Нажмите *OK* и выберите скаченный файл прошивки.
Для загрузки последней версии **стандартной прошивки** сразу нажмите *OK*. 1. Запустите программу QGroundControl.
2. Зайдите во вкладку *Vehicle Setup*.
3. Выберите меню *Firmware*.
4. Подключите Pixracer к компьютеру по USB.
5. Дождитесь подключения Pixracer к QGroundControl.
6. Выберите в меню справа *PX4 Flight Stack*.
Для загрузки прошивки от Copter Express (рекомендуется):
* Выберите *Advanced settings*.
* В выпадающем меню выберите *Custom firmware file...*
* Нажмите *OK* и выберите скаченный файл прошивки.
Для загрузки последней версии стандартной прошивки сразу нажмите *OK*.
Дождитесь, пока QGroundControl загрузит прошивку и выполнит перезагрузку полетного контроллера. Дождитесь, пока QGroundControl загрузит прошивку и выполнит перезагрузку полетного контроллера.
@@ -75,7 +82,7 @@
### Параметры ### Параметры
Для настройки параметров полетного контроллера войдите во вкладку *Vehicle Setup* и выберите меню *Parameters*. Вы можете использовать поле *Search* для поиска параметров по имени. Рекомендуемые параметры для Клевера приведены в дальнейшей документации а также в соответствующей [сводной статье](parameters.md). Для настройки параметров полетного контроллера войдите во вкладку *Vehicle Setup* и выберите меню *Parameters*. Вы можете использовать поле *Search* для поиска параметров по имени.
<img src="../assets/qgc-parameters.png" alt="QGroundControl parameters" class="zoom"> <img src="../assets/qgc-parameters.png" alt="QGroundControl parameters" class="zoom">

View File

@@ -1,4 +1,11 @@
# Автономный полет Автономный полет (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). Модуль `simple_offboard` пакета `clover` предназначен для упрощенного программирования автономного полета дрона ([режим](modes.md) `OFFBOARD`). Он позволяет устанавливать желаемые полетные задачи и автоматически трансформирует [систему координат](frames.md).
@@ -6,7 +13,8 @@
Основные сервисы [`get_telemetry`](#gettelemetry) (получение телеметрии), [`navigate`](#navigate) (полет в заданную точку по прямой), [`navigate_global`](#navigateglobal) (полет в глобальную точку по прямой), [`land`](#land) (переход в режим посадки). Основные сервисы [`get_telemetry`](#gettelemetry) (получение телеметрии), [`navigate`](#navigate) (полет в заданную точку по прямой), [`navigate_global`](#navigateglobal) (полет в глобальную точку по прямой), [`land`](#land) (переход в режим посадки).
## Использование из языка Python Использование из языка Python
---
Для использования сервисов, необходимо создать объекты-прокси к ним. Используйте этот шаблон для вашей программы: Для использования сервисов, необходимо создать объекты-прокси к ним. Используйте этот шаблон для вашей программы:
@@ -29,7 +37,8 @@ land = rospy.ServiceProxy('land', Trigger)
Неиспользуемые функции-прокси можно удалить из кода. Неиспользуемые функции-прокси можно удалить из кода.
## Описание API Описание API
---
> **Note** Незаполненные числовые параметры устанавливаются в значение 0. > **Note** Незаполненные числовые параметры устанавливаются в значение 0.
@@ -286,7 +295,7 @@ set_velocity(vx=1, vy=0.0, vz=0, frame_id='body')
Перевести коптер в [режим](modes.md) посадки (`AUTO.LAND` или аналогичный). Перевести коптер в [режим](modes.md) посадки (`AUTO.LAND` или аналогичный).
> **Note** Для автоматического отключения винтов после посадки [параметр PX4](parameters.md) `COM_DISARM_LAND` должен быть установлен в значение > 0. > **Note** Для автоматического отключения винтов после посадки [параметр PX4](px4_parameters.md) `COM_DISARM_LAND` должен быть установлен в значение > 0.
Посадка коптера: Посадка коптера:
@@ -303,9 +312,14 @@ if res.success:
rosservice call /land "{}" rosservice call /land "{}"
``` ```
> **Caution** В более новых версиях PX4 коптер выйдет из режима LAND в ручной режим, если сильно перемещать стики. <!--
### release
## Дополнительные материалы Перестать публиковать setpoint'ы коптеру (отпустить управление). Необходим для продолжения контроля средствами [MAVROS](mavros.md).
-->
Дополнительные материалы
------------------------
* [Полеты в поле ArUco-маркеров](aruco.md). * [Полеты в поле ArUco-маркеров](aruco.md).
* [Примеры программ и сниппеты](snippets.md). * [Примеры программ и сниппеты](snippets.md).

View File

@@ -4,40 +4,16 @@
> **Hint** Смотрите актуальный набор команд установки необходимого ПО для запуска симулятора Клевера в скрипте сборки виртуальной машины с симулятором: [`install_software.sh`](https://github.com/CopterExpress/clover_vm/blob/master/scripts/install_software.sh). > **Hint** Смотрите актуальный набор команд установки необходимого ПО для запуска симулятора Клевера в скрипте сборки виртуальной машины с симулятором: [`install_software.sh`](https://github.com/CopterExpress/clover_vm/blob/master/scripts/install_software.sh).
Требования для сборки: **Ubuntu 20.04**. Требования для сборки: Ubuntu 20.04 и [ROS Noetic](http://wiki.ros.org/noetic/Installation/Ubuntu).
## Установка ROS
Установите ROS Noetic используя [официальную документацию по установке](http://wiki.ros.org/noetic/Installation/Ubuntu) (Desktop или Full установка).
Добавьте выполнение инициализирующего скрипта ROS `setup.bash` в ваш файл `.bashrc`:
```bash
echo "source /opt/ros/noetic/setup.bash" >> ~/.bashrc
source ~/.bashrc
```
Установите необходимые инструменты, которые понадобятся для дальнейшей установки:
```bash
sudo apt install build-essential git python3-pip python3-rosdep
```
## Создание рабочего пространства для симулятора ## Создание рабочего пространства для симулятора
Создайте рабочее пространство: В этой статье мы будем использовать `catkin_ws` как имя рабочего пространства (вы можете поменять её). Мы создадим её в домашнем каталоге текущего пользователя (`~`).
Создайте рабочее пространство и загрузите исходный код Клевера:
```bash ```bash
mkdir -p ~/catkin_ws/src mkdir -p ~/catkin_ws/src
cd ~/catkin_ws
catkin_make
echo "source ~/catkin_ws/devel/setup.bash" >> ~/.bashrc
source ~/.bashrc
```
Склонируйте исходный код пакетов Clover:
```bash
cd ~/catkin_ws/src cd ~/catkin_ws/src
git clone --depth 1 https://github.com/CopterExpress/clover git clone --depth 1 https://github.com/CopterExpress/clover
git clone --depth 1 https://github.com/CopterExpress/ros_led git clone --depth 1 https://github.com/CopterExpress/ros_led
@@ -48,7 +24,6 @@ git clone --depth 1 https://github.com/ethz-asl/mav_comm
```bash ```bash
cd ~/catkin_ws cd ~/catkin_ws
sudo rosdep init
rosdep update rosdep update
rosdep install --from-paths src --ignore-src -y rosdep install --from-paths src --ignore-src -y
``` ```
@@ -61,19 +36,15 @@ sudo /usr/bin/python3 -m pip install -r ~/catkin_ws/src/clover/clover/requiremen
## Загрузка исходного кода PX4 ## Загрузка исходного кода PX4
Сборка PX4 будет осуществлена вместе с другими пакетами в нашем рабочем пространстве. Вы можете загрузить его прямо в рабочее пространство или поместить куда-нибудь и создать симлинк к `~/catkin_ws/src`. Нам также нужно будет поместить его подмодули `sitl_gazebo` и `mavlink` в `~/catkin_ws/src`. Сборка PX4 будет осуществлена вместе с другими пакетами в нашем рабочем пространстве. Вы можете загрузить его прямо в рабочее пространство или поместить куда-нибудь и создать симлинк к `~/catkin_ws/src`. Нам также нужно будет поместить его подмодуль `sitl_gazebo` в `~/catkin_ws/src`. Для упрощения мы загрузим прошивку прямо в рабочее пространство:
Склонируйте исходный код PX4 и создайте необходимые симлинки:
```bash ```bash
cd ~/catkin_ws/src
git clone --recursive --depth 1 --branch v1.12.0 https://github.com/PX4/PX4-Autopilot.git ~/PX4-Autopilot git clone --recursive --depth 1 --branch v1.12.0 https://github.com/PX4/PX4-Autopilot.git ~/PX4-Autopilot
ln -s ~/PX4-Autopilot ~/catkin_ws/src/ ln -s ~/PX4-Autopilot ~/catkin_ws/src/PX4-Autopilot
ln -s ~/PX4-Autopilot/Tools/sitl_gazebo ~/catkin_ws/src/ ln -s ~/PX4-Autopilot/Tools/sitl_gazebo ~/catkin_ws/src/sitl_gazebo
ln -s ~/PX4-Autopilot/mavlink ~/catkin_ws/src/
``` ```
> **Hint** Вы можете использовать более позднюю версию PX4 с большим риском, что что-то не заработает.
## Установка зависимостей PX4 ## Установка зависимостей PX4
PX4 имеет свой собственный скрипт для установки зависимостей. Воспользуемся им: PX4 имеет свой собственный скрипт для установки зависимостей. Воспользуемся им:
@@ -85,12 +56,10 @@ sudo ./ubuntu.sh
Он установит все, что нужно для сборки PX4 и SITL. Он установит все, что нужно для сборки PX4 и SITL.
> **Hint** Также вы можете пропустить установку ARM тулчейна, если вы не планируете компилировать PX4 для вашего полетного контроллера. Для этого воспользуйтесь флагом `--no-nuttx`: `sudo ./ubuntu.sh --no-nuttx`. Также вы можете пропустить установку ARM тулчейна, если вы не планируете компилировать PX4 для вашего полетного контроллера. Для этого воспользуйтесь флагом `--no-nuttx`:
Установите дополнительные необходимые Python-пакеты: ```
sudo ./ubuntu.sh --no-nuttx
```bash
pip3 install --user toml
``` ```
## Добавление рамы Клевера ## Добавление рамы Клевера
@@ -98,7 +67,7 @@ pip3 install --user toml
Добавьте в PX4 раму Клевера с помощью следующей команды: Добавьте в PX4 раму Клевера с помощью следующей команды:
```bash ```bash
ln -s ~/catkin_ws/src/clover/clover_simulation/airframes/* ~/PX4-Autopilot/ROMFS/px4fmu_common/init.d-posix/airframes/ ln -s "$(catkin_find clover_simulation airframes)"/* ~/PX4-Autopilot/ROMFS/px4fmu_common/init.d-posix/airframes/
``` ```
## Установка датасетов geographiclib ## Установка датасетов geographiclib
@@ -118,37 +87,13 @@ cd ~/catkin_ws
catkin_make catkin_make
``` ```
> **Note** Если процесс сборки завершится с ошибкой, связанной с недостатком памяти (`c++: fatal error: Killed signal terminated program cc1plus`), уменьшите количество параллельно исполняемых процессов используя ключ `-j`. Например, чтобы использовать только два параллельных процесса используйте команду `catkin_make -j2`. > **Note** Некоторые файлы, особенно плагины Gazebo, требуют большого объема оперативной памяти для сборки. Вы можете уменьшить количество параллельных процессов; количество параллельных процессов должно быть равно объёму RAM в гигабайтах, поделенному на 2. Например, для машины с 16Гб следует указывать не более 8 процессов. Вы можете указать количество процессов, используя флаг `-j` : ```catkin_make -j8```
## Запуск симулятора ## Запуск симулятора
Чтобы удостовериться в том, что все было собрано корректно, попробуйте запустить симулятор: Чтобы удостовериться в том, что все было собрано корректно, попробуйте запустить симулятор:
```bash ```bash
source ~/catkin_ws/devel/setup.bash
roslaunch clover_simulation simulator.launch roslaunch clover_simulation simulator.launch
``` ```
Вы можете проверить автономный полет используя скрипты в директории `~/catkin_ws/src/clover/clover/examples`.
## Дополнительные шаги
Опционально вы можете установить systemd-сервис для roscore для того, чтобы roscore был постоянно запущен в фоне:
```bash
sed -i "s/pi/$USER/g" ~/catkin_ws/src/clover/builder/assets/roscore.service
sudo cp ~/catkin_ws/src/clover/builder/assets/roscore.service /etc/systemd/system
sudo systemctl enable roscore
sudo systemctl start roscore
```
Установите любой веб-сервер, чтобы раздавать веб-инструменты Клевера (директория `~/.ros/www`), например, Monkey:
```bash
wget https://github.com/CopterExpress/clover_vm/raw/master/assets/packages/monkey_1.6.9-1_amd64.deb -O /tmp/monkey_1.6.9-1_amd64.deb
sudo apt-get install -y /tmp/monkey_1.6.9-1_amd64.deb
sed "s/pi/$USER/g" ~/catkin_ws/src/clover/builder/assets/monkey | sudo tee /etc/monkey/sites/default
sudo -E sh -c "sed -i 's/SymLink Off/SymLink On/' /etc/monkey/monkey.conf"
sudo cp ~/catkin_ws/src/clover/builder/assets/monkey.service /etc/systemd/system/monkey.service
sudo systemctl enable monkey
sudo systemctl start monkey
```

View File

@@ -77,7 +77,7 @@ GPS датчик необходим полетов с использование
### Выставление скорости симуляции ### Выставление скорости симуляции
PX4, начиная с версии 1.9, поддерживает [принудительную установку скорости симуляции](https://docs.px4.io/master/en/simulation/#run-simulation-faster-than-realtime) с помощью переменной окружения `PX4_SIM_SPEED_FACTOR`. Выставление этой переменной подготавливает все компоненты симулятора к соответствующему ускорению/замедлению. PX4, начиная с версии 1.9, поддерживает [принудительную установку скорости симуляции](https://dev.px4.io/v1.9.0/en/simulation/#simulation_speed) с помощью переменной окружения `PX4_SIM_SPEED_FACTOR`. Выставление этой переменной подготавливает все компоненты симулятора к соответствующему ускорению/замедлению.
Значение этой переменной должно соответствовать величине Real Time Factor (скорости симуляции по отношению к реальному времени), получаемой при использовании `throttling_camera`. Величина Real Time Factor отображается в окне Gazebo на нижней панели: Значение этой переменной должно соответствовать величине Real Time Factor (скорости симуляции по отношению к реальному времени), получаемой при использовании `throttling_camera`. Величина Real Time Factor отображается в окне Gazebo на нижней панели:

View File

@@ -4,7 +4,7 @@
Основная статья: https://dev.px4.io/en/simulation/ Основная статья: https://dev.px4.io/en/simulation/
Симуляция PX4 возможна в ОС GNU/Linux и macOS с использованием систем симуляции физической среды [jMAVSim](https://docs.px4.io/master/en/simulation/jmavsim.html) и [Gazebo](http://gazebosim.org). Симуляция PX4 возможна в ОС GNU/Linux и macOS с использованием систем симуляции физической среды [jMAVSim](https://pixhawk.org/dev/hil/jmavsim) и [Gazebo](http://gazebosim.org).
jMAVSim является легковесной средой, предназначенной только для тестирование мультироторных летательных систем; Gazebo универсальная среда для любых типов роботов. jMAVSim является легковесной средой, предназначенной только для тестирование мультироторных летательных систем; Gazebo универсальная среда для любых типов роботов.

View File

@@ -14,7 +14,7 @@
* Пакеты [ROS](http://www.ros.org/), требуемые для запуска нод Клевера * Пакеты [ROS](http://www.ros.org/), требуемые для запуска нод Клевера
* Собранный для симулятора PX4 * Собранный для симулятора PX4
* Легковесный web-интерфейс для Gazebo [Gzweb](http://gazebosim.org/gzweb.html) * Легковесный web-интерфейс для Gazebo [Gzweb](http://gazebosim.org/gzweb.html)
* Web-терминал [Butterfly](https://github.com/paradoxxxzero/butterfly) * Web-терминал [Butterfly](http://paradoxxxzero.github.io/2014/02/28/butterfly.html)
## Предварительная настройка ## Предварительная настройка

View File

@@ -17,11 +17,13 @@
<a name="block-takeoff"></a><!-- old name of anchor --> <a name="block-takeoff"></a><!-- old name of anchor -->
Функция для полета в точку и ожидание окончания полета: Полет в точку и ожидание окончания полета:
```python ```python
import math 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): 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) navigate(x=x, y=y, z=z, yaw=yaw, speed=speed, frame_id=frame_id, auto_arm=auto_arm)
@@ -72,6 +74,8 @@ land_wait()
```python ```python
import math import math
# ...
def wait_arrival(tolerance=0.2): def wait_arrival(tolerance=0.2):
while not rospy.is_shutdown(): while not rospy.is_shutdown():
telem = get_telemetry(frame_id='navigate_target') telem = get_telemetry(frame_id='navigate_target')
@@ -87,6 +91,8 @@ def wait_arrival(tolerance=0.2):
```python ```python
import math import math
# ...
def get_distance(x1, y1, z1, x2, y2, z2): def get_distance(x1, y1, z1, x2, y2, z2):
return math.sqrt((x1 - x2) ** 2 + (y1 - y2) ** 2 + (z1 - z2) ** 2) return math.sqrt((x1 - x2) ** 2 + (y1 - y2) ** 2 + (z1 - z2) ** 2)
``` ```
@@ -98,6 +104,8 @@ def get_distance(x1, y1, z1, x2, y2, z2):
```python ```python
import math import math
# ...
def get_distance_global(lat1, lon1, lat2, lon2): def get_distance_global(lat1, lon1, lat2, lon2):
return math.hypot(lat1 - lat2, lon1 - lon2) * 1.113195e5 return math.hypot(lat1 - lat2, lon1 - lon2) * 1.113195e5
``` ```
@@ -213,16 +221,19 @@ from geometry_msgs.msg import PoseStamped, TwistStamped
from sensor_msgs.msg import BatteryState from sensor_msgs.msg import BatteryState
from mavros_msgs.msg import RCIn from mavros_msgs.msg import RCIn
# ...
def pose_update(pose): def pose_update(pose):
# Обработка новых данных о позиции коптера # Обработка новых данных о позиции коптера
pass pass
# Остальные функции-обработчики
# ...
rospy.Subscriber('/mavros/local_position/pose', PoseStamped, pose_update) rospy.Subscriber('/mavros/local_position/pose', PoseStamped, pose_update)
rospy.Subscriber('/mavros/local_position/velocity', TwistStamped, velocity_update) rospy.Subscriber('/mavros/local_position/velocity', TwistStamped, velocity_update)
rospy.Subscriber('/mavros/battery', BatteryState, battery_update) rospy.Subscriber('/mavros/battery', BatteryState, battery_update)
rospy.Subscriber('mavros/rc/in', RCIn, rc_callback) rospy.Subscriber('mavros/rc/in', RCIn, rc_callback)
rospy.spin()
``` ```
Информацию по топикам MAVROS см. по [ссылке](mavros.md). Информацию по топикам MAVROS см. по [ссылке](mavros.md).
@@ -236,10 +247,14 @@ rospy.spin()
Пример отправки произвольного [MAVLink-сообщения](mavlink.md) коптеру: Пример отправки произвольного [MAVLink-сообщения](mavlink.md) коптеру:
```python ```python
# ...
from mavros_msgs.msg import Mavlink from mavros_msgs.msg import Mavlink
from mavros import mavlink from mavros import mavlink
from pymavlink import mavutil from pymavlink import mavutil
# ...
mavlink_pub = rospy.Publisher('mavlink/to', Mavlink, queue_size=1) mavlink_pub = rospy.Publisher('mavlink/to', Mavlink, queue_size=1)
# Отправка сообщения HEARTBEAT: # Отправка сообщения HEARTBEAT:
@@ -284,6 +299,8 @@ rospy.spin()
```python ```python
from mavros_msgs.srv import SetMode from mavros_msgs.srv import SetMode
# ...
set_mode = rospy.ServiceProxy('mavros/set_mode', SetMode) set_mode = rospy.ServiceProxy('mavros/set_mode', SetMode)
# ... # ...
@@ -298,6 +315,8 @@ set_mode(custom_mode='STABILIZED')
```python ```python
import math import math
# ...
PI_2 = math.pi / 2 PI_2 = math.pi / 2
def flip(): def flip():
@@ -336,6 +355,8 @@ from pymavlink import mavutil
from mavros_msgs.srv import CommandLong from mavros_msgs.srv import CommandLong
from mavros_msgs.msg import State from mavros_msgs.msg import State
# ...
send_command = rospy.ServiceProxy('/mavros/cmd/command', CommandLong) send_command = rospy.ServiceProxy('/mavros/cmd/command', CommandLong)
def calibrate_gyro(): def calibrate_gyro():
@@ -369,14 +390,16 @@ calibrate_gyro()
import rospy import rospy
import dynamic_reconfigure.client import dynamic_reconfigure.client
# ...
client = dynamic_reconfigure.client.Client('aruco_detect') client = dynamic_reconfigure.client.Client('aruco_detect')
# Включить распознавание маркеров # Turn markers recognition off
client.update_configuration({'enabled': False}) client.update_configuration({'enabled': False})
rospy.sleep(5) rospy.sleep(5)
# Выключить распознавание маркеров # Turn markers recognition on
client.update_configuration({'enabled': True}) client.update_configuration({'enabled': True})
``` ```
@@ -387,42 +410,10 @@ client.update_configuration({'enabled': True})
```python ```python
import math import math
# ...
while not rospy.is_shutdown(): while not rospy.is_shutdown():
if math.isfinite(get_telemetry().lat): if math.isfinite(get_telemetry().lat):
break break
rospy.sleep(0.2) rospy.sleep(0.2)
``` ```
### # {#get-param}
Считать параметр полетного контроллера:
```python
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
# Считать параметр типа FLOAT
value = param_get(param_id='MPC_Z_P').value.float
```
### # {#set-param}
Изменить параметр полетного контроллера:
```python
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))
# Изменить параметр типа FLOAT:
param_set(param_id='MPC_Z_P', value=ParamValue(real=1.5))
```

View File

@@ -1,25 +0,0 @@
# Конкурс на лучшее образовательное видео по сборке и настройке
Требования:
- видео содержит весь процесс сборки и настройки конструктора Клевер 4.2: от открытия коробки с компонентами до летающего Коптера в режиме Position по ArUco-маркерам;
- видео загружено на YouTube и находится в открытом доступе;
- видео содержит озвучивание и субтитры на русском языке;
- видео длится от 6 до 60 минут.
Даты проведения конкурса: 12 февраля 13 декабря 2021.
## Призы
- 🥇 1 место: $500.
- 🥈 2 место: $300.
- 🥉 3 место: $200.
## Результаты
|Место|Участник|Ссылка на видео|
|:-:|-|-|
|1|🇷🇺 Филипп Баталин|https://www.youtube.com/watch?v=f0rpdulOSEk|
|2|🇮🇹 Sara Pettinari|https://www.youtube.com/watch?v=PxxfyVH6RRA|
|3|🇲🇾 Kai Feng Chew|https://www.youtube.com/watch?v=skgSwFle6Ms|
|3|🇰🇿 Никита Лобанов|https://www.youtube.com/watch?v=93b1epEM3SQ|

View File

@@ -63,11 +63,8 @@
{ "from": "power/", "to": "en/power.html" }, { "from": "power/", "to": "en/power.html" },
{ "from": "connection/", "to": "en/connection.html" }, { "from": "connection/", "to": "en/connection.html" },
{ "from": "clover_vm/", "to": "en/simulation_vm.html" }, { "from": "clover_vm/", "to": "en/simulation_vm.html" },
{ "from": "gpio/", "to": "en/gpio.html" },
{ "from": "ru/microsd_images.html", "to": "image.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" }
] ]
} }

View File

@@ -1,7 +1,7 @@
<?xml version="1.0"?> <?xml version="1.0"?>
<package format="2"> <package format="2">
<name>roswww_static</name> <name>roswww_static</name>
<version>0.23.0</version> <version>0.21.1</version>
<description>Static web pages for ROS packages</description> <description>Static web pages for ROS packages</description>
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer> <maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>
<license>MIT</license> <license>MIT</license>