Compare commits
1 Commits
vuepress
...
web-params
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
2930eb9c22 |
14
.github/workflows/build.yml
vendored
@@ -7,13 +7,13 @@ on:
|
||||
branches: [ master ]
|
||||
|
||||
jobs:
|
||||
# melodic:
|
||||
# runs-on: ubuntu-latest
|
||||
# steps:
|
||||
# - uses: actions/checkout@v2
|
||||
# - name: Native Melodic build
|
||||
# run: |
|
||||
# docker run --rm -v $(pwd):/root/catkin_ws/src/clover ros:melodic-ros-base /root/catkin_ws/src/clover/builder/standalone-install.sh
|
||||
melodic:
|
||||
runs-on: ubuntu-latest
|
||||
steps:
|
||||
- uses: actions/checkout@v2
|
||||
- name: Native Melodic build
|
||||
run: |
|
||||
docker run --rm -v $(pwd):/root/catkin_ws/src/clover ros:melodic-ros-base /root/catkin_ws/src/clover/builder/standalone-install.sh
|
||||
noetic:
|
||||
runs-on: ubuntu-latest
|
||||
steps:
|
||||
|
||||
17
.github/workflows/docs.yml
vendored
@@ -10,10 +10,6 @@ jobs:
|
||||
docs:
|
||||
runs-on: ubuntu-18.04
|
||||
steps:
|
||||
- name: Cancel previous runs
|
||||
uses: styfle/cancel-workflow-action@0.9.1
|
||||
with:
|
||||
access_token: ${{ github.token }}
|
||||
- uses: actions/checkout@v2
|
||||
- name: Use Node.js
|
||||
uses: actions/setup-node@v1
|
||||
@@ -38,11 +34,7 @@ jobs:
|
||||
gitbook install
|
||||
gitbook build
|
||||
- name: Generate PDF
|
||||
id: generate-pdf
|
||||
env:
|
||||
GITBOOK_SKIP_PDF: ${{ secrets.GITBOOK_SKIP_PDF }}
|
||||
continue-on-error: ${{ env.GITBOOK_SKIP_PDF != '' }}
|
||||
if: ${{ github.event_name == 'push' }}
|
||||
if: ${{ github.event_name == 'push' && github.ref == 'refs/heads/master' }}
|
||||
run: |
|
||||
for i in 1 2 3 4; do gitbook pdf ./ _book/clover.pdf && break || sleep 1; done
|
||||
sudo apt-get -q install ghostscript
|
||||
@@ -51,13 +43,6 @@ jobs:
|
||||
rm _book/clover_ru.pdf && mv _book/clover_ru_compressed.pdf _book/clover_ru.pdf
|
||||
rm _book/clover_en.pdf && mv _book/clover_en_compressed.pdf _book/clover_en.pdf
|
||||
ls -lah _book/clover*.pdf
|
||||
echo '::set-output name=GITBOOK_PDF_OK::1'
|
||||
- name: Download older PDFs
|
||||
if: ${{ !steps.generate-pdf.outputs.GITBOOK_PDF_OK }}
|
||||
run: |
|
||||
rm _book/clover*.pdf
|
||||
wget --no-verbose https://clover.coex.tech/clover_ru.pdf -P _book/
|
||||
wget --no-verbose https://clover.coex.tech/clover_en.pdf -P _book/
|
||||
- name: Deploy
|
||||
uses: JamesIves/github-pages-deploy-action@4.1.3
|
||||
if: ${{ github.event_name == 'push' && github.ref == 'refs/heads/master' }}
|
||||
|
||||
2
.github/workflows/editorconfig.yaml
vendored
@@ -15,4 +15,4 @@ jobs:
|
||||
run: |
|
||||
wget --no-verbose https://github.com/okalachev/editorconfig-checker/releases/download/1.2.1-disable-spaces-amount/ec-linux-amd64
|
||||
chmod +x ec-linux-amd64
|
||||
./ec-linux-amd64 -spaces-after-tabs -e "roslib.js|ros3d.js|eventemitter2.js|json-to-pretty-yaml.js|draw.cpp|BinUtils.swift|\.idea|apps/android/app|blockly/|clover_blocks/programs/|highlight/|python.js|Assets.xcassets|test_parser_pass.txt|test_node_failure.txt|aruco_pose/vendor|\.stl|\.dxf|\.dae|\.material"
|
||||
./ec-linux-amd64 -spaces-after-tabs -e "roslib.js|ros3d.js|eventemitter2.js|json-to-pretty-yaml.js|draw.cpp|BinUtils.swift|\.idea|apps/android/app|blockly/|clover_blocks/programs/|highlight/|python.js|Assets.xcassets|test_parser_pass.txt|test_node_failure.txt|aruco_pose/vendor|\.stl|\.dxf|\.dae"
|
||||
|
||||
3
.gitignore
vendored
@@ -7,6 +7,3 @@ package-lock.json
|
||||
clover_blocks/programs/*.*
|
||||
!clover_blocks/programs/examples/*
|
||||
/.vscode/
|
||||
docs/.vuepress/.cache/
|
||||
docs/.vuepress/.temp/
|
||||
docs/.vuepress/dist
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>aruco_pose</name>
|
||||
<version>0.23.0</version>
|
||||
<version>0.21.1</version>
|
||||
<description>Positioning with ArUco markers</description>
|
||||
|
||||
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>
|
||||
|
||||
@@ -30,7 +30,7 @@ Options:
|
||||
-o <filename> Output map file name in the 'map' subdirectory of aruco_pose package
|
||||
|
||||
Example:
|
||||
rosrun aruco_pose genmap.py 0.33 2 4 1 1 0 -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
|
||||
|
||||
@@ -13,7 +13,7 @@
|
||||
# copies or substantial portions of the Software.
|
||||
#
|
||||
|
||||
set -ex # exit on error, echo commands
|
||||
set -e # Exit immidiately on non-zero result
|
||||
|
||||
REPO=$1
|
||||
REF=$2
|
||||
@@ -90,7 +90,7 @@ echo_stamp "Installing OpenCV 4.2-compatible ROS packages"
|
||||
apt install -y --no-install-recommends \
|
||||
ros-${ROS_DISTRO}-compressed-image-transport=1.14.0-0buster \
|
||||
ros-${ROS_DISTRO}-cv-bridge=1.15.0-0buster \
|
||||
ros-${ROS_DISTRO}-cv-camera=0.5.1-0buster \
|
||||
ros-${ROS_DISTRO}-cv-camera=0.5.0-0buster \
|
||||
ros-${ROS_DISTRO}-image-publisher=1.15.3-0buster \
|
||||
ros-${ROS_DISTRO}-web-video-server=0.2.1-0buster
|
||||
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
|
||||
source /opt/ros/${ROS_DISTRO}/setup.bash
|
||||
# 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
|
||||
|
||||
echo_stamp "Install clever package (for backwards compatibility)"
|
||||
|
||||
@@ -137,8 +137,6 @@ pip3 --version
|
||||
echo_stamp "Install and enable Butterfly (web terminal)"
|
||||
echo_stamp "Workaround for tornado >= 6.0 breaking butterfly"
|
||||
export CRYPTOGRAPHY_DONT_BUILD_RUST=1
|
||||
my_travis_retry pip3 install cryptography==3.4.6 # https://stackoverflow.com/a/68472128/6850197
|
||||
my_travis_retry pip3 install pyOpenSSL==20.0.1
|
||||
my_travis_retry pip3 install tornado==5.1.1
|
||||
my_travis_retry pip3 install butterfly
|
||||
my_travis_retry pip3 install butterfly[systemd]
|
||||
|
||||
@@ -58,9 +58,5 @@ rosversion rosshow
|
||||
rosversion nodelet
|
||||
rosversion image_view
|
||||
|
||||
# validate some versions
|
||||
[[ $(rosversion cv_camera) == "0.5.1" ]] # patched version with init fix
|
||||
[[ $(rosversion ws281x) == "0.0.12" ]]
|
||||
|
||||
# validate examples are present
|
||||
[[ $(ls /home/pi/examples/*) ]]
|
||||
|
||||
@@ -8,11 +8,8 @@
|
||||
|
||||
<!-- For additional help go to https://clover.coex.tech/aruco -->
|
||||
|
||||
<arg name="force_init" default="false"/>
|
||||
<arg name="disable" default="false"/> <!-- only force init -->
|
||||
|
||||
<!-- aruco_detect: detect aruco markers, estimate poses -->
|
||||
<node name="aruco_detect" pkg="nodelet" if="$(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="camera_info" to="main_camera/camera_info"/>
|
||||
<remap from="map_markers" to="aruco_map/markers"/>
|
||||
@@ -29,7 +26,7 @@
|
||||
</node>
|
||||
|
||||
<!-- 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="camera_info" to="main_camera/camera_info"/>
|
||||
<remap from="markers" to="aruco_detect/markers"/>
|
||||
@@ -44,11 +41,11 @@
|
||||
</node>
|
||||
|
||||
<!-- 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">
|
||||
<remap from="~pose_cov" to="aruco_map/pose" if="$(arg aruco_vpe)"/>
|
||||
<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"/>
|
||||
<remap from="~vpe" to="mavros/vision_pose/pose"/>
|
||||
<param name="frame_id" value="aruco_map_detected" if="$(arg aruco_vpe)"/>
|
||||
<param name="force_init" value="$(arg force_init)"/>
|
||||
<param name="frame_id" value="aruco_map_detected"/>
|
||||
<param name="publish_zero" value="true"/>
|
||||
<param name="offset_frame_id" value="aruco_map"/>
|
||||
</node>
|
||||
</launch>
|
||||
|
||||
@@ -12,7 +12,6 @@
|
||||
<arg name="led" default="true"/>
|
||||
<arg name="blocks" default="false"/>
|
||||
<arg name="rc" default="false"/>
|
||||
<arg name="force_init" value="true"/> <!-- force estimator to init by publishing zero pose -->
|
||||
|
||||
<arg name="simulator" default="false"/> <!-- flag that we are operating on a simulated drone -->
|
||||
|
||||
@@ -34,10 +33,7 @@
|
||||
</node>
|
||||
|
||||
<!-- aruco markers -->
|
||||
<include file="$(find clover)/launch/aruco.launch" if="$(eval aruco or force_init)">
|
||||
<arg name="force_init" value="$(arg force_init)"/>
|
||||
<arg name="disable" value="$(eval not aruco)"/>
|
||||
</include>
|
||||
<include file="$(find clover)/launch/aruco.launch" if="$(arg aruco)"/>
|
||||
|
||||
<!-- 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">
|
||||
@@ -51,6 +47,9 @@
|
||||
|
||||
<!-- simplified offboard control -->
|
||||
<node name="simple_offboard" pkg="clover" type="simple_offboard" output="screen" clear_params="true">
|
||||
<param name="reference_frames/body" value="map"/>
|
||||
<param name="reference_frames/base_link" value="map"/>
|
||||
<param name="reference_frames/navigate_target" value="map"/>
|
||||
<param name="reference_frames/main_camera_optical" value="map"/>
|
||||
</node>
|
||||
|
||||
|
||||
@@ -39,7 +39,7 @@
|
||||
<rosparam command="load" file="$(find clover)/launch/mavros_config.yaml"/>
|
||||
|
||||
<!-- remap rangefinder -->
|
||||
<remap from="mavros/distance_sensor/rangefinder_sub" to="$(arg distance_sensor_remap)" if="$(eval bool(distance_sensor_remap))"/>
|
||||
<remap from="mavros/distance_sensor/rangefinder_sub" to="rangefinder/range"/>
|
||||
|
||||
<rosparam param="plugin_whitelist">
|
||||
- altitude
|
||||
|
||||
@@ -1,11 +1,11 @@
|
||||
# Config file for mavros
|
||||
# Based on https://raw.githubusercontent.com/mavlink/mavros/master/mavros/launch/px4_config.yaml
|
||||
|
||||
startup_px4_usb_quirk: false
|
||||
startup_px4_usb_quirk: true
|
||||
|
||||
conn:
|
||||
heartbeat_rate: 1.0 # send heartbeat rate in Hertz
|
||||
timeout: 10.0 # heartbeat timeout in seconds
|
||||
heartbeat_rate: 1.0 # send hertbeat rate in Hertz
|
||||
timeout: 10.0 # hertbeat timeout in seconds
|
||||
timesync_rate: 10.0 # TIMESYNC rate in Hertz (feature disabled if 0.0)
|
||||
system_time_rate: 1.0 # send system time to FCU rate in Hertz (disabled if 0.0)
|
||||
|
||||
@@ -13,7 +13,6 @@ time:
|
||||
time_ref_source: "fcu" # time_reference source
|
||||
timesync_mode: MAVLINK
|
||||
timesync_avg_alpha: 0.6 # timesync averaging factor
|
||||
publish_sim_time: false # don't publish /clock
|
||||
|
||||
global_position:
|
||||
frame_id: "map" # origin frame
|
||||
@@ -78,9 +77,6 @@ distance_sensor:
|
||||
field_of_view: 0.5
|
||||
rangefinder_sub:
|
||||
subscriber: true
|
||||
id: 1
|
||||
orientation: PITCH_270
|
||||
covariance: 1 # cm
|
||||
|
||||
# fake_gps
|
||||
fake_gps:
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
<?xml version="1.0"?>
|
||||
<package format="3">
|
||||
<name>clover</name>
|
||||
<version>0.23.0</version>
|
||||
<version>0.21.1</version>
|
||||
<description>The Clover package</description>
|
||||
|
||||
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>
|
||||
|
||||
@@ -53,7 +53,6 @@ private:
|
||||
std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
|
||||
std::unique_ptr<tf2_ros::TransformListener> tf_listener_;
|
||||
bool calc_flow_gyro_;
|
||||
float flow_gyro_default_;
|
||||
|
||||
void onInit()
|
||||
{
|
||||
@@ -70,7 +69,6 @@ private:
|
||||
roi_px_ = nh_priv.param("roi", 128);
|
||||
roi_rad_ = nh_priv.param("roi_rad", 0.0);
|
||||
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);
|
||||
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;
|
||||
|
||||
// Calculate flow gyro
|
||||
flow_.integrated_xgyro = flow_gyro_default_;
|
||||
flow_.integrated_ygyro = flow_gyro_default_;
|
||||
flow_.integrated_zgyro = flow_gyro_default_;
|
||||
flow_.integrated_xgyro = NAN;
|
||||
flow_.integrated_ygyro = NAN;
|
||||
flow_.integrated_zgyro = NAN;
|
||||
|
||||
if (calc_flow_gyro_) {
|
||||
try {
|
||||
|
||||
@@ -30,7 +30,6 @@ from visualization_msgs.msg import MarkerArray as VisualizationMarkerArray
|
||||
import tf.transformations as t
|
||||
from aruco_pose.msg import MarkerArray
|
||||
from mavros import mavlink
|
||||
import locale
|
||||
|
||||
|
||||
# TODO: check attitude is present
|
||||
@@ -44,10 +43,6 @@ import locale
|
||||
|
||||
rospy.init_node('selfcheck')
|
||||
|
||||
os.environ['ROSCONSOLE_FORMAT']='[${severity}]: ${message}'
|
||||
|
||||
# use user's locale to convert numbers, etc
|
||||
locale.setlocale(locale.LC_ALL, '')
|
||||
|
||||
tf_buffer = tf2_ros.Buffer()
|
||||
tf_listener = tf2_ros.TransformListener(tf_buffer)
|
||||
@@ -198,27 +193,24 @@ def check_fcu():
|
||||
failure('no connection to the FCU (check wiring)')
|
||||
return
|
||||
|
||||
clover_tag = re.compile(r'-cl[oe]ver\.\d+$')
|
||||
clover_fw = False
|
||||
|
||||
# Make sure the console is available to us
|
||||
mavlink_exec('\n')
|
||||
version_str = mavlink_exec('ver all')
|
||||
if version_str == '':
|
||||
info('no version data available from SITL')
|
||||
|
||||
for line in version_str.split('\n'):
|
||||
if line.startswith('FW version: '):
|
||||
info(line[len('FW version: '):])
|
||||
elif line.startswith('FW git tag: '): # only Clover's firmware
|
||||
tag = line[len('FW git tag: '):]
|
||||
clover_fw = clover_tag.search(tag)
|
||||
info(tag)
|
||||
elif line.startswith('HW arch: '):
|
||||
info(line[len('HW arch: '):])
|
||||
r = re.compile(r'^FW (git tag|version): (v?\d\.\d\.\d.*)$')
|
||||
is_clover_firmware = False
|
||||
for ver_line in version_str.split('\n'):
|
||||
match = r.search(ver_line)
|
||||
if match is not None:
|
||||
field, version = match.groups()
|
||||
info('firmware %s: %s' % (field, version))
|
||||
if 'clover' in version or 'clever' in version:
|
||||
is_clover_firmware = True
|
||||
|
||||
if not clover_fw:
|
||||
info('not Clover PX4 firmware, check https://clover.coex.tech/firmware')
|
||||
if not is_clover_firmware:
|
||||
failure('not running Clover PX4 firmware, https://clover.coex.tech/firmware')
|
||||
|
||||
est = get_param('SYS_MC_EST_GROUP')
|
||||
if est == 1:
|
||||
@@ -491,12 +483,6 @@ def check_local_position():
|
||||
failure('roll is %.2f deg; place copter horizontally or redo level horizon calib',
|
||||
math.degrees(roll))
|
||||
|
||||
if not tf_buffer.can_transform('base_link', pose.header.frame_id, rospy.get_rostime(), rospy.Duration(0.5)):
|
||||
failure('can\'t transform from %s to base_link (timeout 0.5 s): is TF enabled?', pose.header.frame_id)
|
||||
|
||||
if not tf_buffer.can_transform('body', pose.header.frame_id, rospy.get_rostime(), rospy.Duration(0.5)):
|
||||
failure('can\'t transform from %s to body (timeout 0.5 s)', pose.header.frame_id)
|
||||
|
||||
except rospy.ROSException:
|
||||
failure('no local position')
|
||||
|
||||
@@ -626,13 +612,13 @@ def check_boot_duration():
|
||||
output = subprocess.check_output('systemd-analyze').decode()
|
||||
r = re.compile(r'([\d\.]+)s\s*$', flags=re.MULTILINE)
|
||||
duration = float(r.search(output).groups()[0])
|
||||
if duration > 20:
|
||||
if duration > 15:
|
||||
failure('long Raspbian boot duration: %ss (systemd-analyze for analyzing)', duration)
|
||||
|
||||
|
||||
@check('CPU usage')
|
||||
def check_cpu_usage():
|
||||
WHITELIST = 'nodelet', 'gzclient', 'gzserver'
|
||||
WHITELIST = 'nodelet',
|
||||
CMD = "top -n 1 -b -i | tail -n +8 | awk '{ printf(\"%-8s\\t%-8s\\t%-8s\\n\", $1, $9, $12); }'"
|
||||
output = subprocess.check_output(CMD, shell=True).decode()
|
||||
processes = output.split('\n')
|
||||
@@ -641,7 +627,7 @@ def check_cpu_usage():
|
||||
continue
|
||||
pid, cpu, cmd = process.split('\t')
|
||||
|
||||
if cmd.strip() not in WHITELIST and locale.atof(cpu) > 30:
|
||||
if cmd.strip() not in WHITELIST and float(cpu) > 30:
|
||||
failure('high CPU usage (%s%%) detected: %s (PID %s)',
|
||||
cpu.strip(), cmd.strip(), pid.strip())
|
||||
|
||||
@@ -660,22 +646,13 @@ def check_clover_service():
|
||||
elif 'failed' in output:
|
||||
failure('service failed to run, check your launch-files')
|
||||
|
||||
BLACKLIST = 'Unexpected command 520', 'Time jump detected', 'different index:'
|
||||
|
||||
r = re.compile(r'^(.*)\[(FATAL|ERROR| WARN)\] \[\d+.\d+\]: (.*?)(\x1b(.*))?$')
|
||||
r = re.compile(r'^(.*)\[(FATAL|ERROR)\] \[\d+.\d+\]: (.*?)(\x1b(.*))?$')
|
||||
error_count = OrderedDict()
|
||||
try:
|
||||
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)
|
||||
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:
|
||||
error_count[msg] += 1
|
||||
else:
|
||||
@@ -746,14 +723,6 @@ def check_network():
|
||||
|
||||
@check('RPi health')
|
||||
def check_rpi_health():
|
||||
try:
|
||||
import shutil
|
||||
total, used, free = shutil.disk_usage('/')
|
||||
if free < 1024 * 1024 * 1024:
|
||||
failure('disk space is less than 1 GB; consider removing logs (~/.ros/log/)')
|
||||
except Exception as e:
|
||||
info('could not check the disk free space: %s', str(e))
|
||||
|
||||
# `vcgencmd get_throttled` output codes taken from
|
||||
# https://github.com/raspberrypi/documentation/blob/JamesH65-patch-vcgencmd-vcdbg-docs/raspbian/applications/vcgencmd.md#get_throttled
|
||||
# TODO: support more base platforms?
|
||||
@@ -784,7 +753,7 @@ def check_rpi_health():
|
||||
# with some of the FLAGs OR'ed together
|
||||
output = subprocess.check_output(['vcgencmd', 'get_throttled']).decode()
|
||||
except OSError:
|
||||
info('could not call vcgencmd binary; not a Raspberry Pi?')
|
||||
failure('could not call vcgencmd binary; not a Raspberry Pi?')
|
||||
return
|
||||
|
||||
throttle_mask = int(output.split('=')[1], base=16)
|
||||
|
||||
@@ -61,7 +61,6 @@ std::shared_ptr<tf2_ros::TransformBroadcaster> transform_broadcaster;
|
||||
std::shared_ptr<tf2_ros::StaticTransformBroadcaster> static_transform_broadcaster;
|
||||
|
||||
// Parameters
|
||||
string mavros;
|
||||
string local_frame;
|
||||
string fcu_frame;
|
||||
ros::Duration transform_timeout;
|
||||
@@ -182,7 +181,6 @@ inline bool waitTransform(const string& target, const string& source,
|
||||
ros::spinOnce();
|
||||
r.sleep();
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
#define TIMEOUT(msg, timeout) (msg.header.stamp.isZero() || (ros::Time::now() - msg.header.stamp > timeout))
|
||||
@@ -849,7 +847,6 @@ bool land(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
|
||||
busy = false;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
int main(int argc, char **argv)
|
||||
@@ -862,9 +859,8 @@ int main(int argc, char **argv)
|
||||
static_transform_broadcaster = std::make_shared<tf2_ros::StaticTransformBroadcaster>();
|
||||
|
||||
// Params
|
||||
nh_priv.param("mavros", mavros, string("mavros")); // for case of using multiple connections
|
||||
nh.param<string>(mavros + "/local_position/tf/frame_id", local_frame, "map");
|
||||
nh.param<string>(mavros + "/local_position/tf/child_frame_id", fcu_frame, "base_link");
|
||||
nh.param<string>("mavros/local_position/tf/frame_id", local_frame, "map");
|
||||
nh.param<string>("mavros/local_position/tf/child_frame_id", fcu_frame, "base_link");
|
||||
nh_priv.param("target_frame", target.child_frame_id, string("navigate_target"));
|
||||
nh_priv.param("setpoint", setpoint.child_frame_id, string("setpoint"));
|
||||
nh_priv.param("auto_release", auto_release, true);
|
||||
@@ -875,13 +871,6 @@ int main(int argc, char **argv)
|
||||
nh_priv.param<string>("body_frame", body.child_frame_id, "body");
|
||||
nh_priv.getParam("reference_frames", reference_frames);
|
||||
|
||||
// Default reference frames
|
||||
std::map<string, string> default_reference_frames;
|
||||
default_reference_frames[body.child_frame_id] = local_frame;
|
||||
default_reference_frames[fcu_frame] = local_frame;
|
||||
if (!target.child_frame_id.empty()) default_reference_frames[target.child_frame_id] = local_frame;
|
||||
reference_frames.insert(default_reference_frames.begin(), default_reference_frames.end()); // merge defaults
|
||||
|
||||
state_timeout = ros::Duration(nh_priv.param("state_timeout", 3.0));
|
||||
local_position_timeout = ros::Duration(nh_priv.param("local_position_timeout", 2.0));
|
||||
velocity_timeout = ros::Duration(nh_priv.param("velocity_timeout", 2.0));
|
||||
@@ -896,25 +885,25 @@ int main(int argc, char **argv)
|
||||
arming_timeout = ros::Duration(nh_priv.param("arming_timeout", 4.0));
|
||||
|
||||
// Service clients
|
||||
arming = nh.serviceClient<mavros_msgs::CommandBool>(mavros + "/cmd/arming");
|
||||
set_mode = nh.serviceClient<mavros_msgs::SetMode>(mavros + "/set_mode");
|
||||
arming = nh.serviceClient<mavros_msgs::CommandBool>("mavros/cmd/arming");
|
||||
set_mode = nh.serviceClient<mavros_msgs::SetMode>("mavros/set_mode");
|
||||
|
||||
// Telemetry subscribers
|
||||
auto state_sub = nh.subscribe(mavros + "/state", 1, &handleState);
|
||||
auto velocity_sub = nh.subscribe(mavros + "/local_position/velocity_body", 1, &handleMessage<TwistStamped, velocity>);
|
||||
auto global_position_sub = nh.subscribe(mavros + "/global_position/global", 1, &handleMessage<NavSatFix, global_position>);
|
||||
auto battery_sub = nh.subscribe(mavros + "/battery", 1, &handleMessage<BatteryState, battery>);
|
||||
auto statustext_sub = nh.subscribe(mavros + "/statustext/recv", 1, &handleMessage<mavros_msgs::StatusText, statustext>);
|
||||
auto manual_control_sub = nh.subscribe(mavros + "/manual_control/control", 1, &handleMessage<mavros_msgs::ManualControl, manual_control>);
|
||||
auto local_position_sub = nh.subscribe(mavros + "/local_position/pose", 1, &handleLocalPosition);
|
||||
auto state_sub = nh.subscribe("mavros/state", 1, &handleState);
|
||||
auto velocity_sub = nh.subscribe("mavros/local_position/velocity_body", 1, &handleMessage<TwistStamped, velocity>);
|
||||
auto global_position_sub = nh.subscribe("mavros/global_position/global", 1, &handleMessage<NavSatFix, global_position>);
|
||||
auto battery_sub = nh.subscribe("mavros/battery", 1, &handleMessage<BatteryState, battery>);
|
||||
auto statustext_sub = nh.subscribe("mavros/statustext/recv", 1, &handleMessage<mavros_msgs::StatusText, statustext>);
|
||||
auto manual_control_sub = nh.subscribe("mavros/manual_control/control", 1, &handleMessage<mavros_msgs::ManualControl, manual_control>);
|
||||
auto local_position_sub = nh.subscribe("mavros/local_position/pose", 1, &handleLocalPosition);
|
||||
|
||||
// Setpoint publishers
|
||||
position_pub = nh.advertise<PoseStamped>(mavros + "/setpoint_position/local", 1);
|
||||
position_raw_pub = nh.advertise<PositionTarget>(mavros + "/setpoint_raw/local", 1);
|
||||
attitude_pub = nh.advertise<PoseStamped>(mavros + "/setpoint_attitude/attitude", 1);
|
||||
attitude_raw_pub = nh.advertise<AttitudeTarget>(mavros + "/setpoint_raw/attitude", 1);
|
||||
rates_pub = nh.advertise<TwistStamped>(mavros + "/setpoint_attitude/cmd_vel", 1);
|
||||
thrust_pub = nh.advertise<Thrust>(mavros + "/setpoint_attitude/thrust", 1);
|
||||
position_pub = nh.advertise<PoseStamped>("mavros/setpoint_position/local", 1);
|
||||
position_raw_pub = nh.advertise<PositionTarget>("mavros/setpoint_raw/local", 1);
|
||||
attitude_pub = nh.advertise<PoseStamped>("mavros/setpoint_attitude/attitude", 1);
|
||||
attitude_raw_pub = nh.advertise<AttitudeTarget>("mavros/setpoint_raw/attitude", 1);
|
||||
rates_pub = nh.advertise<TwistStamped>("mavros/setpoint_attitude/cmd_vel", 1);
|
||||
thrust_pub = nh.advertise<Thrust>("mavros/setpoint_attitude/thrust", 1);
|
||||
|
||||
// Service servers
|
||||
auto gt_serv = nh.advertiseService("get_telemetry", &getTelemetry);
|
||||
|
||||
@@ -141,11 +141,11 @@ int main(int argc, char **argv) {
|
||||
vpe_pub = nh_priv.advertise<PoseStamped>("vpe", 1);
|
||||
//vpe_cov_pub = nh_priv_.advertise<PoseStamped>("pose_cov_pub", 1);
|
||||
|
||||
if (nh_priv.param("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
|
||||
zero_timer = nh.createTimer(ros::Duration(0.1), &publishZero);
|
||||
publish_zero_timout = ros::Duration(nh_priv.param("force_init_timeout", 5.0));
|
||||
publish_zero_duration = ros::Duration(nh_priv.param("force_init_duration", 5.0));
|
||||
publish_zero_timout = ros::Duration(nh_priv.param("publish_zero_timout", 5.0));
|
||||
publish_zero_duration = ros::Duration(nh_priv.param("publish_zero_duration", 5.0));
|
||||
local_position_sub = nh.subscribe("mavros/local_position/pose", 1, &localPositionCallback);
|
||||
}
|
||||
|
||||
|
||||
@@ -33,29 +33,3 @@ def test_web_video_server(node):
|
||||
# Python 3
|
||||
import urllib.request as urllib
|
||||
urllib.urlopen("http://localhost:8080").read()
|
||||
|
||||
def test_blocks(node):
|
||||
rospy.wait_for_service('clover_blocks/run', timeout=5)
|
||||
rospy.wait_for_service('clover_blocks/stop', timeout=5)
|
||||
rospy.wait_for_service('clover_blocks/load', timeout=5)
|
||||
rospy.wait_for_service('clover_blocks/store', timeout=5)
|
||||
|
||||
from std_msgs.msg import String
|
||||
from clover_blocks.srv import Run
|
||||
|
||||
def wait_print():
|
||||
try:
|
||||
wait_print.result = rospy.wait_for_message('clover_blocks/print', String, timeout=5).data
|
||||
except Exception as e:
|
||||
wait_print.result = str(e)
|
||||
|
||||
import threading
|
||||
t = threading.Thread(target=wait_print)
|
||||
t.start()
|
||||
rospy.sleep(0.1)
|
||||
|
||||
run = rospy.ServiceProxy('clover_blocks/run', Run)
|
||||
assert run(code='print("test")').success == True
|
||||
|
||||
t.join()
|
||||
assert wait_print.result == 'test'
|
||||
|
||||
@@ -23,7 +23,10 @@
|
||||
|
||||
<node pkg="tf2_ros" type="static_transform_publisher" name="map_flipped_frame" args="0 0 0 3.1415926 3.1415926 0 map map_flipped" required="true"/>
|
||||
|
||||
<node name="simple_offboard" pkg="clover" type="simple_offboard" required="true" output="screen"/>
|
||||
<node name="simple_offboard" pkg="clover" type="simple_offboard" required="true" output="screen">
|
||||
<param name="reference_frames/body" value="map"/>
|
||||
<param name="reference_frames/base_link" value="map"/>
|
||||
</node>
|
||||
|
||||
<node name="tf2_web_republisher" pkg="tf2_web_republisher" type="tf2_web_republisher" required="true"/>
|
||||
|
||||
@@ -35,8 +38,6 @@
|
||||
<rosparam param="notify">startup: { r: 255, g: 255, b: 255 }</rosparam>
|
||||
</node>
|
||||
|
||||
<node name="clover_blocks" pkg="clover_blocks" type="clover_blocks" output="screen" required="true"/>
|
||||
|
||||
<param name="test_module" value="$(find clover)/test/basic.py"/>
|
||||
<test test-name="basic_test" pkg="ros_pytest" type="ros_pytest_runner"/>
|
||||
</launch>
|
||||
|
||||
@@ -12,6 +12,4 @@ SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0016", ATTRS{produ
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0013", ATTRS{product}=="PX4 FMU v4.x PRO", SYMLINK+="px4fmu"
|
||||
# Omnibus
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0001", ATTRS{product}=="PX4 OmnibusF4SD", SYMLINK+="px4fmu"
|
||||
# CUAV X7 Pro
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="3163", ATTRS{idProduct}=="004c", ATTRS{product}=="PX4 CUAV X7Pro", SYMLINK+="px4fmu"
|
||||
|
||||
|
||||
@@ -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>
|
||||
@@ -9,7 +9,7 @@
|
||||
<li><a href="" id="butterfly">Open web terminal</a> (<code>Butterfly</code>)</li>
|
||||
<li>View <a href="viz.html">View 3D visualization</a>, <a href="aruco_map.html">3D visualization for markers map</a> (<code>ros3djs</code>)</li>
|
||||
<li><a href="../clover_blocks/">Blocks programming</a> (<code>Blockly</code>)</li>
|
||||
<li><a href="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>
|
||||
|
||||
<div class="version"></div>
|
||||
|
||||
@@ -1,16 +1,13 @@
|
||||
const url = 'ws://' + location.hostname + ':9090';
|
||||
const ros = new ROSLIB.Ros({ url: url });
|
||||
const params = Object.fromEntries(new URLSearchParams(window.location.search).entries());
|
||||
|
||||
ros.on('connection', function () {
|
||||
document.body.classList.add('connected');
|
||||
document.body.classList.remove('closed');
|
||||
init();
|
||||
});
|
||||
|
||||
ros.on('close', function () {
|
||||
document.body.classList.remove('connected');
|
||||
document.body.classList.add('closed');
|
||||
setTimeout(function() {
|
||||
// reconnect
|
||||
ros.connect(url);
|
||||
@@ -40,38 +37,56 @@ function viewTopicsList() {
|
||||
let rosdistro;
|
||||
|
||||
function viewTopic(topic) {
|
||||
let index = '<a href=topics.html>Topics</a>';
|
||||
title.innerHTML = `${index}: ${topic}`;
|
||||
title.innerHTML = topic;
|
||||
topicMessage.style.display = 'block';
|
||||
|
||||
ros.getTopicType(topic, function(typeStr) {
|
||||
const [pack, type] = typeStr.split('/');
|
||||
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) {
|
||||
document.title = topic;
|
||||
if (mouseDown) return;
|
||||
|
||||
if (msg.header.stamp) {
|
||||
if (params.date || params.offset) {
|
||||
let date = new Date(msg.header.stamp.secs * 1e3 + msg.header.stamp.nsecs * 1e-6);
|
||||
if (params.date) msg.header.date = date.toISOString();
|
||||
if (params.offset) msg.header.offset = (new Date() - date) * 1e-3;
|
||||
}
|
||||
}
|
||||
|
||||
topicMessage.innerHTML = yamlStringify(msg); // JSON.stringify(msg, null, 4);
|
||||
});
|
||||
}
|
||||
|
||||
function viewParameters() {
|
||||
title.innerHTML = 'Parameters';
|
||||
topicMessage.style.display = 'block';
|
||||
|
||||
let names = ['aruco_detect', 'main_camera', 'main_camera_nodelet_manager', 'mavros', 'optical_flow',
|
||||
'rangefinder', 'rosapi', 'rosbridge_websocket', 'rosdistro', 'roslaunch', 'rosversion',
|
||||
'roswww_static', 'run_id', 'simple_offboard', 'visualization', 'web_video_server'];
|
||||
let params = {};
|
||||
// ros.getParams(function(params) {
|
||||
|
||||
Promise.all(names.map(function(name) {
|
||||
return new Promise(function(resolve, reject) {
|
||||
new ROSLIB.Param({ ros, name }).get(function(value) {
|
||||
params[name] = value;
|
||||
resolve();
|
||||
})
|
||||
});
|
||||
})).then(function() {
|
||||
console.log(params);
|
||||
topicMessage.innerHTML = yamlStringify(params);
|
||||
});
|
||||
}
|
||||
|
||||
let mouseDown;
|
||||
|
||||
topicMessage.addEventListener('mousedown', function() { mouseDown = true; });
|
||||
topicMessage.addEventListener('mouseup', function() { mouseDown = false; });
|
||||
|
||||
function init() {
|
||||
const params = Object.fromEntries(new URLSearchParams(window.location.search).entries());
|
||||
|
||||
viewParameters();
|
||||
return;
|
||||
|
||||
if (!params.topic) {
|
||||
viewTopicsList();
|
||||
} else {
|
||||
@@ -81,3 +96,5 @@ function init() {
|
||||
});
|
||||
}
|
||||
}
|
||||
|
||||
window.ros = ros;
|
||||
|
||||
@@ -17,12 +17,11 @@
|
||||
}
|
||||
#topic-type { font-family: monospace; font-size: 0.5em; vertical-align: super; font-weight: normal; }
|
||||
.topic { font-family: monospace; }
|
||||
body.closed { background-color: rgb(207, 207, 207); }
|
||||
</style>
|
||||
</head>
|
||||
<body>
|
||||
<h1> </h1>
|
||||
<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>
|
||||
</html>
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>clover_blocks</name>
|
||||
<version>0.23.0</version>
|
||||
<version>0.21.1</version>
|
||||
<description>Blockly programming support for Clover</description>
|
||||
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>
|
||||
<license>MIT</license>
|
||||
|
||||
@@ -464,7 +464,7 @@ Blockly.Python.led_count = function(block) {
|
||||
|
||||
function 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):
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
<package format="2">
|
||||
<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>
|
||||
|
||||
<maintainer email="sfalexrog@gmail.com">Alexey Rogachevskiy</maintainer>
|
||||
|
||||
@@ -35,7 +35,7 @@
|
||||
<xacro:property name="sqrt2" value="1.4142135623730951" />
|
||||
<xacro:property name="rotor_drag_coefficient" value="1.75e-04" />
|
||||
<xacro:property name="rolling_moment_coefficient" value="0.000001" />
|
||||
<xacro:property name="color" value="DarkGrey" />
|
||||
<xacro:property name="color" value="$(arg visual_material)" />
|
||||
|
||||
<!-- Property Blocks -->
|
||||
<!-- Clover body inertia -->
|
||||
|
||||
@@ -64,12 +64,6 @@
|
||||
<!-- <gazebo>
|
||||
<static>true</static>
|
||||
</gazebo> -->
|
||||
<gazebo>
|
||||
<plugin name="${name}_ros_controller" filename="libsim_leds_controller.so">
|
||||
<robotNamespace></robotNamespace>
|
||||
<ledCount>${led_count}</ledCount>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
</xacro:macro>
|
||||
|
||||
</robot>
|
||||
|
||||
@@ -37,14 +37,6 @@ target_compile_options(sim_leds PRIVATE -std=c++11)
|
||||
|
||||
add_dependencies(sim_leds ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
|
||||
|
||||
add_library(sim_leds_controller src/sim_leds_controller.cpp)
|
||||
|
||||
target_include_directories(sim_leds_controller PRIVATE ${catkin_INCLUDE_DIRS} ${GAZEBO_INCLUDE_DIRS})
|
||||
target_link_libraries(sim_leds_controller PRIVATE ${catkin_LIBRARIES} ${GAZEBO_LIBRARIES})
|
||||
target_compile_options(sim_leds_controller PRIVATE -std=c++11)
|
||||
|
||||
add_dependencies(sim_leds_controller ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
|
||||
|
||||
# Gazebo throttling camera plugin
|
||||
# for some reason, CMake does not support per-target link directories, and Gazebo does not put
|
||||
# CameraPlugin into ${GAZEBO_LIBRARIES}
|
||||
|
||||
@@ -21,7 +21,7 @@ param set LPE_VIS_Z 0.1
|
||||
param set LPE_FUSION 86
|
||||
|
||||
param set SENS_FLOW_ROT 0
|
||||
param set SENS_FLOW_MINHGT 0.0
|
||||
param set SENS_FLOW_MINHGT 0.01
|
||||
param set SENS_FLOW_MAXHGT 4.0
|
||||
param set SENS_FLOW_MAXR 10.0
|
||||
|
||||
|
||||
@@ -4,7 +4,6 @@
|
||||
<arg name="est" default="ekf2"/> <!-- PX4 estimator: lpe, ekf2 -->
|
||||
<arg name="vehicle" default="clover"/> <!-- PX4 vehicle configuration: clover, clover_vpe -->
|
||||
<arg name="main_camera" default="true"/> <!-- Simulated vision position estimation camera (optical flow, ArUco) -->
|
||||
<arg name="maintain_camera_rate" default="false"/> <!-- Slow simulation down to maintain camera rate -->
|
||||
<arg name="rangefinder" default="true"/> <!-- Simulated downward-facing rangefinder, vl53l1x-like -->
|
||||
<arg name="led" default="true"/> <!-- Simulated LED strip, ws281x-like -->
|
||||
<arg name="gps" default="false"/> <!--Simulated GPS module -->
|
||||
@@ -29,7 +28,6 @@
|
||||
<!-- Clover model -->
|
||||
<include file="$(find clover_description)/launch/spawn_drone.launch" if="$(eval type == 'gazebo')">
|
||||
<arg name="main_camera" value="$(arg main_camera)"/>
|
||||
<arg name="maintain_camera_rate" value="$(arg maintain_camera_rate)"/>
|
||||
<arg name="rangefinder" value="$(arg rangefinder)"/>
|
||||
<arg name="led" value="$(arg led)"/>
|
||||
<arg name="gps" value="$(arg gps)"/>
|
||||
|
||||
@@ -1,24 +0,0 @@
|
||||
<?xml version="1.0"?>
|
||||
<sdf version="1.5">
|
||||
<model name="aruco_100">
|
||||
<static>true</static>
|
||||
<link name="marker_100_link">
|
||||
<pose>0 0 1e-3 0 0 1.5707963267948966</pose>
|
||||
<visual name="visual_marker_100">
|
||||
<cast_shadows>false</cast_shadows>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.22 0.22 1e-3</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<uri>model://aruco_100/materials/scripts</uri>
|
||||
<uri>model://aruco_100/materials/textures</uri>
|
||||
<name>aruco/marker_100</name>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
</sdf>
|
||||
@@ -1,15 +0,0 @@
|
||||
material aruco/marker_100
|
||||
{
|
||||
technique
|
||||
{
|
||||
pass
|
||||
{
|
||||
texture_unit
|
||||
{
|
||||
texture aruco_marker_100.png
|
||||
filtering none
|
||||
scale 1.0 1.0
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
Before Width: | Height: | Size: 94 B |
@@ -1,13 +0,0 @@
|
||||
<?xml version="1.0"?>
|
||||
<model>
|
||||
<name>ArUco Marker 100</name>
|
||||
<version>1.0</version>
|
||||
<sdf version="1.5">marker_100.sdf</sdf>
|
||||
<author>
|
||||
<name>Marker Generator script</name>
|
||||
<email>marker@generator.sh</email>
|
||||
</author>
|
||||
<description>
|
||||
ArUco marker #100
|
||||
</description>
|
||||
</model>
|
||||
@@ -1,24 +0,0 @@
|
||||
<?xml version="1.0"?>
|
||||
<sdf version="1.5">
|
||||
<model name="aruco_101">
|
||||
<static>true</static>
|
||||
<link name="marker_101_link">
|
||||
<pose>0 0 1e-3 0 0 1.5707963267948966</pose>
|
||||
<visual name="visual_marker_101">
|
||||
<cast_shadows>false</cast_shadows>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.44 0.44 1e-3</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<uri>model://aruco_101/materials/scripts</uri>
|
||||
<uri>model://aruco_101/materials/textures</uri>
|
||||
<name>aruco/marker_101</name>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
</sdf>
|
||||
@@ -1,15 +0,0 @@
|
||||
material aruco/marker_101
|
||||
{
|
||||
technique
|
||||
{
|
||||
pass
|
||||
{
|
||||
texture_unit
|
||||
{
|
||||
texture aruco_marker_101.png
|
||||
filtering none
|
||||
scale 1.0 1.0
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
Before Width: | Height: | Size: 94 B |
@@ -1,13 +0,0 @@
|
||||
<?xml version="1.0"?>
|
||||
<model>
|
||||
<name>ArUco Marker 101</name>
|
||||
<version>1.0</version>
|
||||
<sdf version="1.5">marker_101.sdf</sdf>
|
||||
<author>
|
||||
<name>Marker Generator script</name>
|
||||
<email>marker@generator.sh</email>
|
||||
</author>
|
||||
<description>
|
||||
ArUco marker #101
|
||||
</description>
|
||||
</model>
|
||||
@@ -1,24 +0,0 @@
|
||||
<?xml version="1.0"?>
|
||||
<sdf version="1.5">
|
||||
<model name="aruco_102">
|
||||
<static>true</static>
|
||||
<link name="marker_102_link">
|
||||
<pose>0 0 1e-3 0 0 1.5707963267948966</pose>
|
||||
<visual name="visual_marker_102">
|
||||
<cast_shadows>false</cast_shadows>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.44 0.44 1e-3</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<uri>model://aruco_102/materials/scripts</uri>
|
||||
<uri>model://aruco_102/materials/textures</uri>
|
||||
<name>aruco/marker_102</name>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
</sdf>
|
||||
@@ -1,15 +0,0 @@
|
||||
material aruco/marker_102
|
||||
{
|
||||
technique
|
||||
{
|
||||
pass
|
||||
{
|
||||
texture_unit
|
||||
{
|
||||
texture aruco_marker_102.png
|
||||
filtering none
|
||||
scale 1.0 1.0
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
Before Width: | Height: | Size: 94 B |
@@ -1,13 +0,0 @@
|
||||
<?xml version="1.0"?>
|
||||
<model>
|
||||
<name>ArUco Marker 102</name>
|
||||
<version>1.0</version>
|
||||
<sdf version="1.5">marker_102.sdf</sdf>
|
||||
<author>
|
||||
<name>Marker Generator script</name>
|
||||
<email>marker@generator.sh</email>
|
||||
</author>
|
||||
<description>
|
||||
ArUco marker #102
|
||||
</description>
|
||||
</model>
|
||||
@@ -6,11 +6,11 @@
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<sensor name='camera' type='camera'>
|
||||
<camera>
|
||||
<horizontal_fov>1.8</horizontal_fov>
|
||||
<horizontal_fov>2.0944</horizontal_fov>
|
||||
<image>
|
||||
<format>B8G8R8</format>
|
||||
<width>640</width>
|
||||
<height>480</height>
|
||||
<width>800</width>
|
||||
<height>600</height>
|
||||
</image>
|
||||
<clip>
|
||||
<near>0.02</near>
|
||||
@@ -18,7 +18,7 @@
|
||||
</clip>
|
||||
</camera>
|
||||
<always_on>1</always_on>
|
||||
<update_rate>30</update_rate>
|
||||
<update_rate>20</update_rate>
|
||||
<visualize>1</visualize>
|
||||
<plugin name='camera_plugin' filename='libgazebo_ros_camera.so'>
|
||||
<alwaysOn>1</alwaysOn>
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
<package format="2">
|
||||
<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>
|
||||
|
||||
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>
|
||||
|
||||
@@ -1,8 +0,0 @@
|
||||
#!/usr/bin/env bash
|
||||
|
||||
# script for running gzweb
|
||||
# usage: ./gzweb [<port>]
|
||||
|
||||
export NVM_DIR=$HOME/.nvm
|
||||
source $NVM_DIR/nvm.sh
|
||||
npm start --prefix $HOME/gzweb -p ${1-8080}
|
||||
@@ -49,9 +49,14 @@ private:
|
||||
|
||||
std::unique_ptr<ros::NodeHandle> nh;
|
||||
|
||||
ros::ServiceServer setLedsSrv;
|
||||
// Note: LED state should only be published by the /gazebo node
|
||||
led_msgs::LEDStateArray ledState;
|
||||
ros::Publisher statePublisher;
|
||||
// LED state will be read from the topic to avoid creating more services
|
||||
ros::Subscriber stateSubscriber;
|
||||
|
||||
bool setLeds(led_msgs::SetLEDs::Request& req, led_msgs::SetLEDs::Response& resp);
|
||||
void handleLedsMsg(const led_msgs::LEDStateArrayConstPtr& leds);
|
||||
|
||||
public:
|
||||
@@ -68,8 +73,16 @@ public:
|
||||
ROS_INFO_NAMED(("LedController_" + robotNamespace).c_str(), "LedController has started (as %s)", role == Role::Client ? "client" : "server");
|
||||
|
||||
nh.reset(new ros::NodeHandle(robotNamespace));
|
||||
|
||||
stateSubscriber = nh->subscribe<led_msgs::LEDStateArray>("led/state", 1, &LedController::handleLedsMsg, this);
|
||||
if (role == Role::Server)
|
||||
{
|
||||
setLedsSrv = nh->advertiseService("led/set_leds", &LedController::setLeds, this);
|
||||
statePublisher = nh->advertise<led_msgs::LEDStateArray>("led/state", 1, true);
|
||||
}
|
||||
else
|
||||
{
|
||||
// LED state should be published to the "led/state" topic, so we grab our data there
|
||||
stateSubscriber = nh->subscribe<led_msgs::LEDStateArray>("led/state", 1, &LedController::handleLedsMsg, this);
|
||||
}
|
||||
};
|
||||
|
||||
~LedController()
|
||||
@@ -83,9 +96,13 @@ public:
|
||||
std::lock_guard<std::mutex> lock(registryMutex);
|
||||
if (totalLeds > 0) {
|
||||
registeredLeds.resize(totalLeds);
|
||||
ledState.leds.resize(totalLeds);
|
||||
}
|
||||
ROS_DEBUG_NAMED(("LedController_" + robotNamespace).c_str(), "Registering LED visual plugin to %s (LED id=%d)", (role == Role::Client) ? "client" : "server", ledIdx);
|
||||
registeredLeds[ledIdx] = plugin;
|
||||
ledState.leds[ledIdx].index = ledIdx;
|
||||
if (role == Role::Server)
|
||||
statePublisher.publish(ledState);
|
||||
}
|
||||
|
||||
void unregisterPlugin(sim_led::LedVisualPlugin* plugin)
|
||||
@@ -140,8 +157,7 @@ public:
|
||||
{
|
||||
auto indexStr = parentName.substr(lastDashPos + 1);
|
||||
try {
|
||||
if (indexStr == "visual") myIndex = 0; // the first visual doesn't have index
|
||||
else myIndex = std::stoi(indexStr);
|
||||
myIndex = std::stoi(indexStr);
|
||||
} catch(const std::exception &e) {
|
||||
gzwarn << "Failed to convert " << indexStr << " to integer: " << e.what() << ", assuming 0\n";
|
||||
myIndex = 0;
|
||||
@@ -179,6 +195,26 @@ public:
|
||||
};
|
||||
}
|
||||
|
||||
// FIXME: These two functions basically do the same thing, maybe they can be merged?
|
||||
bool led_controller::LedController::setLeds(led_msgs::SetLEDs::Request &req, led_msgs::SetLEDs::Response &resp)
|
||||
{
|
||||
std::lock_guard<std::mutex> lock(registryMutex);
|
||||
for(const auto& led : req.leds)
|
||||
{
|
||||
if (led.index < registeredLeds.size()) {
|
||||
auto color = GazeboColor(led.r / 255.0f, led.g / 255.0f, led.b / 255.0f);
|
||||
auto ledPlugin = registeredLeds[led.index];
|
||||
if (ledPlugin) ledPlugin->SetColor(color);
|
||||
ledState.leds[led.index].r = led.r;
|
||||
ledState.leds[led.index].g = led.g;
|
||||
ledState.leds[led.index].b = led.b;
|
||||
}
|
||||
}
|
||||
statePublisher.publish(ledState);
|
||||
resp.success = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
void led_controller::LedController::handleLedsMsg(const led_msgs::LEDStateArrayConstPtr& leds)
|
||||
{
|
||||
std::lock_guard<std::mutex> lock(registryMutex);
|
||||
|
||||
@@ -1,71 +0,0 @@
|
||||
#include <led_msgs/SetLEDs.h>
|
||||
#include <led_msgs/LEDStateArray.h>
|
||||
|
||||
#include <ros/ros.h>
|
||||
|
||||
#include <gazebo/gazebo.hh>
|
||||
#include <gazebo/physics/physics.hh>
|
||||
#include <gazebo/common/common.hh>
|
||||
|
||||
class LedControllerPlugin : public gazebo::ModelPlugin {
|
||||
private:
|
||||
std::unique_ptr<ros::NodeHandle> nh;
|
||||
std::string ns;
|
||||
ros::ServiceServer setLedsSrv;
|
||||
led_msgs::LEDStateArray ledState;
|
||||
ros::Publisher statePublisher;
|
||||
std::mutex handleMutex;
|
||||
|
||||
public:
|
||||
bool setLeds(led_msgs::SetLEDs::Request &req, led_msgs::SetLEDs::Response &resp)
|
||||
{
|
||||
std::lock_guard<std::mutex> lock(handleMutex);
|
||||
for(const auto& led : req.leds)
|
||||
{
|
||||
if (led.index < ledState.leds.size()) {
|
||||
ledState.leds[led.index].r = led.r;
|
||||
ledState.leds[led.index].g = led.g;
|
||||
ledState.leds[led.index].b = led.b;
|
||||
}
|
||||
}
|
||||
statePublisher.publish(ledState);
|
||||
resp.success = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
virtual void Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) override
|
||||
{
|
||||
ROS_INFO("Initialize LED Controller");
|
||||
|
||||
// We need "libgazebo_ros_api.so" to be loaded
|
||||
if (!ros::isInitialized())
|
||||
{
|
||||
ROS_FATAL_NAMED("LedController", "Tried to load ROS plugin when ROS Gazebo API is not loaded. Please use gazebo_ros node to"
|
||||
"launch Gazebo.");
|
||||
}
|
||||
|
||||
ns = "";
|
||||
|
||||
if (sdf->HasElement("robotNamespace")) {
|
||||
ns = sdf->Get<std::string>("robotNamespace");
|
||||
}
|
||||
if (!sdf->HasElement("ledCount")) {
|
||||
gzerr << "ledCount is not set, but is required for the plugin to function correctly\n";
|
||||
return;
|
||||
}
|
||||
int totalLeds = sdf->Get<int>("ledCount");
|
||||
ledState.leds.resize(totalLeds);
|
||||
for (int i = 0; i < totalLeds; i++) {
|
||||
ledState.leds[i].index = i;
|
||||
}
|
||||
|
||||
nh.reset(new ros::NodeHandle(ns));
|
||||
|
||||
setLedsSrv = nh->advertiseService("led/set_leds", &LedControllerPlugin::setLeds, this);
|
||||
statePublisher = nh->advertise<led_msgs::LEDStateArray>("led/state", 1, true);
|
||||
|
||||
statePublisher.publish(ledState);
|
||||
}
|
||||
};
|
||||
|
||||
GZ_REGISTER_MODEL_PLUGIN(LedControllerPlugin);
|
||||
@@ -1,83 +0,0 @@
|
||||
const sidebar = require('./sidebar');
|
||||
|
||||
const hostname = 'https://clover.coex.tech/';
|
||||
const allowedTags = ['font', 'center', 'nobr']; // allow using some deprecated and non-standard html tags
|
||||
|
||||
module.exports = {
|
||||
lang: 'en-US',
|
||||
title: 'Clover',
|
||||
description: 'Clover Drone Kit',
|
||||
// theme and its config
|
||||
theme: '@vuepress/theme-default',
|
||||
themeConfig: {
|
||||
logo: 'clover-logo.png',
|
||||
sidebar: {
|
||||
'/ru/': sidebar.readSummary("./ru/SUMMARY.md"),
|
||||
'/en/': sidebar.readSummary("./en/SUMMARY.md"),
|
||||
},
|
||||
sidebarDepth: 0,
|
||||
locales: {
|
||||
'/en/': {
|
||||
selectLanguageName: 'English',
|
||||
navbar: [
|
||||
{ text: 'Official Site', link: 'https://coex.tech' },
|
||||
{ text: 'Support Chat', link: 'https://t.me/COEXHelpdesk' },
|
||||
]
|
||||
},
|
||||
'/ru/': {
|
||||
selectLanguageName: 'Русский',
|
||||
tip: 'СОВЕТ',
|
||||
warning: 'ВНИМАНИЕ',
|
||||
danger: 'ОПАСНО',
|
||||
toggleDarkMode: 'Переключить темную тему',
|
||||
navbar: [
|
||||
{ text: 'Сайт', link: 'https://coex.tech' },
|
||||
{ text: 'Чат поддержки', link: 'https://t.me/COEXHelpdesk' },
|
||||
]
|
||||
},
|
||||
},
|
||||
toggleSidebar: true,
|
||||
repo: 'CopterExpress/clover',
|
||||
docsBranch: 'master',
|
||||
docsDir: 'docs',
|
||||
lastUpdated: false,
|
||||
contributors: false
|
||||
},
|
||||
pagePatterns: ['**/*.md', '!.vuepress', '!node_modules', '!ru/metodmaterials.md'],
|
||||
locales: {
|
||||
'/en/': {
|
||||
lang: 'en',
|
||||
title: 'Clover',
|
||||
description: 'Clover Drone Kit'
|
||||
},
|
||||
'/ru/': {
|
||||
lang: 'ru',
|
||||
title: 'Клевер',
|
||||
description: 'Конструктор квадрокоптера «Клевер»'
|
||||
}
|
||||
},
|
||||
markdown: {
|
||||
code: {
|
||||
lineNumbers: false
|
||||
},
|
||||
linkify: true,
|
||||
},
|
||||
extendsMarkdown(md) {
|
||||
md.use(require('markdown-it-attrs')); // to use custom headers anchors
|
||||
},
|
||||
bundlerConfig: {
|
||||
vuePluginOptions: {
|
||||
template: {
|
||||
compilerOptions: {
|
||||
isCustomElement: tag => allowedTags.includes(tag)
|
||||
}
|
||||
}
|
||||
}
|
||||
},
|
||||
plugins: [
|
||||
'@vuepress/plugin-search',
|
||||
'vuepress-plugin-copy-code2',
|
||||
['sitemap2', { hostname, excludeUrls: ['/', '/LANGS.html'] }],
|
||||
require('./rich-quotes')
|
||||
]
|
||||
}
|
||||
|
Before Width: | Height: | Size: 110 KiB |
@@ -1,37 +0,0 @@
|
||||
// Plugin to convert GitBook rich quotes to custom containers
|
||||
|
||||
const types = {
|
||||
info: 'tip',
|
||||
note: 'tip',
|
||||
tag: 'tip',
|
||||
comment: 'tip',
|
||||
hint: 'tip',
|
||||
success: 'tip',
|
||||
warning: 'warning',
|
||||
caution: 'warning',
|
||||
danger: 'danger',
|
||||
quote: 'tip'
|
||||
}
|
||||
|
||||
function replace(src) {
|
||||
return src.replace(/^> \*\*(.*?)\*\* (.*\n(>.*\n)*)/gm, function (match, type, text) {
|
||||
text = text.replace(/^>/gm, '');
|
||||
return `::: ${types[type.toLowerCase()]}\n${text}\n:::`;
|
||||
});
|
||||
}
|
||||
|
||||
module.exports = {
|
||||
name: 'vuepress-plugin-rich-quotes',
|
||||
extendsMarkdown: (md) => {
|
||||
var _render = md.render;
|
||||
|
||||
// TODO: a rough hack to replace rich quotes
|
||||
// TODO: use proper plugin api
|
||||
|
||||
md.render = function(src, env) {
|
||||
src = replace(src);
|
||||
return _render.call(md, src, env);
|
||||
}
|
||||
},
|
||||
|
||||
};
|
||||
@@ -1,50 +0,0 @@
|
||||
const fs = require('fs')
|
||||
|
||||
const regex = /(\s*?)\*\s\[(.*?)\]\((.*?)\)/;
|
||||
|
||||
exports.readSummary = function (path) {
|
||||
let sidebar = [];
|
||||
let lines = fs.readFileSync(path).toString().split('\n');
|
||||
let item = {};
|
||||
|
||||
for (let line of lines) {
|
||||
if (line.startsWith('#')) continue;
|
||||
if (!line.trim()) continue;
|
||||
|
||||
let match = regex.exec(line);
|
||||
if (!match) {
|
||||
console.log('cannot parse', line);
|
||||
continue;
|
||||
}
|
||||
level = match[1].length / 2;
|
||||
text = match[2];
|
||||
path = match[3].trim();
|
||||
|
||||
if (level == 0) {
|
||||
if (item.path) {
|
||||
// push new item
|
||||
if (item.children) {
|
||||
sidebar.push(item);
|
||||
} else {
|
||||
sidebar.push(item.path)
|
||||
}
|
||||
item = {};
|
||||
}
|
||||
item.text = text;
|
||||
item.path = path;
|
||||
item.collapsible = true;
|
||||
|
||||
} else if (level == 1 || level == 2) {
|
||||
if (!item.children) {
|
||||
item.children = [];
|
||||
if (item.path) item.children.push(item.path);
|
||||
}
|
||||
item.children.push(path);
|
||||
|
||||
} else {
|
||||
console.log('skip', text);
|
||||
}
|
||||
}
|
||||
|
||||
return sidebar;
|
||||
}
|
||||
@@ -1,49 +0,0 @@
|
||||
.big-clover {
|
||||
max-width: 80% !important;
|
||||
display: block;
|
||||
margin-left: auto;
|
||||
margin-right: auto;
|
||||
}
|
||||
|
||||
/* change image for dark theme */
|
||||
html .big-clover.dark { display: none; }
|
||||
html.dark .big-clover { display: none; }
|
||||
html.dark .big-clover.dark { display: block; }
|
||||
|
||||
img.logo {
|
||||
transform: scale(2.5) translateX(-5%);
|
||||
}
|
||||
|
||||
/* Centered images */
|
||||
img.center {
|
||||
display: block;
|
||||
margin-left: auto;
|
||||
margin-right: auto;
|
||||
}
|
||||
|
||||
/* Images with border */
|
||||
img.border {
|
||||
border: 1px #e9e9e9 solid;
|
||||
border-radius: 5px;
|
||||
}
|
||||
|
||||
html.dark img.border {
|
||||
border: none;
|
||||
background: #fffffa;
|
||||
}
|
||||
|
||||
table.versions td {
|
||||
text-align: center;
|
||||
background: white;
|
||||
}
|
||||
table.versions .subversion {
|
||||
font-size: 80%;
|
||||
}
|
||||
|
||||
.circle {
|
||||
width: 0.8em;
|
||||
height: 0.8em;
|
||||
border-radius: 50%;
|
||||
display: inline-block;
|
||||
margin-right: 0.5em;
|
||||
}
|
||||
@@ -1,4 +0,0 @@
|
||||
# Languages
|
||||
|
||||
* [English](en/)
|
||||
* [Русский](ru/)
|
||||
|
Before Width: | Height: | Size: 220 KiB After Width: | Height: | Size: 695 KiB |
|
Before Width: | Height: | Size: 104 KiB |
|
Before Width: | Height: | Size: 151 KiB |
|
Before Width: | Height: | Size: 112 KiB |
BIN
docs/assets/qgc-params.png
Normal file
|
After Width: | Height: | Size: 972 KiB |
@@ -1,183 +0,0 @@
|
||||
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||
<svg
|
||||
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||
xmlns:cc="http://creativecommons.org/ns#"
|
||||
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||
xmlns:svg="http://www.w3.org/2000/svg"
|
||||
xmlns="http://www.w3.org/2000/svg"
|
||||
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||
id="svg2"
|
||||
version="1.1"
|
||||
viewBox="0 0 385.99219 102.04687"
|
||||
height="102.04688pt"
|
||||
width="385.99219pt"
|
||||
sodipodi:docname="Ros_logo.svg"
|
||||
inkscape:export-filename="/home/mguenther/Downloads/ros-press-kit/1280px-Ros_logo.svg.png"
|
||||
inkscape:export-xdpi="238.75999"
|
||||
inkscape:export-ydpi="238.75999"
|
||||
inkscape:version="0.92.5 (2060ec1f9f, 2020-04-08)">
|
||||
<sodipodi:namedview
|
||||
pagecolor="#ffffff"
|
||||
bordercolor="#666666"
|
||||
borderopacity="1"
|
||||
objecttolerance="10"
|
||||
gridtolerance="10"
|
||||
guidetolerance="10"
|
||||
inkscape:pageopacity="0"
|
||||
inkscape:pageshadow="2"
|
||||
inkscape:window-width="2560"
|
||||
inkscape:window-height="1391"
|
||||
id="namedview33"
|
||||
showgrid="false"
|
||||
fit-margin-top="0"
|
||||
fit-margin-left="0"
|
||||
fit-margin-right="0"
|
||||
fit-margin-bottom="0"
|
||||
inkscape:zoom="3.1550388"
|
||||
inkscape:cx="232.61011"
|
||||
inkscape:cy="102.64938"
|
||||
inkscape:window-x="0"
|
||||
inkscape:window-y="25"
|
||||
inkscape:window-maximized="1"
|
||||
inkscape:current-layer="svg2" />
|
||||
<metadata
|
||||
id="metadata58">
|
||||
<rdf:RDF>
|
||||
<cc:Work
|
||||
rdf:about="">
|
||||
<dc:format>image/svg+xml</dc:format>
|
||||
<dc:type
|
||||
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
||||
<dc:title></dc:title>
|
||||
</cc:Work>
|
||||
</rdf:RDF>
|
||||
</metadata>
|
||||
<defs
|
||||
id="defs4">
|
||||
<clipPath
|
||||
id="clip1">
|
||||
<path
|
||||
id="path7"
|
||||
d="M 0.0585938,2 H 22 V 25 H 0.0585938 Z m 0,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
</clipPath>
|
||||
<clipPath
|
||||
id="clip2">
|
||||
<path
|
||||
id="path10"
|
||||
d="M 0.0585938,40 H 22 V 64 H 0.0585938 Z m 0,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
</clipPath>
|
||||
<clipPath
|
||||
id="clip3">
|
||||
<path
|
||||
id="path13"
|
||||
d="M 0.0585938,79 H 22 v 23 H 0.0585938 Z m 0,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
</clipPath>
|
||||
<clipPath
|
||||
id="clip4">
|
||||
<path
|
||||
id="path16"
|
||||
d="m 220,0.894531 h 82 V 102.94141 h -82 z m 0,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
</clipPath>
|
||||
<clipPath
|
||||
id="clip5">
|
||||
<path
|
||||
id="path19"
|
||||
d="m 316,0.894531 h 70.05078 V 102.94141 H 316 Z m 0,0"
|
||||
inkscape:connector-curvature="0" />
|
||||
</clipPath>
|
||||
</defs>
|
||||
<g
|
||||
id="surface839"
|
||||
transform="translate(-0.0585938,-0.894531)">
|
||||
<g
|
||||
id="g22"
|
||||
clip-path="url(#clip1)"
|
||||
style="clip-rule:nonzero">
|
||||
<path
|
||||
id="path24"
|
||||
d="m 21.839844,13.492188 c 0,6.230468 -4.890625,11.285156 -10.917969,11.285156 C 4.890625,24.777344 0,19.722656 0,13.492188 0,7.257812 4.890625,2.207031 10.921875,2.207031 c 6.027344,0 10.917969,5.050781 10.917969,11.285157"
|
||||
style="fill:#212e4a;fill-opacity:1;fill-rule:nonzero;stroke:none"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g26"
|
||||
clip-path="url(#clip2)"
|
||||
style="clip-rule:nonzero">
|
||||
<path
|
||||
id="path28"
|
||||
d="m 21.839844,51.949219 c 0,6.230469 -4.890625,11.285156 -10.917969,11.285156 C 4.890625,63.234375 0,58.179688 0,51.949219 0,45.714844 4.890625,40.664062 10.921875,40.664062 c 6.027344,0 10.917969,5.050782 10.917969,11.285157"
|
||||
style="fill:#212e4a;fill-opacity:1;fill-rule:nonzero;stroke:none"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g30"
|
||||
clip-path="url(#clip3)"
|
||||
style="clip-rule:nonzero">
|
||||
<path
|
||||
id="path32"
|
||||
d="m 21.839844,90.40625 c 0,6.230469 -4.890625,11.28516 -10.917969,11.28516 C 4.890625,101.69141 0,96.636719 0,90.40625 0,84.175781 4.890625,79.121094 10.921875,79.121094 c 6.027344,0 10.917969,5.054687 10.917969,11.285156"
|
||||
style="fill:#212e4a;fill-opacity:1;fill-rule:nonzero;stroke:none"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<path
|
||||
id="path34"
|
||||
d="m 59.945312,51.949219 c 0,6.230469 -4.886718,11.285156 -10.917968,11.285156 -6.03125,0 -10.921875,-5.054687 -10.921875,-11.285156 0,-6.234375 4.890625,-11.285157 10.921875,-11.285157 6.03125,0 10.917968,5.050782 10.917968,11.285157"
|
||||
style="fill:#212e4a;fill-opacity:1;fill-rule:nonzero;stroke:none"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path36"
|
||||
d="m 59.945312,13.492188 c 0,6.230468 -4.886718,11.285156 -10.917968,11.285156 -6.03125,0 -10.921875,-5.054688 -10.921875,-11.285156 0,-6.234376 4.890625,-11.285157 10.921875,-11.285157 6.03125,0 10.917968,5.050781 10.917968,11.285157"
|
||||
style="fill:#212e4a;fill-opacity:1;fill-rule:nonzero;stroke:none"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path38"
|
||||
d="m 98.054688,51.949219 c 0,6.230469 -4.890626,11.285156 -10.921876,11.285156 -6.03125,0 -10.917968,-5.054687 -10.917968,-11.285156 0,-6.234375 4.886718,-11.285157 10.917968,-11.285157 6.03125,0 10.921876,5.050782 10.921876,11.285157"
|
||||
style="fill:#212e4a;fill-opacity:1;fill-rule:nonzero;stroke:none"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path40"
|
||||
d="m 98.054688,13.492188 c 0,6.230468 -4.890626,11.285156 -10.921876,11.285156 -6.03125,0 -10.917968,-5.054688 -10.917968,-11.285156 0,-6.234376 4.886718,-11.285157 10.917968,-11.285157 6.03125,0 10.921876,5.050781 10.921876,11.285157"
|
||||
style="fill:#212e4a;fill-opacity:1;fill-rule:nonzero;stroke:none"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path42"
|
||||
d="m 98.054688,90.40625 c 0,6.230469 -4.890626,11.28516 -10.921876,11.28516 -6.03125,0 -10.917968,-5.054691 -10.917968,-11.28516 0,-6.230469 4.886718,-11.285156 10.917968,-11.285156 6.03125,0 10.921876,5.054687 10.921876,11.285156"
|
||||
style="fill:#212e4a;fill-opacity:1;fill-rule:nonzero;stroke:none"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path44"
|
||||
d="m 59.945312,90.40625 c 0,6.230469 -4.886718,11.28516 -10.917968,11.28516 -6.03125,0 -10.921875,-5.054691 -10.921875,-11.28516 0,-6.230469 4.890625,-11.285156 10.921875,-11.285156 6.03125,0 10.917968,5.054687 10.917968,11.285156"
|
||||
style="fill:#212e4a;fill-opacity:1;fill-rule:nonzero;stroke:none"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path46"
|
||||
d="m 171.61328,16.453125 h -27.91797 v 31.816406 h 27.91797 c 9.57813,0 16.28125,-5.089843 16.28125,-15.835937 0,-10.324219 -6.56641,-15.980469 -16.28125,-15.980469 z M 181.32812,61 200.89453,101.44531 H 184.33984 L 165.31641,62.273438 h -21.6211 V 101.44531 H 129.60156 V 2.449219 h 42.01172 c 16.69531,0 30.78906,9.195312 30.78906,29.558593 0,15.839844 -8.07422,25.597657 -21.07422,28.992188"
|
||||
style="fill:#212e4a;fill-opacity:1;fill-rule:nonzero;stroke:none"
|
||||
inkscape:connector-curvature="0" />
|
||||
<g
|
||||
id="g48"
|
||||
clip-path="url(#clip4)"
|
||||
style="clip-rule:nonzero">
|
||||
<path
|
||||
id="path50"
|
||||
d="m 260.5625,15.746094 c -16.69531,0 -25.86328,14 -25.86328,36.203125 0,22.203125 9.16797,36.203125 25.86328,36.203125 16.83203,0 26,-14 26,-36.203125 0,-22.203125 -9.16797,-36.203125 -26,-36.203125 z m 0,87.253906 c -24.76563,0 -40.50391,-21.070312 -40.50391,-51.050781 0,-29.980469 15.73828,-51.054688 40.50391,-51.054688 24.90625,0 40.64062,21.074219 40.64062,51.054688 C 301.20312,81.929688 285.46875,103 260.5625,103"
|
||||
style="fill:#212e4a;fill-opacity:1;fill-rule:nonzero;stroke:none"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="g52"
|
||||
clip-path="url(#clip5)"
|
||||
style="clip-rule:nonzero">
|
||||
<path
|
||||
id="path54"
|
||||
d="m 350.60937,103 c -13.96093,0 -26,-6.222656 -34.07421,-15.980469 l 10.26171,-10.324219 c 6.4336,7.214844 15.875,11.738282 24.90625,11.738282 13.41016,0 19.83985,-4.808594 19.83985,-14.425782 0,-7.636718 -5.60938,-11.453124 -21.6211,-16.402343 -20.25,-6.222657 -29.96484,-11.457031 -29.96484,-29.132813 0,-17.113281 13.95703,-27.578125 31.60938,-27.578125 13,0 22.85156,4.953125 31.33593,13.4375 l -10.125,10.605469 c -6.02343,-6.363281 -12.86328,-9.476562 -22.30468,-9.476562 -11.22266,0 -16.01172,5.65625 -16.01172,12.304687 0,6.929687 4.3789,10.324219 20.9375,15.414063 18.88281,5.941406 30.65234,12.164062 30.65234,29.839843 C 386.05078,90.839844 375.10156,103 350.60937,103"
|
||||
style="fill:#212e4a;fill-opacity:1;fill-rule:nonzero;stroke:none"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
</svg>
|
||||
|
Before Width: | Height: | Size: 8.5 KiB |
|
Before Width: | Height: | Size: 381 KiB After Width: | Height: | Size: 1.2 MiB |
|
Before Width: | Height: | Size: 178 KiB |
|
Before Width: | Height: | Size: 395 KiB |
@@ -1,7 +1,6 @@
|
||||
# COEX Clover
|
||||
|
||||
<img class="big-clover light" src="../assets/clover42-main.png" alt="Clover 4.2">
|
||||
<img class="big-clover dark" src="../assets/clover42-black.png" alt="Clover 4.2">
|
||||
<img class="center zoom big-clover" src="../assets/clover42-main.png" width="80%" alt="Clover 4.2">
|
||||
|
||||
**Clover** is an educational kit of a programmable quadcopter that consists of popular open source components, and a set of necessary documentation and libraries for working with it.
|
||||
|
||||
|
||||
@@ -17,6 +17,7 @@
|
||||
* [Power setup](power.md)
|
||||
* [Failsafe configuration](failsafe.md)
|
||||
* [Manual flight](flight.md)
|
||||
* [Basics](flight.md)
|
||||
* [Exercises](flight_exercises.md)
|
||||
* [Working with Raspberry Pi](raspberry.md)
|
||||
* [RPi Image](image.md)
|
||||
@@ -49,7 +50,6 @@
|
||||
* [Native setup](simulation_native.md)
|
||||
* [VM setup](simulation_vm.md)
|
||||
* [Usage](simulation_usage.md)
|
||||
* [Setup on M1 computers](simulation_m1.md)
|
||||
* [ROS](ros.md)
|
||||
* [MAVROS](mavros.md)
|
||||
* [Supplementary materials](supplementary.md)
|
||||
@@ -70,7 +70,7 @@
|
||||
* [Remote control app](rc.md)
|
||||
* [Wi-Fi Configuration](network.md)
|
||||
* [UART settings](uart.md)
|
||||
* [PX4 Parameters](parameters.md)
|
||||
* [PX4 Parameters](px4_parameters.md)
|
||||
* [PX4 Logs and Topics](flight_logs.md)
|
||||
* [PX4 Firmware](firmware.md)
|
||||
* [MAVLink](mavlink.md)
|
||||
@@ -100,8 +100,6 @@
|
||||
* [CopterHack-2019](copterhack2019.md)
|
||||
* [CopterHack-2018](copterhack2018.md)
|
||||
* [CopterHack-2017](copterhack2017.md)
|
||||
* [Video contest](video_contest.md)
|
||||
* [Educational contests](educational_contests.md)
|
||||
* [Clover-based projects](projects.md)
|
||||
* [Autonomous Multirotor Landing System (AMLS)](amls.md)
|
||||
* [Drone show](clever-show.md)
|
||||
|
||||
@@ -75,9 +75,9 @@ else:
|
||||
shape = 'undefined'
|
||||
color = 'undefined'
|
||||
|
||||
if shape == 'brown':
|
||||
if shape = 'brown':
|
||||
culture = "greshiha"
|
||||
if shape == 'yellow_orange':
|
||||
if shape = 'yellow_orange':
|
||||
culture = "pshenitsa"
|
||||
|
||||
image_sub = rospy.Subscriber('main_camera/image_raw', Image, image_colback_color)
|
||||
|
||||
@@ -49,7 +49,7 @@ This feature allows getting rid of the system interface elements. Let's go ahead
|
||||
|
||||
This is how the transmitter looks at this stage:
|
||||
|
||||
<img src="../assets/IMG_4397.png" width="50%">
|
||||
<img src="../assets/IMG_4397.PNG" width="50%">
|
||||
|
||||
If you run your application, you will see that the sticks are not functioning. This is due to the fact that *JavaScript* is disabled in our page. To enable it, write the following code:
|
||||
|
||||
|
||||
@@ -1,5 +1,7 @@
|
||||
# ArUco markers
|
||||
|
||||
> **Note** The following applies to [image versions](image.md) **0.16** and up. Older documentation is still available for [for version **0.15.1**](https://github.com/CopterExpress/clover/blob/v0.15.1/docs/en/aruco.md).
|
||||
|
||||
[ArUco markers](https://docs.opencv.org/3.2.0/d5/dae/tutorial_aruco_detection.html) are commonly used for vision-based position estimation.
|
||||
|
||||
Examples of ArUco markers:
|
||||
|
||||
@@ -93,7 +93,7 @@ The marker map adheres to the [ROS coordinate system convention](http://www.ros.
|
||||
|
||||
## VPE setup
|
||||
|
||||
In order to enable vision position estimation you should use the following [PX4 parameters](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`):
|
||||
|
||||
@@ -152,7 +152,7 @@ If the drone's altitude is not stable, try increasing the `MPC_Z_VEL_P` paramete
|
||||
|
||||
## Placing markers on the ceiling
|
||||
|
||||

|
||||

|
||||
|
||||
In order to navigate using markers on the ceiling, mount the onboard camera so that it points up and [adjust the camera frame accordingly](camera_setup.md).
|
||||
|
||||
|
||||
@@ -113,3 +113,7 @@ rospy.spin()
|
||||
```
|
||||
|
||||
Each message contains the marker ID, its corner points on the image and its position relative to the camera.
|
||||
|
||||
---
|
||||
|
||||
Suggested reading: [map-based navigation](aruco_map.md)
|
||||
|
||||
@@ -341,7 +341,7 @@ should be increased up to 4 – 5.
|
||||
|
||||
### ESC assembly
|
||||
|
||||
1. Stick the double-sided adhesive tape to the base of the ESC protective case.
|
||||
1. Stick the double-sided adhesive tape to the base of the ESC protective case 
|
||||
2. Put the ESCs into protective cases. Fasten the assembly to the motor mounts of the frame. 
|
||||
|
||||
### Installation of guard
|
||||
|
||||
@@ -36,7 +36,7 @@ TODO
|
||||
|
||||
Cut the remaining part of the clamp (cable tie) with scissors.
|
||||
|
||||

|
||||

|
||||
|
||||
## Frame elements installation
|
||||
|
||||
@@ -45,7 +45,7 @@ TODO
|
||||
3. Attach the assembled unit to the frame with M3x16 screws, complying with the layout.
|
||||
4. Install the frame for the LED strip, using the slots in the leg holders.
|
||||
|
||||

|
||||

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

|
||||

|
||||
|
||||
## 4 in 1 ESC board and the PDB power-board installation
|
||||
|
||||
@@ -108,7 +108,7 @@ TODO
|
||||
3. Install the PDB power distribution board as shown in the picture (the XT60 connector should point to the tail of the drone).
|
||||
4. Connect the wires of the PCB power supply board and ESC XT30 board.
|
||||
|
||||

|
||||

|
||||
|
||||
## Pairing the receiver and transmitter
|
||||
|
||||
@@ -125,7 +125,7 @@ TODO
|
||||
* Remove the BIND connector from the receiver.
|
||||
* Disconnect the battery.
|
||||
|
||||

|
||||

|
||||
|
||||
> **Hint** If the remote cannot be powered on, or is blocked, see
|
||||
article [remote faults](radioerrors.md).
|
||||
@@ -145,7 +145,7 @@ article [remote faults](radioerrors.md).
|
||||
4. Check the motor rotation direction according to the scheme. Repeat for each motor. Thus, it will be clear which motor is controlled.
|
||||
5. If you have to change the rotation direction, swap any two phase wires of the motor (needs re-connection).
|
||||
|
||||

|
||||

|
||||
|
||||
## Installation and connection of the Pixracer flight controller
|
||||
|
||||
@@ -162,7 +162,7 @@ article [remote faults](radioerrors.md).
|
||||
|
||||
4. Connect the ribbon cable from the radio receiver to the RCIN connector in Pixracer.
|
||||
|
||||

|
||||

|
||||
|
||||
## Raspberry installation
|
||||
|
||||
@@ -186,7 +186,7 @@ article [remote faults](radioerrors.md).
|
||||
|
||||
Use an M3x16 screw and an M3 nut
|
||||
|
||||

|
||||

|
||||
|
||||
## Arduino and FlySky radio receiver installation
|
||||
|
||||
@@ -200,7 +200,7 @@ article [remote faults](radioerrors.md).
|
||||
black -> GND
|
||||
orange, green -> currently not used. They are set to the unused pins of the radio receiver.
|
||||
|
||||

|
||||

|
||||
|
||||
## RPi camera installation
|
||||
|
||||
@@ -213,7 +213,7 @@ article [remote faults](radioerrors.md).
|
||||
|
||||
5. Install the legs into the mounts (4 pcs).
|
||||
|
||||

|
||||

|
||||
|
||||
## Installation of the remaining structural elements
|
||||
|
||||
@@ -223,13 +223,13 @@ article [remote faults](radioerrors.md).
|
||||
|
||||
Secure the upper deck with M3x8 screws (4 pcs.)
|
||||
|
||||

|
||||

|
||||
|
||||
## USB connectors installation
|
||||
|
||||
1. Connect Pixracer to Raspberry using the micro USB - USB cable.
|
||||
2. Connect Arduino to Raspberry using the micro USB - USB cable.
|
||||
|
||||
.
|
||||
.
|
||||
|
||||
Read more about connection in [article](connection.md).
|
||||
|
||||
@@ -6,7 +6,7 @@ Software autorun
|
||||
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.
|
||||
|
||||
@@ -50,12 +50,12 @@ You can add your own node to the list of automatically launched ones. To do this
|
||||
|
||||
The started file must have *permission* to run:
|
||||
|
||||
```bash
|
||||
```(bash)
|
||||
chmod +x my_program.py
|
||||
```
|
||||
|
||||
When scripting languages are used, 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
|
||||
#!/usr/bin/env python3
|
||||
```(bash)
|
||||
#!/usr/bin/env python
|
||||
```
|
||||
|
||||
@@ -49,7 +49,7 @@ The rest of categories contains standard Blockly's blocks.
|
||||
|
||||
### take_off
|
||||
|
||||
<img src="../assets/blocks/take-off.png" srcset="@source/assets/blocks/take-off.png 2x">
|
||||
<img src="../assets/blocks/take-off.png" srcset="../assets/blocks/take-off.png 2x">
|
||||
|
||||
Take off to specified altitude in meters. The altitude may be an arbitrary block, that returns a number.
|
||||
|
||||
@@ -57,7 +57,7 @@ The `wait` flag specifies, if the drone should wait until take off is complete,
|
||||
|
||||
### navigate
|
||||
|
||||
<img src="../assets/blocks/navigate.png" srcset="@source/assets/blocks/navigate.png 2x">
|
||||
<img src="../assets/blocks/navigate.png" srcset="../assets/blocks/navigate.png 2x">
|
||||
|
||||
Navigate to specified point. Coordinates are specified in meters.
|
||||
|
||||
@@ -77,7 +77,7 @@ This block allows to specify the [coordinate frame](frames.md) of the target poi
|
||||
|
||||
### land
|
||||
|
||||
<img src="../assets/blocks/land.png" srcset="@source/assets/blocks/land.png 2x">
|
||||
<img src="../assets/blocks/land.png" srcset="../assets/blocks/land.png 2x">
|
||||
|
||||
Land the drone.
|
||||
|
||||
@@ -85,31 +85,31 @@ The `wait` flag specifies, if the drone should wait until landing is complete, b
|
||||
|
||||
### wait
|
||||
|
||||
<img src="../assets/blocks/wait.png" srcset="@source/assets/blocks/wait.png 2x">
|
||||
<img src="../assets/blocks/wait.png" srcset="../assets/blocks/wait.png 2x">
|
||||
|
||||
Wait specified time period in seconds. The time period may be an arbitrary block, that returns a number.
|
||||
|
||||
### wait_arrival
|
||||
|
||||
<img src="../assets/blocks/wait-arrival.png" srcset="@source/assets/blocks/wait-arrival.png 2x">
|
||||
<img src="../assets/blocks/wait-arrival.png" srcset="../assets/blocks/wait-arrival.png 2x">
|
||||
|
||||
Wait, until the drone reaches [navigate](#navigate)-block's target point.
|
||||
|
||||
### get_position
|
||||
|
||||
<img src="../assets/blocks/get-position.png" srcset="@source/assets/blocks/get-position.png 2x">
|
||||
<img src="../assets/blocks/get-position.png" srcset="../assets/blocks/get-position.png 2x">
|
||||
|
||||
The block returns current position, velocity or yaw angle of the drone relative to the specified [coordinate frame](#relative_to).
|
||||
|
||||
### set_effect
|
||||
|
||||
<img src="../assets/blocks/set-effect.png" srcset="@source/assets/blocks/set-effect.png 2x">
|
||||
<img src="../assets/blocks/set-effect.png" srcset="../assets/blocks/set-effect.png 2x">
|
||||
|
||||
The block allows to set animations to LED strip, similarly to [`set_effect`](leds.md#set_effect) ROS-service.
|
||||
|
||||
Example of using the block with a random color (colors-related blocks are located in *Colour* category):
|
||||
|
||||
<img src="../assets/blocks/random-color.png" srcset="@source/assets/blocks/random-color.png 2x">
|
||||
<img src="../assets/blocks/random-color.png" srcset="../assets/blocks/random-color.png 2x">
|
||||
|
||||
### Work with GPIO {#GPIO}
|
||||
|
||||
|
||||
@@ -14,7 +14,7 @@ In order to perform the sensor calibration, select the *Vehicle Setup* tab and c
|
||||
4. Put the drone in one of the orientations marked by the red outline and wait for the appropriate outline to turn yellow.
|
||||
5. Spin the drone as required until the outline turns green. Do this for all orientations.
|
||||
|
||||
Read more in the PX4 docs: https://docs.px4.io/master/en/config/compass.html.
|
||||
Read more in the PX4 docs: https://docs.px4.io/v1.9.0/en/config/compass.html.
|
||||
|
||||
## 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.
|
||||
|
||||
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
|
||||
|
||||
@@ -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.
|
||||
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
|
||||
|
||||
@@ -50,4 +50,6 @@ Read more in the PX4 docs: https://docs.px4.io/master/en/config/accelerometer.ht
|
||||
4. Press *OK*.
|
||||
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).
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
# 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.
|
||||
|
||||
|
||||
@@ -16,7 +16,7 @@ USB connection is the preferred way to connect to the flight controller.
|
||||
|
||||
The `connected` field should have the `True` value.s
|
||||
|
||||
> **Hint** You need to set the `CBRK_USB_CHK` [parameter](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
|
||||
|
||||
@@ -50,3 +50,5 @@ In order to connect to a local or a remote [SITL](sitl.md) instance set the `fcu
|
||||
<arg name="fcu_conn" default="udp"/>
|
||||
<arg name="fcu_ip" default="127.0.0.1"/>
|
||||
```
|
||||
|
||||
**Next**: [Using QGroundControl over Wi-Fi](gcs_bridge.md)
|
||||
|
||||
@@ -8,39 +8,6 @@ You can see the articles of the CopterHack 2021 finalist teams by the link [Copt
|
||||
|
||||
The proposed projects have to be open-source and be compatible with the Clover quadcopter platform. Teams will work on their projects throughout the competition, bringing them closer to the state of the finished product. Industry experts will assist the participants through lectures and regular feedback.
|
||||
|
||||
## Projects of the contest's participants {#participants}
|
||||
|
||||
|Place|Team|Project|Points|
|
||||
|:-:|-|-|-|
|
||||
||🇧🇾 FTL|[Advanced Clover 2](https://github.com/FTL-team/clover/blob/FTL-advancedClover2/docs/ru/advanced_clover_simulator.md)||
|
||||
||🇷🇺 Stereo|[Neural obstacle avoidance](https://github.com/den250400/clover/blob/neural-obstacle-avoidance/docs/en/neural-obstacle-avoidance.md)||
|
||||
||🇷🇺 Space clowns|[Copter For Space](https://github.com/slavikyd/clover/blob/patch-3/docs/ru/c4s.md)||
|
||||
||🇷🇺 R.S.|[Drone Hawk](https://github.com/slavaroot/clover/blob/droneHawkSecurity/docs/ru/drone-hawk-security.md)||
|
||||
||🇲🇾 Moopt|[IoT Water Monitoring & Optimization](https://github.com/kafechew/clover/blob/master/docs/en/moopt-uav.md)||
|
||||
||🇧🇷 Atena - Grupo SEMEAR|[Swarm in Blocks](https://github.com/Grupo-SEMEAR-USP/clover/blob/Swarm_in_Blocks/docs/en/swarm_in_blocks.md)||
|
||||
||🇷🇺 Clover Rescue Team|[Rescue Clover](https://github.com/DevMBS/clover/blob/CloverRescueTeam/docs/ru/clover-rescue-team.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)||
|
||||
||🇮🇳 DJS Phoenix|[Autonomous valet parking drone assistance](https://github.com/DJSPhoenix/clover/blob/DJSPhoenix-Ikshana/docs/en/djs_phoenix_ikshana.md)||
|
||||
||🇷🇺 SPECTRE|[SPECTRE](https://github.com/alakhmenev/clover/blob/spectre_team/docs/ru/spectre_team.md)||
|
||||
||🇷🇺 С305|[Система мониторинга воздуха](https://github.com/Ruslan2288/clover/blob/master/docs/ru/air_monitor.md)| |
|
||||
|✕|🇰🇬 Alatoo University Team|[Облачная платформа для симулятора Клевера](https://github.com/pteacher/clover/blob/clover_simulator/docs/ru/clover-development-studio.md)||
|
||||
|✕|🇷🇺 Clevertron|[Clevertron](https://github.com/Daniel-drone/clover/blob/Clevertron-1/docs/ru/clevertron.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)||
|
||||
|✕|🇩🇪 Inondro|[Inondro Pix](https://github.com/Inondro/clover/blob/inondro-pix/docs/en/inondro_copterhack22_pix.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)||
|
||||
|✕|🇻🇳 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)| |
|
||||
|
||||
✕ – teams which haven't qualified for the Final.
|
||||
|
||||
## Company case competition
|
||||
|
||||
Teams are welcome to dive into the development of the following company cases:
|
||||
@@ -107,38 +74,40 @@ Prepare your application and send it as a Draft Pull Request to [Clover reposito
|
||||
|
||||
4. Fill out your application by the recommended template:
|
||||
|
||||
```markdown
|
||||
# Project name
|
||||
|
||||
[CopterHack-2022](copterhack2022.md), team **Team name**.
|
||||
|
||||
## Team information
|
||||
|
||||
The list of team members:
|
||||
|
||||
(Describe the team: full name, contacts (e-mail/Telegram username), role in the team).
|
||||
|
||||
* Alexander Sokolov, @aleksandrsokolov111, engineer.
|
||||
* Elena Smirnova, @elenasmirnova111, programmer.
|
||||
|
||||
## Project description
|
||||
|
||||
### Project idea
|
||||
|
||||
Briefly describe the idea and stage of the project.
|
||||
|
||||
### The potential outcomes
|
||||
|
||||
Describe how you see the project result.
|
||||
|
||||
### Using Clover platform
|
||||
|
||||
Describe how the Clover platform will be used in your project.
|
||||
|
||||
### Additional information at the request of participants
|
||||
|
||||
For example, information about the team's experience working on projects, attach a link to articles, videos.
|
||||
```
|
||||
```markdown
|
||||
# Project name
|
||||
|
||||
[CopterHack-2022](copterhack2022.md), team **Team name**.
|
||||
|
||||
## Team information
|
||||
|
||||
The list of team members:
|
||||
|
||||
(Describe the team: full name, contacts (e-mail/Telegram username), role in the team).
|
||||
|
||||
* Alexander Sokolov, @aleksandrsokolov111, engineer.
|
||||
* Elena Smirnova, @elenasmirnova111, programmer.
|
||||
|
||||
## Project description
|
||||
|
||||
### Project idea
|
||||
|
||||
Briefly describe the idea and stage of the project.
|
||||
|
||||
### The potential outcomes
|
||||
|
||||
Describe how you see the project result.
|
||||
|
||||
### Using Clover platform
|
||||
|
||||
Describe how the Clover platform will be used in your project.
|
||||
|
||||
### Additional information at the request of participants
|
||||
|
||||
For example, information about the team's experience working on projects, attach a link to articles, videos.
|
||||
```
|
||||
|
||||
<!-- markdownlint-disable MD029 -->
|
||||
|
||||
5. Go to the bottom of the page and create a new branch with the title of your article:
|
||||
|
||||
@@ -154,9 +123,7 @@ Prepare your application and send it as a Draft Pull Request to [Clover reposito
|
||||
|
||||
8. In the Pull Request comments, you will be given feedback on the application. On the contest page, in the section "Projects of the contest participants", a link to your application in your fork will be published.
|
||||
|
||||
9. Note the *Checks* block at the bottom, a check mark should appear in the *Documentation* field. If a cross appeared, click *Details* link to see the list of issues in you article found by markdownlint. If you need to change added files, edit them in you branch – changes will appear in the Pull Request automatically. **Do not open a new Pull Request for the same application**.
|
||||
|
||||
10. During the contest, you will work on this document, bringing it closer to the state of the finished article. By the end of the contest, you will publish your article, which will be the result of your work in CopterHack 2022.
|
||||
9. During the contest, you will work on this document, bringing it closer to the state of the finished article. By the end of the contest, you will publish your article, which will be the result of your work in CopterHack 2022.
|
||||
|
||||
As soon as the link to the application is added to this page in the section "Projects of the contest's participants", your team has become an official participant of the CopterHack 2022!
|
||||
|
||||
@@ -164,6 +131,10 @@ Contest participants will be added to the special Telegram group, where one can
|
||||
|
||||
> **Info** There are no restrictions on the age, education, and number of people in the team.
|
||||
|
||||
## Projects of the contest's participants
|
||||
|
||||
Applications will be published as they will become available.
|
||||
|
||||
---
|
||||
|
||||
For all questions: [CopterHack 2022](https://t.me/CopterHack).
|
||||
|
||||
@@ -10,9 +10,9 @@ People strive to teach artificial intelligence everything they can do themselves
|
||||
|
||||
## Models and assembly
|
||||
|
||||
<img class="center zoom" src="../assets/ddrone/full_holder.png" width="300">
|
||||
<img class="center" src="../assets/ddrone/full_holder.png" width="300" class="zoom">
|
||||
|
||||
<img class="center zoom" src="../assets/ddrone/full_holder_in_real.jpg" width="300">
|
||||
<img class="center" src="../assets/ddrone/full_holder_in_real.jpg" width="300" class="zoom">
|
||||
|
||||
To complete the project you need to have in stock:
|
||||
|
||||
@@ -43,9 +43,9 @@ If the diameter of the can is less than the diameter of the holder, we use the p
|
||||
|
||||
**Pressing mechanism.** To push the valve, we will use a screw drive with a fixed nut. A bar with holes will be attached to the servo, which will include the racks attached to the nut. This helps the servo to move only on one axis, up and down. We also modeled the cap for the spray can button, since the surface of the nozzle is uneven.
|
||||
|
||||
<img class="center zoom" src="../assets/ddrone/pressing_mechanism.png" width="300">
|
||||
<img class="center" src="../assets/ddrone/pressing_mechanism.png" width="300" class="zoom">
|
||||
|
||||
<img class="center zoom" src="../assets/ddrone/pressing_mechanism_in_real.jpg" width="300">
|
||||
<img class="center" src="../assets/ddrone/pressing_mechanism_in_real.jpg" width="300" class="zoom">
|
||||
|
||||
## Before launching
|
||||
|
||||
@@ -81,11 +81,11 @@ Now to open the web interface, click on the link [http://192.168.11.1/clover/dro
|
||||
|
||||
Our drone is launched via [website](https://perizatkurmanbaeva.github.io/visual_ddrone). The web interface allows you to draw and encode what you draw in G-code. The coordinate data will be transmitted for further processing and execution by the copter.
|
||||
|
||||
<img class="center zoom" src="../assets/ddrone/screen_2.png" width="600">
|
||||
<img class="center" src="../assets/ddrone/screen_2.png" width="600" class="zoom">
|
||||
|
||||
We pick the web interface to control the copter because it is easier for the user.
|
||||
|
||||
<img class="center zoom" src="../assets/ddrone/instruction.png" width="300">
|
||||
<img class="center" src="../assets/ddrone/instruction.png" width="300" class="zoom">
|
||||
|
||||
## Flights
|
||||
|
||||
@@ -95,4 +95,4 @@ We pick the web interface to control the copter because it is easier for the use
|
||||
|
||||
Project was created with financial support of International Ala-Too University.
|
||||
|
||||

|
||||

|
||||
|
||||
@@ -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.
|
||||
@@ -4,10 +4,10 @@ Main article is available at https://docs.px4.io/master/en/config/safety.html.
|
||||
|
||||
The *Safety* panel allows you to configure actions that should be performed when a failsafe is triggered. You should at the very least configure the RC Loss failsafe, which is triggered when the RC transmitter link is lost:
|
||||
|
||||
1. 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:
|
||||
* *Land mode* – transition to automatic land mode;
|
||||
* *Terminate* – set all outputs to their failsafe values.
|
||||
3. Set the timeout value before RC Loss triggers in the *RC Loss Timeout* field. We recommend setting it to 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">
|
||||
|
||||
@@ -77,19 +77,19 @@ PX4 may be compiled from the source and automatically flashed to the flight cont
|
||||
To do this, clone the PX4 repository:
|
||||
|
||||
```bash
|
||||
git clone https://github.com/PX4/PX4-Autopilot.git
|
||||
git clone https://github.com/PX4/Firmware.git
|
||||
```
|
||||
|
||||
Select the appropriate version (tag) using `git checkout`. Then compile and upload the firmware:
|
||||
|
||||
```bash
|
||||
make px4_fmu-v4_default upload
|
||||
```
|
||||
make px4fmu-v4_default upload
|
||||
```
|
||||
|
||||
Where `px4_fmu-v4_default` is the required firmware variant.
|
||||
Where `px4fmu-v4_default` is the required firmware variant.
|
||||
|
||||
In order to upload the `v3` firmware to Pixhawk, you may need to use the `force_upload` option:
|
||||
|
||||
```bash
|
||||
make px4_fmu-v3_default force-upload
|
||||
```
|
||||
make px4fmu-v3_default force-upload
|
||||
```
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
# 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.
|
||||
|
||||
@@ -106,3 +106,5 @@ When the *Kill Switch* is activated, no control signals are sent to the motors a
|
||||
> **Caution** Be careful, *Kill Switch* does not put the copter into *Disarmed* state!
|
||||
|
||||
Before disabling the *Kill Switch*, make sure the throttle stick is its down position and the aircraft is in *Disarmed* state. If the throttle stick is not in the lower position, when the *Kill Switch* is turned off, a signal corresponding to the stick position will be sent to the motors, which will lead your copter to jerk.
|
||||
|
||||
**Next**: [Drone control exercises](flight_exercises.md).
|
||||
|
||||
@@ -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;
|
||||
* `body` is bound to the drone, but its Z axis points up regardless of the drone's pitch and roll. It is shown by the red, blue and green lines in the illustration;
|
||||
* <a name="navigate_target"></a>`navigate_target` is bound to the current navigation target (as set by the [navigate](simple_offboard.md#navigate) service);
|
||||
* `setpoint` is current position setpoint;
|
||||
* `main_camera_optical` is the coordinate system, [linked to the main camera](camera_setup.md#frame);
|
||||
* `setpoint` is current position setpoint.
|
||||
|
||||
Additional frames become available when [ArUco positioning system](aruco.md) is active:
|
||||
|
||||
|
||||
@@ -67,3 +67,5 @@ Change parameter `gcs_bridge` in the launch file:
|
||||
```
|
||||
|
||||
After opening the QGroundControl application, the connection should be established automatically.
|
||||
|
||||
**Next**: [Remote access using SSH](ssh.md)
|
||||
|
||||
@@ -43,14 +43,14 @@ After printing the first version of the frame we discovered the following proble
|
||||
|
||||
To conquer those problems we made several changes. We increased the minimal thickness for the generated structures and generated a new model. We changed the settings in the slicer so that the support structure could be removed easier as well as changed the infill structure. Finally we changed the filament and increased the printing temperature. Further we concluded that printing with a water dissolvable support structure would be optimal, however as of right now we don’t have access to a printer capable of that.
|
||||
|
||||

|
||||

|
||||
|
||||
#### Prototype 2
|
||||
|
||||
This prototype took 48 hours of printing and used 277 grams of filament including 100 grams for the support. Installation of the components is very easy as no other tools than a screwdriver are needed. This prototype was the first to take flight in January 2021. Please see [this](https://youtu.be/M4f8_JmJADM) video.
|
||||
|
||||
<p float="left">
|
||||
<img src="../assets/generative-design-frame/p21.jpg" width="32%" class="zoom"/>
|
||||
<img src="../assets/generative-design-frame/p21.JPG" width="32%" class="zoom"/>
|
||||
<img src="../assets/generative-design-frame/p22.jpg" width="32%" class="zoom"/>
|
||||
<img src="../assets/generative-design-frame/p23.jpg" width="32%" class="zoom"/>
|
||||
</p>
|
||||
@@ -73,7 +73,7 @@ Videos:
|
||||
|
||||
In this final prototype we have changed the preserved geometry on the bottom to form a rectangle for added stability. We have also changed some of the forces on the points we observed breakings in our previous tests. We have also updated the prop guard to make it more stable and increased the area around the screws, so it would break harder. The frame without the prop guard weighs only 150g making it significantly lighter than the default frame.
|
||||
|
||||

|
||||

|
||||
|
||||
### Benefits
|
||||
|
||||
|
||||
@@ -15,3 +15,5 @@ The RPi image for Clover contains all the necessary software for working with Cl
|
||||
<img src="../assets/etcher.png" class="zoom">
|
||||
|
||||
After flashing the image on the MicroSD-card, you can [connect to the Clover over Wi-Fi](wifi.md), use [wireless connection in QGroundControl](gcs_bridge.md), gain access to the Raspberry [over SSH](ssh.md) and use all the other features.
|
||||
|
||||
**Next:** [Connecting over Wi-Fi](wifi.md).
|
||||
|
||||
@@ -38,7 +38,7 @@ rostopic echo /rangefinder/range
|
||||
|
||||
> **Hint** We recommend using our [custom PX4 firmware for Clover](firmware.md#modified-firmware-for-clover) for best laser rangefinder support.
|
||||
|
||||
PX4 should be properly [configured](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`):
|
||||
|
||||
@@ -75,7 +75,7 @@ from sensor_msgs.msg import Range
|
||||
|
||||
# ...
|
||||
|
||||
dist = rospy.wait_for_message('rangefinder/range', Range).range
|
||||
data = rospy.wait_for_message('rangefinder/range', Range)
|
||||
```
|
||||
|
||||
### Data visualization
|
||||
|
||||
@@ -158,9 +158,3 @@ Current LED strip state is published in the `/led/state` ROS topic. You can view
|
||||
```bash
|
||||
rostopic echo /led/state
|
||||
```
|
||||
|
||||
Using the same topic you can get the configured number os LEDs, using Python:
|
||||
|
||||
```python
|
||||
led_count = len(rospy.wait_for_message('led/state', LEDStateArray, timeout=10).leds)
|
||||
```
|
||||
|
||||
@@ -63,64 +63,3 @@ Then connect the signal output of the circuit to the selected port and solder th
|
||||
2. Use a zip tie to pull the assembled circuit to the back of the deck.
|
||||
3. Plug the Arduino *D11* signal pin into one of the *AUX* pins on the flight controller.
|
||||
4. Plug the power wire of the electromagnetic gripper to JST 5V.
|
||||
|
||||
## Setting up electromagnetic gripper
|
||||
|
||||
To control the magnet through Arduino Nano, use the following code:
|
||||
|
||||
```cpp
|
||||
void setup() {
|
||||
pinMode(11, INPUT);
|
||||
pinMode(13, OUTPUT);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
if (int duration = pulseIn(11, HIGH) > 1200) {
|
||||
digitalWrite(13, HIGH);
|
||||
} else {
|
||||
digitalWrite(13, LOW);
|
||||
}
|
||||
}
|
||||
```
|
||||
|
||||
To monitor the status of the electromagnetic gripper, you can connect the *ws281x* LED strip (included to Clover kit). Connect it to power +5v – 5v, ground GND – GND, and signal wire DIN – Arduino D12.
|
||||
|
||||
To control the magnet and monitor it using the LED strip, use the following code:
|
||||
|
||||
```cpp
|
||||
#include <Adafruit_NeoPixel.h>
|
||||
#define NUMPIXELS 72
|
||||
#define PIN 12
|
||||
int pin = 11;
|
||||
int led = 13;
|
||||
|
||||
unsigned long duration;
|
||||
Adafruit_NeoPixel strip (NUMPIXELS, PIN, NEO_GRB + NEO_KHZ800);
|
||||
|
||||
void setup() {
|
||||
strip.begin();
|
||||
strip.setBrightness(10);
|
||||
Serial.begin(9600);
|
||||
pinMode(pin, INPUT);
|
||||
pinMode(led, OUTPUT);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
duration = pulseIn(pin, HIGH);
|
||||
Serial.println(duration);
|
||||
delay(100);
|
||||
if (duration >= 1500) {
|
||||
digitalWrite(led, HIGH);
|
||||
for (int i = -1; i < NUMPIXELS; i++) {
|
||||
strip.setPixelColor(i, strip.Color(255, 0, 0));
|
||||
strip.show();
|
||||
}
|
||||
} else {
|
||||
digitalWrite(led, LOW);
|
||||
for (int i = -1; i < NUMPIXELS; i++) {
|
||||
strip.setPixelColor(i, strip.Color(0, 255, 0));
|
||||
strip.show();
|
||||
}
|
||||
}
|
||||
}
|
||||
```
|
||||
|
||||
@@ -29,7 +29,7 @@ Examples of MAVLink messages:
|
||||
* `GLOBAL_POSITION_INT` – global position of the quadcopter (latitude/longitude/altitude);
|
||||
* `COMMAND_LONG` – a command to the quadcopter (take off, land, toggle modes, etc).
|
||||
|
||||
A complete list of MAVLink messages is available in [MAVLink documentation](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
|
||||
|
||||
|
||||
@@ -56,13 +56,13 @@
|
||||
12. Install the assembled grip onto the aircraft from below.
|
||||
|
||||
<div class="image-group">
|
||||
<img src="../assets/mechanical_grip/mech_grip_15.png" width=300 class="zoom border">
|
||||
<img src="../assets/mechanical_grip/mech_grip_16.png" width=300 class="zoom border">
|
||||
<img src="../assets/mechanical_grip/mech_grip_17.png" width=300 class="zoom border">
|
||||
</div>
|
||||
|
||||
13. Insert the servo cable into the *AUX* 1-2 output on the flight controller.
|
||||
|
||||
<img src="../assets/mechanical_grip/mech_grip_17.png" width=300 class="zoom border center">
|
||||
<img src="../assets/mechanical_grip/mech_grip_18.png" width=300 class="zoom border center">
|
||||
|
||||
14. Go to the *Radio* tab to control capture with the remote control.
|
||||
15. In the *AUX 1/2 Passthrough RC channel* parameter, select the desired channel.
|
||||
|
||||
@@ -4,11 +4,10 @@ PX4 **mode** determines how the vehicle should react to commands and RC signals.
|
||||
|
||||
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.
|
||||
3. Set the *Mode Channel* to the SwC switch (*Channel 6*).
|
||||
4. Optionally, set the *Emergency Kill Switch Channel* to SwA switch (*Channel 5*).
|
||||
5. Set desired flight modes.
|
||||
3. Choose SwC (Channel 6) as mode selection switch.
|
||||
4. Set desired flight modes.
|
||||
|
||||
The following flight modes are recommended:
|
||||
|
||||
@@ -16,8 +15,8 @@ In order to configure flight modes:
|
||||
* Flight Mode 4: *Altitude*.
|
||||
* Flight Mode 6: *Position*.
|
||||
|
||||
6. Check mode switching by changing the switch position.
|
||||
7. Choose SwA (Channel 5) as emergency motor stop (*Kill switch*).
|
||||
5. Check mode switching by changing the switch position.
|
||||
6. Choose SwA (Channel 5) as emergency motor stop (*Kill switch*).
|
||||
|
||||
<img src="../assets/qgc-modes.png" class="zoom" alt="QGroundControl modes">
|
||||
|
||||
@@ -46,3 +45,5 @@ In autonomous flight modes the quadcopter ignores the control signals from the t
|
||||
* **AUTO.LAND** – the copter lands at the current position.
|
||||
|
||||
Additional information: https://dev.px4.io/en/concept/flight_modes.html.
|
||||
|
||||
**Next**: [Power setup](power.md).
|
||||
|
||||
@@ -1,10 +1,12 @@
|
||||
# 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
|
||||
|
||||
> **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`:
|
||||
|
||||
@@ -12,7 +14,7 @@ Enable Optical Flow in the file `~/catkin_ws/src/clover/clover/launch/clover.lau
|
||||
<arg name="optical_flow" default="true"/>
|
||||
```
|
||||
|
||||
Optical Flow publishes data in `/mavros/px4flow/raw/send` topic. In the topic `/optical_flow/debug` is also published a visualization, that can be viewed with [web_video_server](web_video_server.md).
|
||||
Optical Flow publishes data in `mavros/px4flow/raw/send` topic. In the topic `optical_flow/debug` is also published a visualization, that can be viewed with [web_video_server](web_video_server.md).
|
||||
|
||||
> **Info** Correct connection and [setup](camera.md) of the camera module is needed for proper functioning.
|
||||
|
||||
@@ -29,7 +31,7 @@ When using **EKF2** (parameter `SYS_MC_EST_GROUP` = `ekf2`):
|
||||
* `EKF2_OF_N_MAX` - 0.2.
|
||||
* `SENS_FLOW_ROT` – No rotation.
|
||||
* `SENS_FLOW_MAXHGT` – 4.0 (for the rangefinder VL53L1X)
|
||||
* `SENS_FLOW_MINHGT` – 0.0 (for the rangefinder VL53L1X)
|
||||
* `SENS_FLOW_MINHGT` – 0.01 (for the rangefinder VL53L1X)
|
||||
* Optional: `EKF2_HGT_MODE` – range sensor (cf. [rangefinder setup](laser.md)).
|
||||
|
||||
When using **LPE** (parameter `SYS_MC_EST_GROUP` = `local_position_estimator, attitude_estimator_q`):
|
||||
@@ -41,7 +43,7 @@ When using **LPE** (parameter `SYS_MC_EST_GROUP` = `local_position_estimator, at
|
||||
* `LPE_FLW_RR` – 0.0.
|
||||
* `SENS_FLOW_ROT` – No rotation.
|
||||
* `SENS_FLOW_MAXHGT` – 4.0 (for the rangefinder VL53L1X)
|
||||
* `SENS_FLOW_MINHGT` – 0.0 (for the rangefinder VL53L1X)
|
||||
* `SENS_FLOW_MINHGT` – 0.01 (for the rangefinder VL53L1X)
|
||||
* Optional: `LPE_FUSION` – flag 'pub agl as lpos down' is on (see [rangefinder setup](laser.md).
|
||||
|
||||
[The `selfcheck.py` utility](selfcheck.md) will help you verify that all settings are correctly set.
|
||||
|
||||
@@ -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.0|For [VL53L1X](laser.md) rangefinder|
|
||||
|`SENS_FLOW_MAXHGT`|4.0|For [VL53L1X](laser.md) rangefinder|
|
||||
|`SENS_FLOW_MAXR`|10.0||
|
||||
|`SYS_HAS_MAG`|0|If impossible to run the magnetometer (*No mags found* error)|
|
||||
|
||||
### Estimator subsystem parameters
|
||||
|
||||
In case of using LPE ([COEX patched firmware](firmware.md)):
|
||||
|
||||
|Parameter|Value|Comment|
|
||||
|-|-|-|
|
||||
|`LPE_FUSION`|86|Checkboxes: *flow* + *vis* + *land Detector* + *gyro comp*. If flying over horizontal floor *pub agl as lpos down* checkbox is allowed.<br>Details: [Optical Flow](optical_flow.md), [ArUco markers](aruco_map.md), [GPS](gps.md).|
|
||||
|`LPE_VIS_DELAY`|0.0||
|
||||
|`LPE_VIS_Z`|0.1||
|
||||
|`LPE_FLW_SCALE`|1.0||
|
||||
|`LPE_FLW_R`|0.2||
|
||||
|`LPE_FLW_RR`|0.0||
|
||||
|`LPE_FLW_QMIN`|10||
|
||||
|`ATT_W_EXT_HDG`|0.5|Enabling usage of external yaw angle (when navigating using [markers map](aruco_map.md))|
|
||||
|`ATT_EXT_HDG_M`|1 (*Vision*)||
|
||||
|`ATT_W_MAG`|0|Disabling usage of the magnetometer (when navigating indoor)|
|
||||
|
||||
In case of using EKF2 (official firmware):
|
||||
|
||||
<!-- markdownlint-disable MD044 -->
|
||||
|
||||
|Parameter|Value|Comment|
|
||||
|-|-|-|
|
||||
|`EKF2_AID_MASK`|27|Checkboxes: (optionally) *gps* + *flow* + *vision position* + *vision yaw*.<br>Details: [Optical Flow](optical_flow.md), [ArUco markers](aruco_map.md), [GPS](gps.md).|
|
||||
|`EKF2_OF_DELAY`|0||
|
||||
|`EKF2_OF_QMIN`|10||
|
||||
|`EKF2_OF_N_MIN`|0.05||
|
||||
|`EKF2_OF_N_MAX`|0.2||
|
||||
|`EKF2_HGT_MODE`|2 (*Range sensor*)|If the [rangefinder](laser.md) is present and flying over horizontal floor|
|
||||
|`EKF2_EVA_NOISE`|0.1||
|
||||
|`EKF2_EVP_NOISE`|0.1||
|
||||
|`EKF2_EV_DELAY`|0||
|
||||
|`EKF2_MAG_TYPE`|5 (*None*)|Disabling usage of the magnetometer (when navigating indoor)|
|
||||
|
||||
<!-- markdownlint-enable MD031 -->
|
||||
|
||||
> **Info** See also: list of default parameters of the [Clover simulator](simulation.md): https://github.com/CopterExpress/clover/blob/master/clover_simulation/airframes/4500_clover.
|
||||
|
||||
## Additional information
|
||||
|
||||
The `SYS_MC_EST_GROUP` parameter defines the estimator subsystem to use.
|
||||
|
||||
Estimator subsystem is a group of modules that calculates the current state of the copter using readings from the sensors. The copter state includes:
|
||||
|
||||
* Angle rate of the copter – pitch_rate, roll_rate, yaw_rate;
|
||||
* Copter orientation (in the local coordinate system) – pitch, roll, yaw (one of presentations);
|
||||
* Copter position (in the local coordinate system) – x, y, z;
|
||||
* Copter speed (in the local coordinate system) – vx, vy, vz;
|
||||
* Global coordinates of the copter – latitude, longitude, altitude;
|
||||
* Altitude above the surface;
|
||||
* Other parameters (the drift of gyroscopes, wind speed, etc.).
|
||||
|
||||
`SYS_AUTOCONFIG` — resets all parameters (sets to 1).
|
||||
|
||||
## EKF2
|
||||
|
||||
`EKF2_AID_MASK` — selects sensors that are used by EKF2 to calculate the copter state.
|
||||
|
||||
`EKF2_HGT_MODE` is the main source of height data (z in the local coordinate system):
|
||||
|
||||
* 0 – pressure reading on the barometer.
|
||||
* 1 – GPS.
|
||||
* 2 – distance meter (for example, vl53l1x).
|
||||
* 3 – data from VPE.
|
||||
|
||||
Variant 2 is the most accurate; however, it is correct to use it only if the surface the copter flies over is flat. Otherwise, the Z axis origin will move up and down with the altitude of the surface.
|
||||
|
||||
## Multicopter Position Control
|
||||
|
||||
These parameters adjust the flight of the copter by position (POSCTL, OFFBOARD, AUTO modes).
|
||||
|
||||
`MPC_THR_HOVER` — hovering throttle. This option is to set to the approximate percentage of throttle needed to make the copter maintain its altitude. If copter has a tendency to gain or lose altitude during the hovering mode, reduce or increase this value.
|
||||
|
||||
`MPC_XY_P` – position factor *P* of the ESC. This parameter affects how sharply the copter will react to the position commands. A too high value may cause overshoots.
|
||||
|
||||
`MPC_XY_VEL_P` – speed factor *P* of the ESC. This parameter also affects the accuracy and sharpness of copter execution of the given position. A too high value may cause overshoots.
|
||||
|
||||
`MPC_XY_VEL_MAX` — the maximum horizontal speed in POSCTL, OFFBOARD, AUTO modes.
|
||||
|
||||
`MPC_Z_P`, `MPC_Z_VEL_P` – vertical position and speed factors *P* of the ESCs they determine the copter's ability to maintain the desired altitude.
|
||||
|
||||
`MPC_LAND_SPEED` is the vertical velocity of landing in the LAND mode.
|
||||
|
||||
## LPE + Q attitude estimator
|
||||
|
||||
These parameters configure the behavior of the `lpe` and `q` modules, which compute the state (orientation, position) of the copter. These parameters apply **only** if the `SYS_MC_EST_GROUP` parameter is set to `1` (local_position_estimator, attitude_estimator_q).
|
||||
|
||||
## Commander
|
||||
|
||||
Prearm checks, switching the modes and states of the copter.
|
||||
|
||||
## Sensors
|
||||
|
||||
Enabling, disabling and configuring various sensors.
|
||||
@@ -6,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.
|
||||
|
||||
1. In QGroundControl software, go the *Vehicle Setup* panel and choose the *Power* menu.
|
||||
2. Set the *Number of cells* parameter according to the number of cells in your battery (*3* for the Clover 4 drone).
|
||||
3. Calculate the voltage divider:
|
||||
If there is no voltage indicator or manual calibration is not possible, set the average value of the voltage divider for the Clover 4 kit (*Voltage divider* = 11).
|
||||
|
||||
1. Set the *Number of cells* parameter according to the number of cells in your battery (*3* for the Clover 4 drone).
|
||||
2. Calculate the voltage divider:
|
||||
* Measure voltage across the battery (you may use a battery voltage tester for that).
|
||||
* Press the *Calculate* button next to the *Voltage divider* label.
|
||||
* Put the battery voltage into the prompt and click *Calculate*.
|
||||
* Press *Close* to save the calculated value.
|
||||
|
||||
If there is no voltage indicator or manual calibration is not possible, set the average value of the voltage divider for the Clover 4 kit (*Voltage divider* = 11).
|
||||
|
||||
<img src="../assets/qgc-voltage-divider.png" class="zoom">
|
||||
|
||||
Further reading: https://docs.qgroundcontrol.com/en/SetupView/Power.html.
|
||||
@@ -31,4 +30,6 @@ Further reading: https://docs.qgroundcontrol.com/en/SetupView/Power.html.
|
||||
|
||||
<img src="../assets/qgc-power.png" class="zoom">
|
||||
|
||||
Further reading: https://docs.px4.io/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)
|
||||
|
||||
@@ -51,6 +51,8 @@ python3 flight.py
|
||||
Below is a complete flight program that performs a takeoff, flies forward and lands:
|
||||
|
||||
```python
|
||||
#coding: utf8
|
||||
|
||||
import rospy
|
||||
from clover import srv
|
||||
from std_srvs.srv import Trigger
|
||||
|
||||
72
docs/en/px4_parameters.md
Normal 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):
|
||||
|
||||

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