Merge branch 'master' of https://github.com/CopterExpress/clever-show
30
.gitignore
vendored
@@ -17,17 +17,21 @@ images/
|
||||
show-env/
|
||||
builder/clever-config
|
||||
|
||||
Server/tests.py
|
||||
Server/convert_ui.sh
|
||||
Server/config/server.ini
|
||||
Server/server_logs
|
||||
Server/testj\.ipynb
|
||||
Server/tst_client\.py
|
||||
Server/tst\.py
|
||||
server/tests.py
|
||||
server/test
|
||||
server/server_venv
|
||||
server/convert_ui.sh
|
||||
server/config/server.ini
|
||||
server/server_logs
|
||||
server/testj\.ipynb
|
||||
server/tst_client\.py
|
||||
server/tst\.py
|
||||
|
||||
Drone/test_animation/
|
||||
Drone/animation.csv
|
||||
Drone/client_logs
|
||||
Drone/config/client.ini
|
||||
Drone/_copter_client_old_\.py
|
||||
Drone/test_cl\.py
|
||||
drone/test_animation/
|
||||
drone/test
|
||||
drone/drone_venv
|
||||
drone/animation.csv
|
||||
drone/client_logs
|
||||
drone/config/client.ini
|
||||
drone/_copter_client_old_\.py
|
||||
drone/test_cl\.py
|
||||
|
||||
20
.travis.yml
@@ -42,19 +42,15 @@ jobs:
|
||||
draft: true
|
||||
name: ${TRAVIS_TAG}
|
||||
|
||||
- stage: Annotate
|
||||
name: Auto-generate changelog
|
||||
- stage: Test
|
||||
name: Execute auto tests for drone modules
|
||||
language: python
|
||||
python: 3.6
|
||||
install:
|
||||
- pip install GitPython PyGithub
|
||||
python: 2.7
|
||||
script:
|
||||
- PYTHONUNBUFFERED=1 python ./builder/assets/gen_changelog.py
|
||||
- cd drone
|
||||
- pip install -r requirements.txt
|
||||
- pytest
|
||||
|
||||
stages:
|
||||
- Test
|
||||
- Build
|
||||
- Annotate
|
||||
# More info there
|
||||
# https://github.com/travis-ci/travis-ci/issues/6893
|
||||
# https://docs.travis-ci.com/user/customizing-the-build/
|
||||
# https://docs.travis-ci.com/user/deployment/releases
|
||||
# https://docs.travis-ci.com/user/environment-variables/
|
||||
|
||||
@@ -1,259 +0,0 @@
|
||||
from __future__ import print_function
|
||||
import threading
|
||||
import time
|
||||
from rpi_ws281x import *
|
||||
from tasking_lib import wait as wait_until
|
||||
import logging
|
||||
logger = logging.getLogger(__name__)
|
||||
# LED strip configuration:
|
||||
LED_COUNT = 60 # Number of LED pixels.
|
||||
LED_PIN = 21 # GPIO pin connected to the pixels (18 uses PWM!) (10 uses SPI /dev/spidev0.0).
|
||||
LED_FREQ_HZ = 800000 # LED signal frequency in hertz (usually 800khz)
|
||||
LED_DMA = 10 # DMA channel to use for generating signal (try 10)
|
||||
LED_BRIGHTNESS = 255 # Set to 0 for darkest and 255 for brightest
|
||||
LED_INVERT = False # True to invert the signal (when using NPN transistor level shift)
|
||||
LED_CHANNEL = 0 # Set to '1' for GPIOs 13, 19, 41, 45 or 53
|
||||
|
||||
# define led strip
|
||||
strip = Adafruit_NeoPixel(LED_COUNT, LED_PIN, LED_FREQ_HZ, LED_DMA, LED_INVERT, LED_BRIGHTNESS, LED_CHANNEL)
|
||||
|
||||
# variables
|
||||
mode = ""
|
||||
r = 0
|
||||
g = 0
|
||||
b = 0
|
||||
|
||||
r_prev = 0
|
||||
g_prev = 0
|
||||
b_prev = 0
|
||||
|
||||
direct = False
|
||||
l = 0
|
||||
wait_ms = 5.0
|
||||
|
||||
INTERRUPTER = threading.Event()
|
||||
INTERRUPTER_UNSET = threading.Event()
|
||||
|
||||
def delay(delay_time, interrupter=INTERRUPTER, maxsleep=0.01):
|
||||
global mode
|
||||
wait_until(time.time()+delay_time, interrupter, maxsleep)
|
||||
if interrupter.is_set():
|
||||
mode = "off"
|
||||
|
||||
|
||||
# functions
|
||||
def math_wheel(pos):
|
||||
"""Generate rainbow colors across 0-255 positions."""
|
||||
if pos < 85:
|
||||
return Color(pos * 3, 255 - pos * 3, 0)
|
||||
elif pos < 170:
|
||||
pos -= 85
|
||||
return Color(255 - pos * 3, 0, pos * 3)
|
||||
else:
|
||||
pos -= 170
|
||||
return Color(0, pos * 3, 255 - pos * 3)
|
||||
|
||||
|
||||
def rainbow(wait=10, direction=False, interrupter=INTERRUPTER):
|
||||
global wait_ms, direct, mode, INTERRUPTER
|
||||
wait_ms = wait
|
||||
direct = direction
|
||||
mode = "rainbow"
|
||||
INTERRUPTER=interrupter
|
||||
|
||||
|
||||
def fill(red, green, blue, interrupter=INTERRUPTER):
|
||||
global r, g, b, mode, INTERRUPTER
|
||||
r = red
|
||||
g = green
|
||||
b = blue
|
||||
mode = "fill"
|
||||
INTERRUPTER=interrupter
|
||||
|
||||
|
||||
def blink(red, green, blue, wait=250, interrupter=INTERRUPTER):
|
||||
global r, g, b, wait_ms, mode, INTERRUPTER
|
||||
r = red
|
||||
g = green
|
||||
b = blue
|
||||
wait_ms = wait
|
||||
mode = "blink"
|
||||
INTERRUPTER=interrupter
|
||||
|
||||
|
||||
def chase(red, green, blue, wait=50, direction=False, interrupter=INTERRUPTER):
|
||||
global r, g, b, wait_ms, direct, mode, INTERRUPTER
|
||||
r = red
|
||||
g = green
|
||||
b = blue
|
||||
wait_ms = wait
|
||||
direct = direction
|
||||
mode = "chase"
|
||||
INTERRUPTER=interrupter
|
||||
|
||||
|
||||
def wipe_to(red, green, blue, wait=50, direction=False, interrupter=INTERRUPTER):
|
||||
global r, g, b, wait_ms, direct, mode, INTERRUPTER
|
||||
r = red
|
||||
g = green
|
||||
b = blue
|
||||
wait_ms = wait
|
||||
direct = direction
|
||||
mode = "wipe_to"
|
||||
INTERRUPTER=interrupter
|
||||
|
||||
|
||||
def fade_to(red, green, blue, wait=20, interrupter=INTERRUPTER): # do not working with rainbow (solid colors only)
|
||||
global r, g, b, r_prev, g_prev, b_prev, wait_ms, mode, INTERRUPTER
|
||||
r_prev = r
|
||||
g_prev = g
|
||||
b_prev = b
|
||||
r = red
|
||||
g = green
|
||||
b = blue
|
||||
wait_ms = wait
|
||||
mode = "fade_to"
|
||||
INTERRUPTER=interrupter
|
||||
|
||||
|
||||
def run(red, green, blue, length=strip.numPixels(), direction=False, wait=25, interrupter=INTERRUPTER):
|
||||
global r, g, b, l, wait_ms, direct, mode, INTERRUPTER
|
||||
r = red
|
||||
g = green
|
||||
b = blue
|
||||
l = length
|
||||
direct = direction
|
||||
wait_ms = wait
|
||||
mode = "run"
|
||||
INTERRUPTER=interrupter
|
||||
|
||||
|
||||
def off():
|
||||
global mode
|
||||
mode = "off"
|
||||
|
||||
|
||||
def strip_set(color):
|
||||
for i in range(strip.numPixels()):
|
||||
strip.setPixelColor(i, color)
|
||||
strip.show()
|
||||
|
||||
|
||||
def strip_rainbow_frame(iteration, direction):
|
||||
for i in range(strip.numPixels()):
|
||||
n = ((strip.numPixels()-1)*direction) - i
|
||||
strip.setPixelColor(abs(n), math_wheel((int(i * 256 / strip.numPixels()) + iteration) & 255))
|
||||
strip.show()
|
||||
|
||||
|
||||
def strip_chase_step(color, direction, interrupter=INTERRUPTER):
|
||||
for q in range(3):
|
||||
for i in range(0, strip.numPixels(), 3):
|
||||
n = ((strip.numPixels() - 1) * direction) - (i + q)
|
||||
strip.setPixelColor(abs(n), color)
|
||||
strip.show()
|
||||
delay(wait_ms / 1000.0, interrupter)
|
||||
for i in range(0, strip.numPixels(), 3):
|
||||
n = ((strip.numPixels() - 1) * direction) - (i + q)
|
||||
strip.setPixelColor(abs(n), 0)
|
||||
|
||||
|
||||
def strip_wipe(color, direction, interrupter=INTERRUPTER):
|
||||
for i in range(strip.numPixels()):
|
||||
n = ((strip.numPixels() - 1) * direction) - i
|
||||
strip.setPixelColor(abs(n), color)
|
||||
delay(wait_ms / 1000.0, interrupter)
|
||||
if interrupter.is_set():
|
||||
return
|
||||
strip.show()
|
||||
|
||||
|
||||
def strip_fade(r1, g1, b1, r2, g2, b2, frames=50, interrupter=INTERRUPTER):
|
||||
r_delta = (r2-r1)//frames
|
||||
g_delta = (g2-g1)//frames
|
||||
b_delta = (b2-b1)//frames
|
||||
for i in range(frames):
|
||||
red = r1 + (r_delta * i)
|
||||
green = g1 + (g_delta * i)
|
||||
blue = b1 + (b_delta * i)
|
||||
strip_set(Color(red, green, blue))
|
||||
delay(wait_ms / 1000.0, interrupter)
|
||||
if interrupter.is_set():
|
||||
return
|
||||
strip_set(Color(r2, g2, b2))
|
||||
|
||||
|
||||
def strip_run_step(red, green, blue, length, direction, iteration):
|
||||
r_delta = red // length
|
||||
g_delta = green // length
|
||||
b_delta = blue // length
|
||||
direction = not direction
|
||||
for i in range(strip.numPixels()):
|
||||
n = ((strip.numPixels()-1)*direction)-((i+iteration) % strip.numPixels())
|
||||
r_fin = max(0, (red - (r_delta * i)))
|
||||
g_fin = max(0, (green - (g_delta * i)))
|
||||
b_fin = max(0, (blue - (b_delta * i)))
|
||||
strip.setPixelColor(abs(n), Color(r_fin, g_fin, b_fin))
|
||||
strip.show()
|
||||
|
||||
|
||||
def strip_off():
|
||||
for i in range(strip.numPixels()):
|
||||
strip.setPixelColor(i, Color(0, 0, 0))
|
||||
strip.show()
|
||||
|
||||
|
||||
def led_thread():
|
||||
global mode
|
||||
logger.info("Starting LedLib thread")
|
||||
iteration = 0
|
||||
while True:
|
||||
if mode == "rainbow":
|
||||
if iteration >= 256:
|
||||
iteration = 0
|
||||
strip_rainbow_frame(iteration, direct)
|
||||
delay(wait_ms / 1000.0, INTERRUPTER)
|
||||
iteration += 1
|
||||
elif mode == "fill":
|
||||
strip_set(Color(r, g, b))
|
||||
mode = ""
|
||||
elif mode == "blink":
|
||||
strip_set(Color(r, g, b))
|
||||
delay(wait_ms / 1000.0, INTERRUPTER)
|
||||
strip_set(Color(0, 0, 0))
|
||||
delay(wait_ms / 1000.0, INTERRUPTER)
|
||||
elif mode == "chase":
|
||||
strip_chase_step(Color(r, g, b), direct)
|
||||
elif mode == "wipe_to":
|
||||
strip_wipe(Color(r, g, b,), direct, INTERRUPTER)
|
||||
mode = "fill"
|
||||
elif mode == "fade_to":
|
||||
strip_fade(r_prev, g_prev, b_prev, r, g, b, interrupter=INTERRUPTER)
|
||||
mode = ""
|
||||
elif mode == "run":
|
||||
strip_run_step(r, g, b, l, direct, iteration)
|
||||
delay(wait_ms / 1000.0, INTERRUPTER)
|
||||
iteration += 1
|
||||
elif mode == "off":
|
||||
strip_off()
|
||||
mode = ""
|
||||
else:
|
||||
delay(1 / 1000.0, interrupter=INTERRUPTER_UNSET)
|
||||
|
||||
|
||||
# init
|
||||
def init_led(led_pin = LED_PIN):
|
||||
global strip
|
||||
strip = Adafruit_NeoPixel(LED_COUNT, led_pin, LED_FREQ_HZ, LED_DMA, LED_INVERT, LED_BRIGHTNESS, LED_CHANNEL)
|
||||
strip.begin()
|
||||
t_l = threading.Thread(target=led_thread)
|
||||
t_l.daemon = True
|
||||
t_l.start()
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
init_led()
|
||||
try:
|
||||
rainbow()
|
||||
except KeyboardInterrupt:
|
||||
off()
|
||||
@@ -1 +0,0 @@
|
||||
__all__ = ['FlightLib', 'LedLib']
|
||||
@@ -1,7 +0,0 @@
|
||||
# Client of clever-show
|
||||
|
||||
Application for remote synchronized control of drones and emergency drone protection module.
|
||||
|
||||
Documentation is located here:
|
||||
* English
|
||||
* [Russian](../docs/ru/client.md)
|
||||
12
README.md
@@ -2,9 +2,9 @@
|
||||
|
||||
[Русская версия](README_RU.md)
|
||||
|
||||
Software for making the drone show controlled by Raspberry Pi, PX4 and COEX [Clever](https://github.com/CopterExpress/clever) package.
|
||||
Software for making the drone show with drones controlled by [Raspberry Pi](https://www.raspberrypi.org/) with COEX [Clover](https://github.com/CopterExpress/clover) package and flight controller with [PX4](https://github.com/PX4/Firmware) firmware.
|
||||
|
||||
Create animation in Blender, convert it to drone paths, set up the drones and run your own show!
|
||||
Create animation in [Blender](https://www.blender.org/), convert it to drone paths, set up the drones and run your own show!
|
||||
|
||||
[](https://travis-ci.org/CopterExpress/clever-show)
|
||||
|
||||
@@ -16,9 +16,9 @@ Create animation in Blender, convert it to drone paths, set up the drones and ru
|
||||
|
||||
## This software includes
|
||||
|
||||
* [Drone side](https://github.com/CopterExpress/clever-show/tree/master/Drone) for remote synchronized control of drones with emergency drone protection module
|
||||
* [Server side](https://github.com/CopterExpress/clever-show/tree/master/Server) for making the drone show with ability of tuning drones, animation and music
|
||||
* [Blender 2.8 addon](https://github.com/CopterExpress/clever-show/tree/master/blender-addon) for exporting animation to drone paths
|
||||
* [Drone side](drone/) for remote synchronized control of drones with emergency drone protection module
|
||||
* [Server side](server/) for making the drone show with ability of tuning drones, animation and music
|
||||
* [Blender 2.8 addon](blender-addon/) for exporting animation to drone paths
|
||||
* [Raspberry Pi image](https://github.com/CopterExpress/clever-show/releases/latest) for quick launch software on the drones
|
||||
|
||||
## Documentation
|
||||
@@ -27,4 +27,4 @@ Create animation in Blender, convert it to drone paths, set up the drones and ru
|
||||
|
||||
Start tutorial is located [here](docs/ru/start-tutorial.md).
|
||||
|
||||
Detailed documentation is located in the [docs](https://github.com/CopterExpress/clever-show/tree/master/docs) folder.
|
||||
Detailed documentation is located in the [docs](docs/) folder.
|
||||
|
||||
12
README_RU.md
@@ -2,9 +2,9 @@
|
||||
|
||||
[English version](README.md)
|
||||
|
||||
Програмное обеспечение для запуска шоу дронов под управлением Raspberry Pi с пакетом COEX [Clever](https://github.com/CopterExpress/clever) и полётного контроллера с прошивкой PX4.
|
||||
Програмное обеспечение для запуска шоу дронов под управлением [Raspberry Pi](https://www.raspberrypi.org/) с пакетом COEX [Clover](https://github.com/CopterExpress/clover) и полётным контроллером с прошивкой [PX4](https://github.com/PX4/Firmware).
|
||||
|
||||
Создайте анимацию в Blender, сконвертируйте её в полётные пути дронов, настройте дроны и запустите своё собственное шоу дронов!
|
||||
Создайте анимацию в [Blender](https://www.blender.org/), сконвертируйте её в полётные пути дронов, настройте дроны и запустите своё собственное шоу дронов!
|
||||
|
||||
[](https://travis-ci.org/CopterExpress/clever-show)
|
||||
|
||||
@@ -16,13 +16,13 @@
|
||||
|
||||
## Пакет включает в себя
|
||||
|
||||
* [Набор ПО для дрона](https://github.com/CopterExpress/clever-show/tree/master/Drone) с клиентским приложением для удаленного синхронизированного управления дронами и модулем экстренной посадки.
|
||||
* [Серверное приложение](https://github.com/CopterExpress/clever-show/tree/master/Server) для создания шоу и настройки дронов, анимации и музыки
|
||||
* [Аддон для Blender 2.8](https://github.com/CopterExpress/clever-show/tree/master/blender-addon) для преобразования анимации полёта коптеров, созданной в Blender, в файлы полётов для каждого коптера
|
||||
* [Набор ПО для дрона](drone/) с клиентским приложением для удаленного синхронизированного управления дронами и модулем экстренной посадки.
|
||||
* [Серверное приложение](server/) для создания шоу и настройки дронов, анимации и музыки
|
||||
* [Аддон для Blender 2.8](blender-addon/) для преобразования анимации полёта коптеров, созданной в Blender, в индивидуальные пути для каждого коптера
|
||||
* [Образ для Raspberry Pi](https://github.com/CopterExpress/clever-show/releases/latest) для быстрого запуска ПО на коптере
|
||||
|
||||
## Документация
|
||||
|
||||
Инструкция по запуску ПО находится [здесь](docs/ru/start-tutorial.md).
|
||||
|
||||
Подробная документация расположена в папке [docs](https://github.com/CopterExpress/clever-show/tree/master/docs).
|
||||
Подробная документация расположена в папке [docs](docs/).
|
||||
|
||||
@@ -1,7 +0,0 @@
|
||||
# Server of clever-show
|
||||
|
||||
Application for creating and running drone shows, adjusting drones, animations and music.
|
||||
|
||||
Documentation is located here:
|
||||
* English
|
||||
* [Russian](../docs/ru/server.md)
|
||||
@@ -1,12 +1,12 @@
|
||||
[Unit]
|
||||
Description=Clever Show Client Service
|
||||
Description=clever-show client service
|
||||
Requires=roscore.service
|
||||
After=clever.service
|
||||
After=clover.service
|
||||
|
||||
[Service]
|
||||
WorkingDirectory=/home/pi/clever-show/Drone
|
||||
WorkingDirectory=/home/pi/clever-show/drone
|
||||
ExecStart=/bin/bash -c ". /home/pi/catkin_ws/devel/setup.sh; \
|
||||
ROS_HOSTNAME=`hostname`.local /usr/bin/python /home/pi/clever-show/Drone/copter_client.py"
|
||||
ROS_HOSTNAME=`hostname`.local /usr/bin/python /home/pi/clever-show/drone/client.py"
|
||||
KillSignal=SIGKILL
|
||||
Restart=on-failure
|
||||
RestartSec=3
|
||||
|
||||
@@ -2,7 +2,6 @@
|
||||
|
||||
# $1 - ssid, $2 - password of wifi router
|
||||
# $3 - hostname of rpi
|
||||
# $4 - server ip
|
||||
|
||||
if [ $(whoami) != "root" ]; then
|
||||
echo -e "\nThis should be run as root!\n"
|
||||
@@ -10,10 +9,10 @@ if [ $(whoami) != "root" ]; then
|
||||
fi
|
||||
|
||||
# check if enough arguments
|
||||
if [[ $# -ne 4 ]] ; then
|
||||
echo -e "\nPlease, enter arguments: router ssid, wifi password, copter id and server ip"
|
||||
echo -e "\nExample: sudo $0 clever-swarm swarmwifi clever-1 192.168.1.100\n"
|
||||
exit 0
|
||||
if [[ $# -ne 3 ]] ; then
|
||||
echo -e "\nPlease, enter 3 positional arguments: router ssid, wifi password and copter id"
|
||||
echo -e "\nExample: sudo client-setup droneshow dronewifi clover-1\n"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
# stop and disable dnsmasq service (to set wifi in client mode)
|
||||
@@ -61,20 +60,9 @@ $3
|
||||
|
||||
EOF
|
||||
|
||||
# configure chrony as client
|
||||
cat << EOF | tee /etc/chrony/chrony.conf
|
||||
server $4 iburst
|
||||
driftfile /var/lib/chrony/drift
|
||||
makestep 1.0 -1
|
||||
rtcsync
|
||||
EOF
|
||||
|
||||
# change server ip in client_config
|
||||
sed -i "0,/^host/s/\(^h.*\)/host = $4/" client_config.ini
|
||||
|
||||
# enable clever show service and visual_pose_watchdog service
|
||||
# enable clever show service and failsafe service
|
||||
systemctl enable clever-show.service
|
||||
systemctl enable visual_pose_watchdog.service
|
||||
systemctl enable failsafe.service
|
||||
|
||||
# restart clever
|
||||
reboot
|
||||
@@ -1,13 +1,13 @@
|
||||
[Unit]
|
||||
Description=Visual Pose Watchdog
|
||||
Description=clever-show failsafe service
|
||||
Requires=roscore.service
|
||||
After=network.target
|
||||
|
||||
[Service]
|
||||
User=pi
|
||||
WorkingDirectory=/home/pi/clever-show/Drone
|
||||
WorkingDirectory=/home/pi/clever-show/drone
|
||||
ExecStart=/bin/bash -c ". /home/pi/catkin_ws/devel/setup.sh; \
|
||||
ROS_HOSTNAME=`hostname`.local /usr/bin/python /home/pi/clever-show/Drone/visual_pose_watchdog.py"
|
||||
ROS_HOSTNAME=`hostname`.local /usr/bin/python /home/pi/clever-show/drone/failsafe.py"
|
||||
Restart=on-failure
|
||||
RestartSec=3
|
||||
|
||||
@@ -1,75 +0,0 @@
|
||||
#!/usr/bin/env python3
|
||||
|
||||
# Generate and upload changelog
|
||||
|
||||
from git import Repo, exc
|
||||
from github import Github
|
||||
import os
|
||||
import sys
|
||||
|
||||
upload_changelog = True
|
||||
|
||||
try:
|
||||
current_tag = os.environ['TRAVIS_TAG']
|
||||
if current_tag == '':
|
||||
current_tag = 'HEAD'
|
||||
upload_changelog = False
|
||||
print('TRAVIS_TAG is set to {}'.format(current_tag))
|
||||
except KeyError:
|
||||
print('TRAVIS_TAG not set - not uploading changelog')
|
||||
current_tag = 'HEAD'
|
||||
upload_changelog = False
|
||||
|
||||
try:
|
||||
api_key = os.environ['GITHUB_OAUTH_TOKEN']
|
||||
except KeyError:
|
||||
print('GITHUB_OAUTH_TOKEN not set - not uploading changelog')
|
||||
api_key = None
|
||||
upload_changelog = False
|
||||
|
||||
try:
|
||||
repo_slug = os.environ['TRAVIS_REPO_SLUG']
|
||||
except KeyError:
|
||||
print('TRAVIS_REPO_SLUG not set - cannot determine remote repository')
|
||||
repo_slug = ''
|
||||
exit(1)
|
||||
|
||||
if len(sys.argv) > 1:
|
||||
repo_path = sys.argv[1]
|
||||
else:
|
||||
repo_path = '.'
|
||||
|
||||
print('Opening repository at {}'.format(repo_path))
|
||||
repo = Repo(repo_path)
|
||||
git = repo.git()
|
||||
try:
|
||||
print('Unshallowing repository')
|
||||
git.fetch('--unshallow', '--tags')
|
||||
except exc.GitCommandError:
|
||||
print('Repository already unshallowed')
|
||||
print('Attempting to get previous tag')
|
||||
base_tag = git.describe('--tags', '--abbrev=0', '{}^'.format(current_tag))
|
||||
print('Base tag set to {}'.format(base_tag))
|
||||
|
||||
changelog = git.log('{}...{}'.format(base_tag, current_tag), '--pretty=format:* %H %s *(%an)*')
|
||||
print('Current changelog: \n{}'.format(changelog))
|
||||
|
||||
# Only interact with Github if uploading is enabled
|
||||
if upload_changelog:
|
||||
gh = Github(api_key)
|
||||
gh_repo = gh.get_repo(repo_slug)
|
||||
# Get all releases and find ours by its tag name
|
||||
gh_release = None
|
||||
for release in gh_repo.get_releases():
|
||||
if release.tag_name == current_tag:
|
||||
gh_release = release
|
||||
if gh_release is None:
|
||||
# We could not find the correct release, so here's our last resort. It will most likely fail.
|
||||
gh_release = gh_repo.get_release(current_tag)
|
||||
gh_body = gh_release.body
|
||||
if gh_body is None:
|
||||
gh_body = ''
|
||||
gh_body = '{}\nChanges between `{}` and `{}`:\n\n{}'.format(gh_body, base_tag, current_tag, changelog)
|
||||
print('New release body: {}'.format(gh_body))
|
||||
gh_release.update_release(gh_release.tag_name, gh_body, draft=True, prerelease=True,
|
||||
tag_name=gh_release.tag_name, target_commitish=gh_release.target_commitish)
|
||||
@@ -1,73 +0,0 @@
|
||||
<launch>
|
||||
<arg name="fcu_conn" default="usb"/>
|
||||
<arg name="fcu_ip" default="127.0.0.1"/>
|
||||
<arg name="gcs_bridge" default="tcp"/>
|
||||
<arg name="web_video_server" default="true"/>
|
||||
<arg name="rosbridge" default="true"/>
|
||||
<arg name="main_camera" default="true"/>
|
||||
<arg name="optical_flow" default="true"/>
|
||||
<arg name="aruco" default="false"/>
|
||||
<arg name="rangefinder_vl53l1x" default="true"/>
|
||||
<arg name="led" default="false"/>
|
||||
<arg name="rc" default="true"/>
|
||||
|
||||
<!-- log formatting -->
|
||||
<env name="ROSCONSOLE_FORMAT" value="[${severity}] [${time}]: ${logger}: ${message}"/>
|
||||
|
||||
<!-- mavros -->
|
||||
<include file="$(find clever)/launch/mavros.launch">
|
||||
<arg name="fcu_conn" value="$(arg fcu_conn)"/>
|
||||
<arg name="fcu_ip" value="$(arg fcu_ip)"/>
|
||||
<arg name="gcs_bridge" value="$(arg gcs_bridge)"/>
|
||||
</include>
|
||||
|
||||
<!-- web video server -->
|
||||
<node name="web_video_server" pkg="web_video_server" type="web_video_server" if="$(arg web_video_server)" required="false" respawn="true" respawn_delay="5">
|
||||
<param name="default_stream_type" value="ros_compressed"/>
|
||||
<param name="publish_rate" value="1.0"/>
|
||||
</node>
|
||||
|
||||
<!-- aruco markers -->
|
||||
<include file="$(find clever)/launch/aruco.launch" if="$(arg aruco)"/>
|
||||
|
||||
<!-- optical flow -->
|
||||
<node pkg="nodelet" type="nodelet" name="optical_flow" args="load clever/optical_flow nodelet_manager" if="$(arg optical_flow)" clear_params="true" output="screen">
|
||||
<remap from="image_raw" to="main_camera/image_raw"/>
|
||||
<remap from="camera_info" to="main_camera/camera_info"/>
|
||||
<param name="calc_flow_gyro" value="true"/>
|
||||
</node>
|
||||
|
||||
<!-- main nodelet manager -->
|
||||
<node pkg="nodelet" type="nodelet" name="nodelet_manager" args="manager" output="screen" clear_params="true">
|
||||
<param name="num_worker_threads" value="2"/>
|
||||
</node>
|
||||
|
||||
<node pkg="tf2_ros" type="static_transform_publisher" name="map_flipped_frame" args="0 0 0 3.1415926 3.1415926 0 map map_flipped"/>
|
||||
|
||||
<!-- simplified offboard control -->
|
||||
<node name="simple_offboard" pkg="clever" 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"/>
|
||||
</node>
|
||||
|
||||
<!-- main camera -->
|
||||
<include file="$(find clever)/launch/main_camera.launch" if="$(arg main_camera)"/>
|
||||
|
||||
<!-- rosbridge -->
|
||||
<include file="$(find rosbridge_server)/launch/rosbridge_websocket.launch" if="$(eval rosbridge or rc)"/>
|
||||
|
||||
<!-- tf2 republisher for web visualization -->
|
||||
<node name="tf2_web_republisher" pkg="tf2_web_republisher" type="tf2_web_republisher" output="screen" if="$(arg rosbridge)"/>
|
||||
|
||||
<!-- vl53l1x ToF rangefinder -->
|
||||
<node name="rangefinder" pkg="vl53l1x" type="vl53l1x_node" output="screen" if="$(arg rangefinder_vl53l1x)">
|
||||
<param name="frame_id" value="rangefinder"/>
|
||||
</node>
|
||||
|
||||
<!-- led strip -->
|
||||
<include file="$(find clever)/launch/led.launch" if="$(arg led)"/>
|
||||
|
||||
<!-- rc backend -->
|
||||
<node name="rc" pkg="clever" type="rc" output="screen" if="$(arg rc)"/>
|
||||
</launch>
|
||||
@@ -1,38 +0,0 @@
|
||||
<launch>
|
||||
<!-- Camera position and orientation are represented by base_link -> main_camera_optical transform -->
|
||||
<!-- static_transform_publisher arguments: x y z yaw pitch roll frame_id child_frame_id -->
|
||||
|
||||
<!-- article about camera setup: https://clever.coex.tech/camera_frame -->
|
||||
|
||||
<!-- camera is oriented downward, camera cable goes backward [option 1] -->
|
||||
<node pkg="tf2_ros" type="static_transform_publisher" name="main_camera_frame" args="0.05 0 -0.07 -1.5707963 0 3.1415926 base_link main_camera_optical"/>
|
||||
|
||||
<!-- camera is oriented downward, camera cable goes forward [option 2] -->
|
||||
<!--<node pkg="tf2_ros" type="static_transform_publisher" name="main_camera_frame" args="0.05 0 -0.07 1.5707963 0 3.1415926 base_link main_camera_optical"/>-->
|
||||
|
||||
<!-- camera is oriented upward, camera cable goes backward [option 3] -->
|
||||
<!--<node pkg="tf2_ros" type="static_transform_publisher" name="main_camera_frame" args="0.05 0 0.07 1.5707963 0 0 base_link main_camera_optical"/>-->
|
||||
|
||||
<!-- camera is oriented upward, camera cable goes forward [option 4] -->
|
||||
<!--<node pkg="tf2_ros" type="static_transform_publisher" name="main_camera_frame" args="0.05 0 0.07 -1.5707963 0 0 base_link main_camera_optical"/>-->
|
||||
|
||||
<!-- camera node -->
|
||||
<node pkg="nodelet" type="nodelet" name="main_camera" args="load cv_camera/CvCameraNodelet nodelet_manager" clear_params="true">
|
||||
<param name="frame_id" value="main_camera_optical"/>
|
||||
<param name="camera_info_url" value="file://$(find clever)/camera_info/calibration.yaml"/>
|
||||
|
||||
<param name="rate" value="100"/> <!-- poll rate -->
|
||||
<param name="cv_cap_prop_fps" value="40"/> <!-- camera FPS -->
|
||||
<param name="capture_delay" value="0.02"/> <!-- approximate delay on frame retrieving -->
|
||||
<param name="rescale_camera_info" value="true"/> <!-- automatically rescale camera calibration info -->
|
||||
|
||||
<!-- camera resolution, NOTE: camera_info file should match it -->
|
||||
<param name="image_width" value="320"/>
|
||||
<param name="image_height" value="240"/>
|
||||
</node>
|
||||
|
||||
<!-- camera visualization markers -->
|
||||
<node pkg="clever" type="camera_markers" ns="main_camera" name="main_camera_markers">
|
||||
<param name="scale" value="3.0"/>
|
||||
</node>
|
||||
</launch>
|
||||
@@ -1,100 +0,0 @@
|
||||
0 0.33 0.0 9.0 0 0 0 0
|
||||
1 0.33 1.0 9.0 0 0 0 0
|
||||
2 0.33 2.0 9.0 0 0 0 0
|
||||
3 0.33 3.0 9.0 0 0 0 0
|
||||
4 0.33 4.0 9.0 0 0 0 0
|
||||
5 0.33 5.0 9.0 0 0 0 0
|
||||
6 0.33 6.0 9.0 0 0 0 0
|
||||
7 0.33 7.0 9.0 0 0 0 0
|
||||
8 0.33 8.0 9.0 0 0 0 0
|
||||
9 0.33 9.0 9.0 0 0 0 0
|
||||
10 0.33 0.0 8.0 0 0 0 0
|
||||
11 0.33 1.0 8.0 0 0 0 0
|
||||
12 0.33 2.0 8.0 0 0 0 0
|
||||
13 0.33 3.0 8.0 0 0 0 0
|
||||
14 0.33 4.0 8.0 0 0 0 0
|
||||
15 0.33 5.0 8.0 0 0 0 0
|
||||
16 0.33 6.0 8.0 0 0 0 0
|
||||
#17 0.33 7.0 8.0 0 0 0 0
|
||||
18 0.33 8.0 8.0 0 0 0 0
|
||||
19 0.33 9.0 8.0 0 0 0 0
|
||||
20 0.33 0.0 7.0 0 0 0 0
|
||||
21 0.33 1.0 7.0 0 0 0 0
|
||||
22 0.33 2.0 7.0 0 0 0 0
|
||||
23 0.33 3.0 7.0 0 0 0 0
|
||||
24 0.33 4.0 7.0 0 0 0 0
|
||||
25 0.33 5.0 7.0 0 0 0 0
|
||||
26 0.33 6.0 7.0 0 0 0 0
|
||||
27 0.33 7.0 7.0 0 0 0 0
|
||||
28 0.33 8.0 7.0 0 0 0 0
|
||||
29 0.33 9.0 7.0 0 0 0 0
|
||||
30 0.33 0.0 6.0 0 0 0 0
|
||||
31 0.33 1.0 6.0 0 0 0 0
|
||||
32 0.33 2.0 6.0 0 0 0 0
|
||||
33 0.33 3.0 6.0 0 0 0 0
|
||||
34 0.33 4.0 6.0 0 0 0 0
|
||||
35 0.33 5.0 6.0 0 0 0 0
|
||||
36 0.33 6.0 6.0 0 0 0 0
|
||||
37 0.33 7.0 6.0 0 0 0 0
|
||||
38 0.33 8.0 6.0 0 0 0 0
|
||||
39 0.33 9.0 6.0 0 0 0 0
|
||||
40 0.33 0.0 5.0 0 0 0 0
|
||||
41 0.33 1.0 5.0 0 0 0 0
|
||||
42 0.33 2.0 5.0 0 0 0 0
|
||||
43 0.33 3.0 5.0 0 0 0 0
|
||||
44 0.33 4.0 5.0 0 0 0 0
|
||||
45 0.33 5.0 5.0 0 0 0 0
|
||||
46 0.33 6.0 5.0 0 0 0 0
|
||||
47 0.33 7.0 5.0 0 0 0 0
|
||||
48 0.33 8.0 5.0 0 0 0 0
|
||||
49 0.33 9.0 5.0 0 0 0 0
|
||||
50 0.33 0.0 4.0 0 0 0 0
|
||||
51 0.33 1.0 4.0 0 0 0 0
|
||||
52 0.33 2.0 4.0 0 0 0 0
|
||||
53 0.33 3.0 4.0 0 0 0 0
|
||||
54 0.33 4.0 4.0 0 0 0 0
|
||||
55 0.33 5.0 4.0 0 0 0 0
|
||||
56 0.33 6.0 4.0 0 0 0 0
|
||||
57 0.33 7.0 4.0 0 0 0 0
|
||||
58 0.33 8.0 4.0 0 0 0 0
|
||||
59 0.33 9.0 4.0 0 0 0 0
|
||||
60 0.33 0.0 3.0 0 0 0 0
|
||||
61 0.33 1.0 3.0 0 0 0 0
|
||||
62 0.33 2.0 3.0 0 0 0 0
|
||||
63 0.33 3.0 3.0 0 0 0 0
|
||||
64 0.33 4.0 3.0 0 0 0 0
|
||||
65 0.33 5.0 3.0 0 0 0 0
|
||||
66 0.33 6.0 3.0 0 0 0 0
|
||||
67 0.33 7.0 3.0 0 0 0 0
|
||||
68 0.33 8.0 3.0 0 0 0 0
|
||||
69 0.33 9.0 3.0 0 0 0 0
|
||||
70 0.33 0.0 2.0 0 0 0 0
|
||||
71 0.33 1.0 2.0 0 0 0 0
|
||||
72 0.33 2.0 2.0 0 0 0 0
|
||||
73 0.33 3.0 2.0 0 0 0 0
|
||||
74 0.33 4.0 2.0 0 0 0 0
|
||||
75 0.33 5.0 2.0 0 0 0 0
|
||||
76 0.33 6.0 2.0 0 0 0 0
|
||||
77 0.33 7.0 2.0 0 0 0 0
|
||||
78 0.33 8.0 2.0 0 0 0 0
|
||||
79 0.33 9.0 2.0 0 0 0 0
|
||||
80 0.33 0.0 1.0 0 0 0 0
|
||||
81 0.33 1.0 1.0 0 0 0 0
|
||||
82 0.33 2.0 1.0 0 0 0 0
|
||||
83 0.33 3.0 1.0 0 0 0 0
|
||||
84 0.33 4.0 1.0 0 0 0 0
|
||||
85 0.33 5.0 1.0 0 0 0 0
|
||||
86 0.33 6.0 1.0 0 0 0 0
|
||||
87 0.33 7.0 1.0 0 0 0 0
|
||||
88 0.33 8.0 1.0 0 0 0 0
|
||||
89 0.33 9.0 1.0 0 0 0 0
|
||||
90 0.33 0.0 0.0 0 0 0 0
|
||||
91 0.33 1.0 0.0 0 0 0 0
|
||||
92 0.33 2.0 0.0 0 0 0 0
|
||||
93 0.33 3.0 0.0 0 0 0 0
|
||||
94 0.33 4.0 0.0 0 0 0 0
|
||||
95 0.33 5.0 0.0 0 0 0 0
|
||||
96 0.33 6.0 0.0 0 0 0 0
|
||||
97 0.33 7.0 0.0 0 0 0 0
|
||||
98 0.33 8.0 0.0 0 0 0 0
|
||||
99 0.33 9.0 0.0 0 0 0 0
|
||||
@@ -1,17 +1,17 @@
|
||||
image_width: 320
|
||||
image_height: 240
|
||||
image_width: 640
|
||||
image_height: 480
|
||||
distortion_model: plumb_bob
|
||||
camera_name: raspicam
|
||||
camera_name: main_camera_optical
|
||||
camera_matrix:
|
||||
rows: 3
|
||||
cols: 3
|
||||
data:
|
||||
- 166.23942373073172
|
||||
- 332.47884746146343
|
||||
- 0.
|
||||
- 162.19011246829268
|
||||
- 320.0
|
||||
- 0.
|
||||
- 166.5880923974026
|
||||
- 109.82227735714285
|
||||
- 333.1761847948052
|
||||
- 240.0
|
||||
- 0.
|
||||
- 0.
|
||||
- 1.
|
||||
@@ -31,13 +31,13 @@ projection_matrix:
|
||||
rows: 3
|
||||
cols: 4
|
||||
data:
|
||||
- 166.23942373073172
|
||||
- 332.47884746146343
|
||||
- 0.
|
||||
- 162.19011246829268
|
||||
- 324.38022493658536
|
||||
- 0.
|
||||
- 0.
|
||||
- 166.5880923974026
|
||||
- 109.82227735714285
|
||||
- 333.1761847948052
|
||||
- 219.6445547142857
|
||||
- 0.
|
||||
- 0.
|
||||
- 0.
|
||||
@@ -1,9 +1,9 @@
|
||||
<launch>
|
||||
<arg name="aruco_detect" default="true"/>
|
||||
<arg name="aruco_map" default="true"/>
|
||||
<arg name="aruco_vpe" default="true"/>
|
||||
<arg name="aruco_map" default="false"/>
|
||||
<arg name="aruco_vpe" default="false"/>
|
||||
|
||||
<!-- For additional help go to https://clever.coex.tech/aruco -->
|
||||
<!-- For additional help go to https://clover.coex.tech/aruco -->
|
||||
|
||||
<!-- aruco_detect: detect aruco markers, estimate poses -->
|
||||
<node name="aruco_detect" pkg="nodelet" if="$(arg aruco_detect)" type="nodelet" args="load aruco_pose/aruco_detect nodelet_manager" output="screen" clear_params="true">
|
||||
@@ -14,6 +14,9 @@
|
||||
<param name="send_tf" value="true"/>
|
||||
<param name="known_tilt" value="map"/>
|
||||
<param name="length" value="0.33"/>
|
||||
<!-- aruco detector parameters -->
|
||||
<param name="cornerRefinementMethod" value="2"/> <!-- contour refinement -->
|
||||
<param name="minMarkerPerimeterRate" value="0.075"/> <!-- 0.075 for 320x240, 0.0375 for 640x480 -->
|
||||
</node>
|
||||
|
||||
<!-- aruco_map: estimate aruco map pose -->
|
||||
@@ -31,7 +34,7 @@
|
||||
</node>
|
||||
|
||||
<!-- vpe publisher from aruco markers -->
|
||||
<node name="vpe_publisher" pkg="clever" type="vpe_publisher" if="$(arg aruco_vpe)" output="screen" clear_params="true">
|
||||
<node name="vpe_publisher" pkg="clover" type="vpe_publisher" if="$(arg aruco_vpe)" output="screen" clear_params="true">
|
||||
<remap from="~pose_cov" to="aruco_map/pose"/>
|
||||
<remap from="~vpe" to="mavros/vision_pose/pose"/>
|
||||
<param name="frame_id" value="aruco_map_detected"/>
|
||||
38
builder/clover-config/launch/led.launch
Normal file
@@ -0,0 +1,38 @@
|
||||
<launch>
|
||||
<arg name="ws281x" default="true"/>
|
||||
<arg name="led_effect" default="true"/>
|
||||
<arg name="led_notify" default="false"/>
|
||||
|
||||
<!-- For additional help go to https://clover.coex.tech/led -->
|
||||
|
||||
<!-- ws281x led strip driver -->
|
||||
<node pkg="ws281x" name="led" type="ws281x_node" clear_params="true" output="screen" if="$(arg ws281x)">
|
||||
<param name="led_count" value="58"/>
|
||||
<param name="gpio_pin" value="21"/>
|
||||
<param name="brightness" value="64"/>
|
||||
<param name="strip_type" value="WS2811_STRIP_GRB"/>
|
||||
<param name="target_frequency" value="800000"/>
|
||||
<param name="dma" value="10"/>
|
||||
<param name="invert" value="false"/>
|
||||
</node>
|
||||
|
||||
<!-- high level led effects control, events notification with leds -->
|
||||
<node pkg="clover" name="led_effect" type="led" ns="led" clear_params="true" output="screen" if="$(arg led_effect)">
|
||||
<param name="blink_rate" value="2"/>
|
||||
<param name="fade_period" value="0.5"/>
|
||||
<param name="rainbow_period" value="5"/>
|
||||
<!-- events effects table -->
|
||||
<rosparam param="notify" if="$(arg led_notify)">
|
||||
startup: { r: 255, g: 255, b: 255 }
|
||||
connected: { effect: rainbow }
|
||||
disconnected: { effect: blink, r: 255, g: 50, b: 50 }
|
||||
acro: { r: 245, g: 155, b: 0 }
|
||||
stabilized: { r: 30, g: 180, b: 50 }
|
||||
altctl: { r: 255, g: 255, b: 40 }
|
||||
posctl: { r: 50, g: 100, b: 220 }
|
||||
offboard: { r: 220, g: 20, b: 250 }
|
||||
low_battery: { threshold: 3.7, effect: blink_fast, r: 255, g: 0, b: 0 }
|
||||
error: { effect: flash, r: 255, g: 0, b: 0 }
|
||||
</rosparam>
|
||||
</node>
|
||||
</launch>
|
||||
37
builder/clover-config/launch/main_camera.launch
Normal file
@@ -0,0 +1,37 @@
|
||||
<launch>
|
||||
<!-- article about camera setup: https://clover.coex.tech/camera_setup -->
|
||||
|
||||
<arg name="direction_z" default="down"/> <!-- direction the camera points: down, up -->
|
||||
<arg name="direction_y" default="backward"/> <!-- direction the camera cable points: backward, forward -->
|
||||
|
||||
<node if="$(eval direction_z == 'down' and direction_y == 'backward')" pkg="tf2_ros" type="static_transform_publisher" name="main_camera_frame" args="0.05 0 -0.07 -1.5707963 0 3.1415926 base_link main_camera_optical"/>
|
||||
<node if="$(eval direction_z == 'down' and direction_y == 'forward')" pkg="tf2_ros" type="static_transform_publisher" name="main_camera_frame" args="0.05 0 -0.07 1.5707963 0 3.1415926 base_link main_camera_optical"/>
|
||||
<node if="$(eval direction_z == 'up' and direction_y == 'backward')" pkg="tf2_ros" type="static_transform_publisher" name="main_camera_frame" args="0.05 0 0.07 1.5707963 0 0 base_link main_camera_optical"/>
|
||||
<node if="$(eval direction_z == 'up' and direction_y == 'forward')" pkg="tf2_ros" type="static_transform_publisher" name="main_camera_frame" args="0.05 0 0.07 -1.5707963 0 0 base_link main_camera_optical"/>
|
||||
|
||||
<!-- Template for custom camera orientation -->
|
||||
<!-- Camera position and orientation are represented by base_link -> main_camera_optical transform -->
|
||||
<!-- static_transform_publisher arguments: x y z yaw pitch roll frame_id child_frame_id -->
|
||||
<!-- <node pkg="tf2_ros" type="static_transform_publisher" name="main_camera_frame" args="0.05 0 -0.07 -1.5707963 0 3.1415926 base_link main_camera_optical"/> -->
|
||||
|
||||
<!-- camera node -->
|
||||
<node pkg="nodelet" type="nodelet" name="main_camera" args="load cv_camera/CvCameraNodelet nodelet_manager" clear_params="true">
|
||||
<param name="device_path" value="/dev/video0"/> <!-- v4l2 device -->
|
||||
<param name="frame_id" value="main_camera_optical"/>
|
||||
<param name="camera_info_url" value="file://$(find clover)/camera_info/calibration.yaml"/>
|
||||
|
||||
<param name="rate" value="100"/> <!-- poll rate -->
|
||||
<param name="cv_cap_prop_fps" value="40"/> <!-- camera FPS -->
|
||||
<param name="capture_delay" value="0.02"/> <!-- approximate delay on frame retrieving -->
|
||||
<param name="rescale_camera_info" value="true"/> <!-- automatically rescale camera calibration info -->
|
||||
|
||||
<!-- camera resolution -->
|
||||
<param name="image_width" value="320"/>
|
||||
<param name="image_height" value="240"/>
|
||||
</node>
|
||||
|
||||
<!-- camera visualization markers -->
|
||||
<node pkg="clover" type="camera_markers" ns="main_camera" name="main_camera_markers">
|
||||
<param name="scale" value="3.0"/>
|
||||
</node>
|
||||
</launch>
|
||||
5
builder/clover-config/map/animation_map.txt
Normal file
@@ -0,0 +1,5 @@
|
||||
# id length x y z rot_z rot_y rot_x
|
||||
1 0.33 0 0 0 0 0 0
|
||||
2 0.33 1 0 0 0 0 0
|
||||
3 0.33 0 1 0 0 0 0
|
||||
4 0.33 1 1 0 0 0 0
|
||||
@@ -2,7 +2,7 @@
|
||||
|
||||
set -e # Exit immidiately on non-zero result
|
||||
|
||||
SOURCE_IMAGE="https://github.com/CopterExpress/clever/releases/download/v0.18/clever_v0.18.img.zip"
|
||||
SOURCE_IMAGE="https://github.com/CopterExpress/clover/releases/download/v0.20/clover_v0.20.img.zip"
|
||||
|
||||
export DEBIAN_FRONTEND=${DEBIAN_FRONTEND:='noninteractive'}
|
||||
export LANG=${LANG:='C.UTF-8'}
|
||||
@@ -30,7 +30,7 @@ echo_stamp() {
|
||||
|
||||
REPO_DIR="/mnt"
|
||||
SCRIPTS_DIR="${REPO_DIR}/builder"
|
||||
CONFIG_DIR="${SCRIPTS_DIR}/clever-config"
|
||||
CONFIG_DIR="${SCRIPTS_DIR}/clover-config"
|
||||
IMAGES_DIR="${REPO_DIR}/images"
|
||||
|
||||
[[ ! -d ${SCRIPTS_DIR} ]] && (echo_stamp "Directory ${SCRIPTS_DIR} doesn't exist" "ERROR"; exit 1)
|
||||
@@ -57,7 +57,7 @@ get_image() {
|
||||
echo_stamp "RPI_IMAGE_NAME=${RPI_IMAGE_NAME}" "INFO"
|
||||
|
||||
if [ ! -e "${BUILD_DIR}/${RPI_ZIP_NAME}" ]; then
|
||||
echo_stamp "Downloading original clever distribution"
|
||||
echo_stamp "Downloading original clover distribution"
|
||||
wget --progress=dot:giga -O ${BUILD_DIR}/${RPI_ZIP_NAME} $2
|
||||
echo_stamp "Downloading complete" "SUCCESS"
|
||||
else echo_stamp "Clever distribution already downloaded" "INFO"; fi
|
||||
@@ -71,7 +71,7 @@ get_image() {
|
||||
get_image ${IMAGE_PATH} ${SOURCE_IMAGE}
|
||||
|
||||
# Make free space
|
||||
img-resize ${IMAGE_PATH} max '5G'
|
||||
img-resize ${IMAGE_PATH} max '6G'
|
||||
|
||||
# Reconfiguring clever show repository for simplier unshallowing
|
||||
# git config remote.origin.fetch "+refs/heads/*:refs/remotes/origin/*"
|
||||
@@ -113,17 +113,23 @@ losetup -d ${DEV_IMAGE}
|
||||
# Install software
|
||||
img-chroot ${IMAGE_PATH} exec ${SCRIPTS_DIR}'/image-software.sh'
|
||||
|
||||
# Copy service files for clever show client and visual_pose_watchdog
|
||||
img-chroot ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/clever-show.service' '/lib/systemd/system/'
|
||||
img-chroot ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/failsafe.service' '/lib/systemd/system/'
|
||||
|
||||
# Copy client-setup script to /usr/local/bin to provide wide access
|
||||
img-chroot ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/client-setup' '/usr/local/bin/'
|
||||
|
||||
# Copy chrony configuration
|
||||
img-chroot ${IMAGE_PATH} copy ${REPO_DIR}'/examples/chrony/client.conf' '/etc/chrony/chrony.conf'
|
||||
|
||||
# Configure image
|
||||
img-chroot ${IMAGE_PATH} exec ${SCRIPTS_DIR}'/image-configure.sh'
|
||||
|
||||
# Copy service files for clever show client and visual_pose_watchdog
|
||||
img-chroot ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/clever-show.service' '/lib/systemd/system/'
|
||||
img-chroot ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/visual_pose_watchdog.service' '/lib/systemd/system/'
|
||||
|
||||
# Copy config files for clever
|
||||
if [[ -d "${CONFIG_DIR}/launch" ]]; then img-chroot ${IMAGE_PATH} copy ${CONFIG_DIR}'/launch' '/home/pi/catkin_ws/src/clever/clever'; fi
|
||||
if [[ -d "${CONFIG_DIR}/map" ]]; then img-chroot ${IMAGE_PATH} copy ${CONFIG_DIR}'/map' '/home/pi/catkin_ws/src/clever/aruco_pose'; fi
|
||||
if [[ -d "${CONFIG_DIR}/camera_info" ]]; then img-chroot ${IMAGE_PATH} copy ${CONFIG_DIR}'/camera_info' '/home/pi/catkin_ws/src/clever/clever'; fi
|
||||
# Copy config files for clover
|
||||
if [[ -d "${CONFIG_DIR}/launch" ]]; then img-chroot ${IMAGE_PATH} copy ${CONFIG_DIR}'/launch' '/home/pi/catkin_ws/src/clover/clover'; fi
|
||||
if [[ -d "${CONFIG_DIR}/map" ]]; then img-chroot ${IMAGE_PATH} copy ${CONFIG_DIR}'/map' '/home/pi/catkin_ws/src/clover/aruco_pose'; fi
|
||||
if [[ -d "${CONFIG_DIR}/camera_info" ]]; then img-chroot ${IMAGE_PATH} copy ${CONFIG_DIR}'/camera_info' '/home/pi/catkin_ws/src/clover/clover'; fi
|
||||
|
||||
# Shrink image
|
||||
img-resize ${IMAGE_PATH}
|
||||
|
||||
@@ -23,7 +23,7 @@ echo_stamp() {
|
||||
}
|
||||
|
||||
# rename wifi ssid
|
||||
sed -i "s/NEW_SSID='CLEVER/NEW_SSID='CLEVERSHOW/" /root/init_rpi.sh
|
||||
sed -i "s/NEW_SSID='clover/NEW_SSID='clever-show/" /root/init_rpi.sh
|
||||
|
||||
# add sudoers variables to make sudo works with ros (for led strip)
|
||||
grep -qxF 'Defaults env_keep += "ROS_LOG_DIR"' /etc/sudoers || cat << EOT >> /etc/sudoers
|
||||
@@ -40,3 +40,5 @@ EOT
|
||||
|
||||
echo_stamp "Image was configured!" "SUCCESS"
|
||||
|
||||
echo "Move /etc/ld.so.preload back to its original position"
|
||||
mv /etc/ld.so.preload.disabled-for-build /etc/ld.so.preload
|
||||
|
||||
@@ -49,19 +49,21 @@ my_travis_retry() {
|
||||
return $result
|
||||
}
|
||||
|
||||
echo_stamp "Move /etc/ld.so.preload out of the way"
|
||||
mv /etc/ld.so.preload /etc/ld.so.preload.disabled-for-build
|
||||
|
||||
echo_stamp "Update apt cache"
|
||||
apt-get update -qq
|
||||
|
||||
echo_stamp "Software installing"
|
||||
apt-get install -y \
|
||||
samba \
|
||||
chrony \
|
||||
&& echo_stamp "Everything was installed!" "SUCCESS" \
|
||||
|| (echo_stamp "Some packages wasn't installed!" "ERROR"; exit 1)
|
||||
|
||||
echo_stamp "Install python libs"
|
||||
my_travis_retry pip install selectors2
|
||||
my_travis_retry pip install psutil
|
||||
cd /home/pi/clever-show/drone
|
||||
my_travis_retry pip install -r requirements.txt
|
||||
|
||||
echo_stamp "Install catkin packages"
|
||||
cd /home/pi/catkin_ws/src
|
||||
|
||||
|
Before Width: | Height: | Size: 8.6 KiB After Width: | Height: | Size: 37 KiB |
@@ -4,15 +4,15 @@
|
||||
|
||||
## Установка и настройка
|
||||
|
||||
* Скачайте и установите согласно инструкциям последнюю версию Blender 2.81 с [оффициального сайта](https://www.blender.org/download/).
|
||||
* Откройте Blender, в верхнем меню выберите `Edit > Preferences`. В открывшемся окне настроек в боковой панели выберите пункт `Add-ons`. Нажмите на кнопку `Install...` в верхнем правом углу окна. В диалоговом окне откройте путь к папке с аддоном [clever-show/blender-addon](../../blender-addon/) и выберите файл `addon.py`. Нажмите `Install Add-on from file...`. Аддон установлен.
|
||||
* После установки аддона поставьте "галочку" напротив аддона `Import-Export: Export > CSV Drone Swarm Animation Exporter` для активации аддона.
|
||||
* Скачайте и установите согласно инструкциям последнюю версию Blender 2.8 с [оффициального сайта](https://www.blender.org/download/).
|
||||
* Откройте Blender, в верхнем меню выберите `Edit > Preferences`. В открывшемся окне настроек в боковой панели выберите пункт `Add-ons`. Нажмите на кнопку `Install...` в правом верхнем углу окна. В диалоговом окне откройте путь к папке с аддоном [clever-show/blender-addon](../../blender-addon/) и выберите файл `addon.py`. Нажмите `Install Add-on from file...`. Аддон установлен.
|
||||
* После установки аддона поставьте "галочку" напротив аддона `Import-Export: clever-show animation (.csv)` для активации аддона.
|
||||
|
||||
Аддон активирован и готов к работе. Выполнение этих операций не понадобится при дальнейших запусках Blender.
|
||||
|
||||
## Экпорт при помощи аддона
|
||||
|
||||
Для вызова диалогового окна экспорта нажмите в верхнем меню `File > Export > CSV Drone Swarm Animation Exporter`. В открывшемся окне экспорта необходимо выбрать целевой путь экспорта и название папки, которую создаст аддон в процессе экспорта. В боковом меню доступна панель параметров экспорта:
|
||||
Для вызова диалогового окна экспорта нажмите в верхнем меню `File > Export > clever-show animation (.csv)`. В открывшемся окне экспорта необходимо выбрать целевой путь экспорта и название папки, которую создаст аддон в процессе экспорта. В боковом меню доступна панель параметров экспорта:
|
||||
|
||||
* `Use name filter for objects` - чекбокс, определяет, будет ли использован фильтр объектов при сохранении их путей. При отключении этого параметра будут экспортированы пути всех видимых объектов.
|
||||
* `Name identifier` - фильтр имён объектов. Если активен чекбокс `Use name filter for objects`, будут сохранены только пути объектов, содержащих данное значение в названии.
|
||||
@@ -20,7 +20,7 @@
|
||||
* `Speed limit` - при нарушении указанного ограничения по скорости передвижения дронов будут выведены предупреждения.
|
||||
* `Distance limit` - при нарушении указанной минимальной дистанции между дронами будут выведены предупреждения.
|
||||
|
||||
После настройки нужных параметров нажмите кнопку `Export Drone Swarm animation`. В указанную папку экспортируются анимации указанных объектов из проекта Blender в формате `.csv`.
|
||||
После настройки нужных параметров нажмите кнопку `Export clever-show animation`. В указанную папку экспортируются анимации указанных объектов из проекта Blender в формате `.csv`.
|
||||
|
||||
## Деактивация и удаление
|
||||
|
||||
|
||||
@@ -2,29 +2,48 @@
|
||||
|
||||
Приложение для удаленного синхронизированного управления дронами в шоу и модуль экстренной защиты дронов.
|
||||
|
||||
* `client.py` - основной модуль связи и управления дроном
|
||||
* `failsafe.py` - модуль защиты дронов, который создает сервис `/emergency_land` и контролирует состояние дрона в соответствии с логикой, указанной в пунктах `[FAILSAFE]` и `[EMERGENCY LAND]` файла настроек `client.ini`
|
||||
|
||||
## Инструкции
|
||||
|
||||
* [Установка и запуск](start-tutorial.md#установка-и-запуск-клиента)
|
||||
* [Настройка клиента](#настройка-клиента)
|
||||
|
||||
## Схема работы клиента
|
||||
## Схема работы клиента в образе для Raspberry Pi
|
||||
|
||||
Клиент является сервисом `clever-show` в операционной системе коптера. Сервис запускает скрипт [copter_client.py](../../Drone/copter_client.py) и автоматически запускается при загрузке операционной системы. В случае необходимости применения параметров обновлённой конфигурации клиента сервис может быть перезапущен. Сервис `clever-show` предназначен для управления и настройки коптера для группового полёта с помощью приложения сервера.
|
||||
Клиент является сервисом `clever-show` в операционной системе коптера. Сервис запускает скрипт [client.py](../../drone/client.py) и автоматически запускается при загрузке операционной системы. В случае необходимости применения параметров обновлённой конфигурации клиента сервис может быть перезапущен. Сервис `clever-show` предназначен для управления и настройки коптера для группового полёта с помощью приложения сервера.
|
||||
|
||||
Вместе с клиентом в операционной системе зарегистрирован сервис экстренной защиты дрона `visual_pose_watchdog`. Данный сервис запускает скрипт [visual_pose_watchdog.py](../../Drone/visual_pose_watchdog.py) и автоматически запускается при загрузке операционной системы. В случае необходимости применения параметров обновлённой конфигурации клиента сервис может быть перезапущен. Сервис `visual_pose_watchdog` предназначен для автоматической посадки коптера в экстренных ситуациях: при отсутствии сообщений о позиции дрона из топика `/mavros/vision_pose/pose` и при столкновении с объектами в полёте, когда расстояние между текущей точкой, где находится коптер, и точкой, где ему следует находиться по полётному заданию, превышает пороговое значение. Также `visual_pose_watchdog` предоставляет ROS сервис `/emergency_land`, к которому может обратиться клиент по команде с сервера для экстренной посадки.
|
||||
Вместе с клиентом в операционной системе зарегистрирован сервис экстренной защиты дрона `failsafe`. Данный сервис запускает скрипт [failsafe.py](../../drone/failsafe.py) и автоматически запускается при загрузке операционной системы. В случае необходимости применения параметров обновлённой конфигурации клиента сервис может быть перезапущен.
|
||||
|
||||
Логи обоих сервисов записываются в файл `/var/log/syslog` операционной системы бортового компьютера Raspberry Pi на дроне. Логи текущего сеанса доступны для просмотра при выполнении команд `journalctl -u clever-show` для клиента и `journalctl -u visual_pose_watchdog` для сервиса экстренной защиты дрона в терминале, подключенном к Raspberry Pi. Логи могут быть полезны при анализе возникших нештатных или аварийных ситуаций при полёте коптера под управлением приложения клиента.
|
||||
Сервис `failsafe` предназначен для автоматической посадки коптера в экстренных ситуациях:
|
||||
|
||||
* при отсутствии сообщений о позиции дрона из топика `/mavros/vision_pose/pose`
|
||||
* при столкновении с объектами в полёте, когда расстояние между текущей точкой, где находится коптер, и точкой, где ему следует находиться по полётному заданию, превышает пороговое значение.
|
||||
|
||||
Также `failsafe` предоставляет ROS сервис `/emergency_land`, к которому может обратиться клиент по команде с сервера для экстренной посадки дрона.
|
||||
|
||||
Логи обоих сервисов записываются в файл `/var/log/syslog` операционной системы бортового компьютера Raspberry Pi на дроне. Логи текущего сеанса доступны для просмотра при выполнении команд `journalctl -u clever-show` для клиента и `journalctl -u failsafe` для сервиса экстренной защиты дрона в терминале, подключенном к Raspberry Pi. Логи могут быть полезны при анализе возникших нештатных или аварийных ситуаций при полёте коптера под управлением приложения клиента.
|
||||
|
||||
## Настройка клиента
|
||||
|
||||
### Файл конфигурации
|
||||
|
||||
Конфигурация клиента создаётся согласно [спецификации](../../Drone/config/spec/configspec_client.ini), в ней можно посмотреть значения по умолчанию для любого параметра после ключевого слова `default`. Все изменения сохраняются в файл конфигурации `client.ini` в папке `clever-show/Drone/config`. Доступно редактирование конфигурации клиента через GUI модуль `Config editor` в приложении сервера. Для редактирования конфигурации с сервера нужно выбрать строку с клиентом, для которого требуется изменение конфигурации, кликнуть левой кнопкой мыши по любой ячейке из строки и выбрать `Edit config` из контекстного меню.
|
||||
Конфигурация клиента создаётся согласно [спецификации](../../drone/config/spec/configspec_client.ini), в ней можно посмотреть значения по умолчанию для любого параметра после ключевого слова `default`. Все изменения сохраняются в файл конфигурации `client.ini` в папке `clever-show/drone/config`. Доступно редактирование конфигурации клиента через GUI модуль `Config editor` в приложении сервера. Для редактирования конфигурации с сервера нужно выбрать строку с клиентом, для которого требуется изменение конфигурации, кликнуть левой кнопкой мыши по любой ячейке из строки и выбрать `Edit config` из контекстного меню.
|
||||
|
||||
Конфигурация по умолчанию является полностью работоспособной и не требует изменений для быстрого старта клиента.
|
||||
|
||||
Для централизованной загрузки конфигурации на все коптеры нужно использовать пункт меню `Send configurations` на [сервере](server.md#раздел-server). Допускается загрузка неполного файла параметров конфигурации, с отсутствующими разделами или параметрами относительно конфигурации по умолчанию. Также доступна опция загрузки конфигурации конкретного клиента на выделенные коптеры: для этого нужно с сервера выбрать строку с клиентом, с которого требуется скопировать конфигурацию на выделенные клиенты, кликнуть левой кнопкой мыши по любой ячейке из строки и выбрать `Copy config to selected` из контекстного меню.
|
||||
Для централизованной загрузки конфигурации на все коптеры нужно использовать пункт меню `Send configurations` на [сервере](server.md#раздел-server). Допускается загрузка неполного файла параметров конфигурации, с отсутствующими разделами или параметрами относительно конфигурации по умолчанию. Также доступна опция загрузки конфигурации конкретного клиента на выделенные коптеры: для этого нужно в приложении сервера выбрать строку с клиентом, с которого требуется скопировать конфигурацию на выделенные клиенты, кликнуть левой кнопкой мыши по любой ячейке из строки и выбрать `Copy config to selected` из контекстного меню.
|
||||
|
||||
### Описание параметров
|
||||
|
||||
#### Основной раздел
|
||||
|
||||
* `config_name` - название конфигурации
|
||||
* `config_version` - версия конфигурации
|
||||
* `id` - имя коптера, отображаемое в таблице. Если значение `/hostname` - имя определяется из файла `/etc/hostname`.
|
||||
* `clover_dir` - путь к директории с ROS пакетом [сlover](https://github.com/CopterExpress/clover). Необходим для загрузки файлов с картами aruco меток и launch файлов настройки запуска сервиса `clover`. Если значение `auto` - клиент пытается сам определить нужную директорию пакета `clover` (или `clever`) через `rospkg` при первом запуске. Если директорию с пакетом не удаётся определить, значение устанавливается в `error`, а файлы, специфичные для настройки ROS пакета `сlover` не передаются с сервера на клиент.
|
||||
|
||||
#### Раздел SERVER
|
||||
|
||||
В этом разделе задаются параметры сетевого взаимодействия клиента с сервером. Доступны следующие параметры:
|
||||
@@ -46,11 +65,85 @@
|
||||
|
||||
* `transmit` - логическое значение, определяет, нужно ли передавать данные на сервер.
|
||||
* `frequency` - частота передачи данных на сервер, целочисленное значение, количество раз в секунду.
|
||||
* `log_resources` - логическое значение, определяет, будет ли записываться в лог сервиса клиента clever-show состояние бортового компьютера Raspberry Pi: загрузка процессора и оперативной памяти, температура процессора, состояние температуры, состояние системы питания.
|
||||
* `log_resources` - логическое значение, определяет, будет ли записываться в лог сервиса клиента clever-show состояние бортового компьютера: загрузка процессора и оперативной памяти, температура процессора, состояние температуры, состояние системы питания (только для Raspberry Pi).
|
||||
|
||||
#### Раздел POSITION WATCHDOG
|
||||
#### Раздел FLIGHT
|
||||
|
||||
В данном разделе настраивается программа экстренной защиты коптера от потери позиции или столкновения с объектом.
|
||||
В данном разделе находятся настройки, влияющие на процесс полёта коптера.
|
||||
|
||||
* `frame_id` - название системы координат, относительно которой будут публиковаться координаты точек для воспроизведения анимации. Если значение `floor` - клиент публикует статическую систему координат с названием `floor` и настройками из раздела [FLOOR_FRAME](#раздел-floor_frame). **Внимание!** Убедитесь, что коптер удерживает позицию в данной системе координат. Для этого вы можете воспользоваться командой [Takeoff](server.md#тестовые-команды) из серверного приложения. Коптер взлетит на высоту `takeoff_height` относительно текущей.
|
||||
* `takeoff_height` - высота взлёта коптера, в метрах. Используется в начале воспроизведения анимации или при тестировании коптера с сервера.
|
||||
* `takeoff_time` - максимальное время взлёта коптера, в секундах.
|
||||
* `reach_first_point_time` - максимальное время полёта к первой точке анимации, в секундах.
|
||||
* `land_time` - время зависания в конечной точке анимации перед посадкой, в секундах.
|
||||
* `land_timeout` - время таймаута посадки, после которого происходит выключение моторов коптера, в секундах.
|
||||
|
||||
#### Раздел FLOOR FRAME
|
||||
|
||||
Данный раздел описывает смещение системы координат с названием `floor` и используется только при указании параметра `frame_id` как `floor` в разделе [COPTERS](#раздел-copters).
|
||||
|
||||
* `enabled` - логическое значение, определяет, нужно ли публиковать фрейм `floor`
|
||||
* `parent` - название опорной системы координат, относительно которой будет располагаться система координат `floor`.
|
||||
* `translation` - смещение системы координат `floor` по осям (x, y, z) относительно системы координат `parent`, в метрах.
|
||||
* `rotation` - поворот системы координат `floor` на углы (roll, pitch, yaw) вокруг осей (x, y, z) относительно системы координат `parent`, в градусах.
|
||||
|
||||
**Внимание!** Повороты `roll`, `pitch`, `yaw` производятся последовательно в указанном порядке.
|
||||
|
||||
#### Раздел GPS FRAME
|
||||
|
||||
Данный раздел описывает создание системы координат с названием `gps`. Начальное положение этой системы координат лежит в точке с координатами `lat` (latitude, широта), `lon` (longitude, долгота). Угол поворота задаётся значением `yaw` (в градусах) поворотом оси z начального положения коптера в системе координат `map`.
|
||||
|
||||
* `lat` - широта в градусах в системе WGS 84
|
||||
* `lon` - долгота в градусах в системе WGS 84
|
||||
* `yaw` - угол поворота системы координат в градусах
|
||||
|
||||
#### Раздел ANIMATION
|
||||
|
||||
В данном разделе настраивается обработка анимации. За обработку анимации отвечает отдельный модуль [animation](../../drone/modules/animation.py). При загрузке анимации на коптер модуль производит разделение последовательности кадров анимации на 5 ключевых этапов:
|
||||
|
||||
1. Коптер неподвижен в начале анимации - `static_begin`
|
||||
2. Коптер взлетает - `takeoff`
|
||||
3. Коптер следует по маршруту анимации - `route`
|
||||
4. Коптер выполняет посадку - `land`
|
||||
5. Коптер неподвижен до завершения файла анимации - `static_end`
|
||||
|
||||
Кадр анимации - это набор данных, необходимых для позиционирования коптера и определения цвета его подсветки. В текущей версии ПО кадр анимации представлен последовательностью чисел `x y z yaw r g b` в строке `.csv` файла с анимацией, где:
|
||||
|
||||
* `x`, `y`, `z` - координаты коптера в текущем кадре в метрах
|
||||
* `yaw` - рыскание коптера в радианах
|
||||
* `r`, `g`, `b` - компоненты цвета подсветки коптера, целые числа от 0 до 255
|
||||
|
||||
После разделения анимации на ключевые этапы модуль формирует выходную последовательность кадров, определяющих положение коптера и цвет его подсветки, а также последовательность действий при полёте к первой точке анимации. Настройка модуля производится с помощью следующих параметров:
|
||||
|
||||
* `start_action` - первое действие при запуске воспроизведения анимации. Доступные варианты:
|
||||
* `auto` - автоматический выбор действия между `takeoff` (взлёт) или `fly` (мгновенный полёт по точкам) на основе текущего уровня высоты коптера. Если (`z` в начальной точке анимации) - (текущая высота коптера) > (уровень взлета `takeoff_level`), то значение устанавливается в `takeoff`, иначе значение устанавливается в `fly`.
|
||||
* `takeoff` - выполнение *логики полёта к первой точке*.
|
||||
* `fly` - выполнение *логики немедленного полёта*
|
||||
|
||||
Если в файле анимации коптер взлетает с земли, при старте анимации будет применена *логика немедленного воспроизведения*: коптер включает двигатели через время, которое требуется для выполнения начальных кадров анимации, которые не включены в выходную последовательность, затем через время `arming_time` начинает следовать точкам, указанным в анимации. Если в файле анимации коптер начинает полёт в воздухе, при старте анимации будет применена *логика полёта к первой точке*: через время, которое требуется для выполнения начальных кадров анимации, которые не включены в выходную последовательность, коптер в начале взлетает на высоту `takeoff_height` за время `takeoff_time`, затем перемещается к первой точке за время `reach_first_point_time`, и затем начинает следовать точкам, указанным в анимации.
|
||||
|
||||
* `takeoff_level` - уровень взлёта для автоматического определения первого действия коптера при старте анимации
|
||||
* `ground_level` - уровень земли, используется для проверки, не попытается ли коптер улететь под землю при воспроизведении анимации. Доступные варианты настройки:
|
||||
* `current` - за уровень земли принимается текущий уровень высоты коптера перед стартом.
|
||||
* координата z в метрах
|
||||
* `frame_delay` - время воспроизведения одного кадра в секундах.
|
||||
* `yaw` - поворот коптера при полёте по точкам, в градусах. Если значение `nan` - коптер сохраняет изначальную ориентацию в полёте. Если значение `animation` - коптер берёт поворот по yaw из файла с анимацией.
|
||||
* `ratio` - масштаб анимации (ratio_x, ratio_y, ratio_z) по осям (x, y, z)
|
||||
* `common_offset` - смещение анимации относительно текущей системы, общее для всех коптеров, в метрах. Список из 3 величин (x, y, z): каждая величина задаёт смещение по соответствующей оси.
|
||||
* `private_offset` - смещение анимации относительно текущей системы, только для данного коптера, в метрах. Список из 3 величин (x, y, z): каждая величина задаёт смещение по соответствующей оси.
|
||||
* `[[OUTPUT]]` - флаги, определяющие, какие этапы будут включены в выходную последовательность кадров.
|
||||
|
||||
#### Раздел LED
|
||||
|
||||
Настройки использования светодиодной ленты на коптере. Для настройки самой ленты необходимо настроить файл `led.launch`, подробная информация в [статье по работе с лентой в Клевере](https://clover.coex.tech/ru/leds.html).
|
||||
|
||||
* `use` - логическое значение, определяет, используется или нет светодиодная лента.
|
||||
* `takeoff_indication` - логическое значение, определяет, использовать ли подсветку для обозначения взлёта
|
||||
* `land_indication` - логическое значение, определяет, использовать ли подсветку для обозначения посадки
|
||||
|
||||
#### Раздел FAILSAFE
|
||||
|
||||
В данном разделе настраивается программа экстренной защиты коптера от потери позиции или столкновения с объектом. Модуль `failsafe` при запуске предоставляет сервис `/emergency_land`, его настройки находятся в следующем разделе [EMERGENCY LAND](#раздел-emergency-land).
|
||||
|
||||
* `enabled` - логическое значение, определяет, использовать или нет экстренную защиту при потере визуальной позиции или столкновении с объектом.
|
||||
* `log_state` - логическое значение, определяет, будет ли записываться в лог сервиса состояние коптера: `armed: {} | mode: {} | vis_dt: {:.2f} | pos_delta: {:.2f} | pos_dt: {:.2f} | range: {:.2f} | watchdog_action: {}`.
|
||||
@@ -67,55 +160,6 @@
|
||||
* `thrust` - начальная мощность, подаваемая на моторы в случае выбора действия `emergency_land` при срабатывании экстренной защиты. Безразмерная величина, от 0 (отсутствие мошности) до 1 (полная мощность). Для гарантированной посадки рекомендуется устанавливать в значение, меньшее по величине на 5-10 процентов, чем газ висения (параметр `MPC_THR_HOVER` в px4). **Внимание!** Неправильная настройка этого параметра может привести к взлёту коптера вверх вместо посадки!
|
||||
* `decrease_thrust_after` - время, через которое мощность на моторах плавно начинает уменьшаться в случае выбора действия `emergency_land` при срабатывании экстренной защиты, в секундах.
|
||||
|
||||
#### Раздел COPTER
|
||||
|
||||
В данном разделе находятся настройки, влияющие на процесс полёта коптера.
|
||||
|
||||
* `frame_id` - название системы координат, относительно которой будут публиковаться координаты точек для воспроизведения анимации. Если значение `floor` - клиент публикует статическую систему координат с названием `floor` и настройками из раздела [FLOOR_FRAME](#раздел-floor_frame). **Внимание!** Убедитесь, что коптер удерживает позицию в данной системе координат. Для этого вы можете воспользоваться командой [Takeoff](server.md#тестовые-команды) из серверного приложения. Коптер взлетит на высоту `takeoff_height` относительно текущей.
|
||||
* `takeoff_height` - высота взлёта коптера, в метрах. Используется в начале воспроизведения анимации или при тестировании коптера с сервера.
|
||||
* `takeoff_time` - максимальное время взлёта коптера, в секундах.
|
||||
* `safe_takeoff` - логическое значение, определяет, нужно ли производить посадку в безопасном режиме.
|
||||
* `reach_first_point_time` - максимальное время полёта к первой точке анимации, в секундах.
|
||||
* `land_time` - время зависания в конечной точке анимации перед посадкой, в секундах.
|
||||
* `land_timeout` - время таймаута посадки, после которого происходит выключение моторов коптера, в секундах.
|
||||
* `common_offset` - смещение координат относительно текущей системы, общее для всех коптеров, в метрах. Список из 3 величин (x, y, z): каждая величина задаёт смещение по соответствующей оси.
|
||||
|
||||
#### Раздел FLOOR_FRAME
|
||||
|
||||
Данный раздел описывает смещение системы координат с названием `floor` и используется только при указании параметра `frame_id` как `floor` в разделе [COPTERS](#раздел-copters).
|
||||
|
||||
* `enabled` - логическое значение, определяет, нужно ли публиковать фрейм `floor`
|
||||
* `parent` - название опорной системы координат, относительно которой будет располагаться система координат `floor`.
|
||||
* `translation` - смещение системы координат `floor` по осям (x, y, z) относительно системы координат `parent`, в метрах.
|
||||
* `rotation` - поворот системы координат `floor` на углы (roll, pitch, yaw) вокруг осей (x, y, z) относительно системы координат `parent`, в градусах.
|
||||
|
||||
**Внимание!** Повороты `roll`, `pitch`, `yaw` производятся последовательно в указанном порядке.
|
||||
|
||||
#### Раздел ANIMATION
|
||||
|
||||
В данном разделе настраивается обработка анимации.
|
||||
|
||||
* `takeoff_detection` - логическое значение, определяет, будет ли производиться автоматическая обработка старта анимации. **Если значение True**, при загрузке анимации проверяется взлёт коптеров. Если в файле анимации коптер взлетает с земли, при старте анимации будет применена *логика немедленного воспроизведения*: коптер сразу начинает следовать точкам, указанным в анимации. Если в файле анимации коптер начинает полёт в воздухе, при старте анимации будет применена *логика полёта к первой точке*: коптер в начале взлетает на высоту `takeoff_height` за время `takeoff_time`, затем перемещается к первой точке за время `reach_first_point_time`, и затем начинает следовать точкам, указанным в анимации. **Если значение False**, при загрузке анимации не проверяется взлёт коптеров, а при старте анимации действует *логика полёта к первой точке*.
|
||||
* `land_detection` - логическое значение, определяет, будет ли производиться автоматическая обработка завершения анимации. **Если значение True**, при загрузке анимации проверяется посадка коптеров. Если в файле анимации коптер садится на землю и стоит до завершения анимации, проверка удалит все точки в анимации после начала посадки коптера. Таким образом, коптер в конце анимации зависнет над точкой посадки на время `land_time`, сядет автоматически и выключит моторы. **Если значение False**, при загрузке анимации не проверяется посадка коптеров и точкой посадки считается последняя точка в анимации. Например, если анимация посадки нарисована полностью и коптер стоит после посадки на земле некоторое время, а значение данного параметра **False**, всё это время у коптера будут включены моторы и он будет пытаться удержать указанную позицию посадки вплоть до завершении файла анимации, затем через время `land_time` перейдёт в редим посадки.
|
||||
* `frame_delay` - время воспроизведения одного кадра в секундах.
|
||||
* `ratio` - масштаб анимации (ratio_x, ratio_y, ratio_z) по осям (x, y, z)
|
||||
* `yaw` - поворот коптера при полёте по точкам, в градусах. Если значение `nan` - коптер сохраняет изначальную ориентацию в полёте. Если значение `animation` - коптер берёт поворот по yaw из файла с анимацией.
|
||||
|
||||
#### Раздел LED
|
||||
|
||||
Настройки адресуемой светодиодной ленты на коптере
|
||||
|
||||
* `use` - логическое значение, определяет, используется или нет светодиодная лента.
|
||||
* `pin` - номер пина GPIO на Raspberry, к которому подключается лента
|
||||
* `count` - количество задействованных светодиодов в ленте
|
||||
|
||||
#### Раздел PRIVATE
|
||||
|
||||
В данном разделе находятся параметры, специфичные для конкретного коптера.
|
||||
|
||||
* `id` - имя коптера, отображаемое в таблице. Если значение `/hostname` - имя определяется из файла `/etc/hostname`.
|
||||
* `offset` - смещение в метрах по осям (x, y, z) относительно текущей системы координат, только для данного коптера.
|
||||
|
||||
#### Раздел SYSTEM
|
||||
|
||||
Системные настройки служебных команд клиента
|
||||
|
||||
@@ -46,7 +46,7 @@
|
||||
* `checks` - состояние самодиагностики коптера. Ячейка в данном столбце проходит проверку, если её значение `OK`. В остальных случаях, если ячейка не пустая, она не проходит проверку.
|
||||
* При двойном клике на ячейку при наличии ошибок будет показано диалоговое окно с полной детализацией всех ошибок.
|
||||
* `current x y z yaw frame_id` - текущее положение коптера с указанием названия системы координат. Ячейка автоматически проходит проверку если у параметра [check_current_position](#раздел-checks) установлено значение `false`. Иначе, ячейка в данном столбце не проходит проверку, если её значение `NO_POS` или содержит `nan`. В остальных случаях, если ячейка не пустая, она проходит проверку.
|
||||
* `start x y z` - стартовое положение коптера для воспроизведения анимации. Ячейка в данном столбце не проходит проверку, если её значение `NO_POS` или разница между текущим и стартовым положением коптера больше значения [start_pos_delta_max](#раздел-checks). В остальных случаях, если ячейка не пустая, она проходит проверку.
|
||||
* `start x y z action delay` - стартовое положение коптера для воспроизведения анимации, первое действие при воспроизведении анимации и время через которое выполнится первое действие после старта анимации. Ячейка в данном столбце не проходит проверку, если её значение `NO_POS`, разница между текущим и стартовым положением коптера больше значения [start_pos_delta_max](#раздел-checks) или модуль анимации клиента выдаёт ошибку при обработке анимации и проверке того, что все точки анимации находятся над уровнем земли. В остальных случаях, если ячейка не пустая, она проходит проверку.
|
||||
* `dt` - разница между временем на сервере и клиенте в секундах, включая сетевую задержку. Ячейка в данном столбце проходит проверку, если её значение меньше значения [time_delta_max](#раздел-checks), задаваемого в настройках сервера. В остальных случаях, если ячейка не пустая, она не проходит проверку. При слишком больших значениях сигнализирует об отсутствии синхронизации времени между коптером и клиентом.
|
||||
|
||||
### Меню
|
||||
@@ -59,27 +59,37 @@
|
||||
|
||||
* Подраздел `Send`
|
||||
|
||||
* `Animations` - отправка файлов анимации, экспортированных аддоном к Blender, на выбранные коптеры. В диалоговом окне необходимо выбрать *папку*, содержащую файлы анимации. Каждый файл анимации будет отправлен на клиент с именем, соответствующим имени файла без расширения.
|
||||
`<clever-show>` - расположение ПО `clever-show` на клиенте.
|
||||
|
||||
`<clover_dir>` - расположение ROS пакета `clover` на клиенте.
|
||||
|
||||
* `Animations` - отправка файлов анимации, экспортированных аддоном к Blender, на выбранные коптеры. В диалоговом окне необходимо выбрать *папку*, содержащую файлы анимации. Каждый файл анимации будет отправлен на клиент с именем, соответствующим имени файла без расширения. На клиенте файл будет сохранён как `<clever-show>/drone/animation.csv`.
|
||||
|
||||
* `Camera calibrations` - отправка yaml-файлов калибровки камеры для сервиса `clover`. В диалоговом окне необходимо выбрать *папку*, содержащую файлы конфигурации с расширением `.yaml`. Каждый файл калибровки будет отправлен на клиент с именем (copter ID), соответствующим имени файла без расширения. На клиенте файл будет сохранён как `<clover_dir>/camera_info/calibration.yaml`. **Внимание!** Существующий файл калибровки на коптере будет перезаписан.
|
||||
|
||||
---
|
||||
|
||||
* `Aruco map` - отправка *единого* файла карты aruco маркеров на все выбранные клиенты. В диалоговом окне необходимо выбрать *один* файл карты в установленном формате. Файл на клиенте будет перезаписан и сохранён как `<clover_dir>/../aruco_pose/map/animation_map.txt`. После получения и записи файла клиент автоматически перезапустит сервис `clover`. Для возобновления работоспособности полётных функций и получения некоторых значений телеметрии *необходимо подождать* некоторое время до полного запуска сервиса.
|
||||
|
||||
* `Animation` - отправка *единого* файла анимации на все выбранные клиенты. В диалоговом окне необходимо выбрать *один* файл анимации. На клиенте файл будет сохранён как `<clever-show>/drone/animation.csv`. Полезная функция для быстрого тестирования нескольких дронов, если использовать в комбинации с `Set start X Y to current position`.
|
||||
|
||||
* `Configuration` - отправка *единого* файла конфигурации клиента на все выбранные клиенты. В диалоговом окне необходимо выбрать *один* файл конфигурации в установленном формате. Файл конфигурации может быть неполным, в таком случае будут перезаписаны лишь указанные в файле параметры. **Внимание!** Не рекомендуется использовать данное действие для массовой перезаписи `copter ID`, кроме значения `/hostname`. **Внимание!** НЕ отправляйте на клиенты файл конфигурации сервера.
|
||||
|
||||
* `Launch files` - отправка launch-файлов конфигурации сервиса `clever`. В диалоговом окне необходимо выбрать *папку*, содержащую файлы конфигурации с сширением `.launch`. Все файлы с таким расширением будут отправлены *на каждый* из клиентов. **Внимание!** Существующие файлы конфигурации на коптерах будут перезаписаны, однако файлы, не отправленные сервером, не будут удалены или модифицированы.
|
||||
* `Launch files folder` - отправка launch-файлов конфигурации сервиса `clover`. В диалоговом окне необходимо выбрать *папку*, содержащую файлы конфигурации с расширением `.launch` и `.yaml`. Все файлы с таким расширением будут отправлены *на каждый* из клиентов в директорию `<clover_dir>/launch`. **Внимание!** Существующие файлы конфигурации на коптерах будут перезаписаны, однако файлы, не отправленные сервером, не будут удалены или модифицированы.
|
||||
|
||||
* `Aruco map` - отправка *единого* файла карты aruco маркеров на все выбранные клиенты. В диалоговом окне необходимо выбрать *один* файл карты в установленном формате. Файл на клиенте будет перезаписан. После получения и записи файла клиент автоматически перезапустит сервис `clever`. Для возобновления работоспособности полётных функций и получения некоторых значений телеметрии *необходимо подождать* некоторое время до полного запуска сервиса.
|
||||
* `FCU parameters file` - отправка и запись *единого* файла конфигураций полётного контроллера (FCU) на все выбранные клиенты. В диалоговом окне необходимо выбрать *один* файл параметров в установленном формате. Параметры на полётном контроллере будут перезаписаны.
|
||||
|
||||
* `Camera calibrations` - отправка yaml-файлов калибровки камеры для сервиса `clever`. В диалоговом окне необходимо выбрать *папку*, содержащую файлы конфигурации с расширением `.yaml`. Каждый файл калибровки будет отправлен на клиент с именем (copter ID), соответствующим имени файла без расширения. **Внимание!** Существующий файл калибровки на коптере будет перезаписан.
|
||||
|
||||
* `FCU parameters` - отправка и запись *единого* файла конфигураций полётного контроллера (FCU) на все выбранные клиенты. В диалоговом окне необходимо выбрать *один* файл параметров в установленном формате. Параметры на полётном контроллере будут перезаписаны.
|
||||
---
|
||||
|
||||
* `File` - отправка *одного* любого файла на все выбранные клиенты. В диалоговом окне необходимо выбрать *один* файл. Далее, необходимо указать путь, по которому данный файл будет записан на клиенты (не включая имя файла).
|
||||
|
||||
* `Command` - отправка и выполнение любой команды терминала на все выбранные клиенты. В диалоговом окне необходимо ввести требуемую команду. Команды *могут* использовать `sudo`-права.
|
||||
|
||||
------
|
||||
---
|
||||
|
||||
* `Retrive file` - позволяет скачать любой файл с клиентов в выбранную директорию в файловой системе сервера. Если при скачивании был выбран более чем один клиент, то к имени файла от каждого клиента будет добавлен его ID. В диалоговом окне сначала введите путь к требуемому файлу на клиенте. Далее, в диалоговом окне необходимо указать путь, по которому данный файл будет записан на сервер.
|
||||
|
||||
------
|
||||
---
|
||||
|
||||
* Подраздел `Restart Service`
|
||||
|
||||
@@ -89,7 +99,7 @@
|
||||
* `clever` - перезапускает сервис `clever` на выбранных клиентах. Для возобновления работоспособности полётных функций и получения некоторых значений телеметрии *необходимо подождать* некоторое время до полного запуска сервиса.
|
||||
* `clever-show` - перезапускает сервис шоу коптеров `clever-show` на выбранных клиентах. Во время перезапуска клиенты будут отключены.
|
||||
|
||||
------
|
||||
---
|
||||
|
||||
* `Set start X Y to current position` - устанавливает точку старта анимации у выбранных клиентов в значения текущей позиции по X Y.
|
||||
|
||||
@@ -97,9 +107,15 @@
|
||||
|
||||
* `Set Z offfset to ground` - устанавливает собственный отступ по Z каждого из выбранных клиентов в значение, равное текущему положению по координате Z. Можно применять для выравнимания общей высоты полёта коптеров.
|
||||
* `Reset Z offfset` - устанавливает собственный отступ по Z каждого из выбранных клиентов в значение `0`.
|
||||
|
||||
---
|
||||
|
||||
* `Developer mode`: **Внимание!** Используйте данные действия с большой осторожностью.
|
||||
|
||||
|
||||
* `Update clever-show git` - обновляет папку репозитория `clever-show` на выбранных клиентах. Файлы конфигурации клиента *не будут* перезаписаны. **Внимание!** Для того, чтобы изменения вступили в силу, *необходимо* перезапустить сервис `clever-show`.
|
||||
|
||||
---
|
||||
|
||||
* `Reboot` - полностью перезагружает полётный контроллер и компьютер на выбранных коптерах. Во время перезапуска клиенты будут отключены.
|
||||
|
||||
#### Раздел Server
|
||||
@@ -112,12 +128,14 @@
|
||||
* `Play music` - воспроизводит загруженную музыку.
|
||||
* `Stop music` - останавливает воспроизведение проигрываемой музыки.
|
||||
|
||||
------
|
||||
---
|
||||
|
||||
* `Edit server config` - открывает [встроенный редактор конфигурационных файлов](#config-editor) с текущей конфигурацией сервера для редактирования. Доступен чекбокс `Restart` - в случае, если он нажат, то при сохранении конфигурации сервер будет перезапущен. **Внимание!** Изменённые параметры конфигурации будут применены к серверу только после его перезапуска (ручного или автоматического).
|
||||
|
||||
* `Edit any config` - открывает [встроенный редактор конфигурационных файлов](#config-editor) и позволяет выбрать для редактирования в файловой системе любой файл конфигурации c расширением `.ini` или же открыть файл спецификации конфигурации для создания файла конфигурации на его основе.
|
||||
|
||||
---
|
||||
|
||||
* `Restart server` - полностью перезапускает сервер. **Внимание!** После перезапуска сервер более не будет соединён с консолью, из которой был запущен, если сервер изначально был запущен из консоли.
|
||||
|
||||
#### Раздел Table
|
||||
@@ -127,7 +145,13 @@
|
||||
* `Toggle select` (`Ctrl+A`) - выделят все коптеры\снимает выделение со всех коптеров. Если в таблице выбраны не все коптеры, то *выделяет все* коптеры. Иначе (если были выделены все коптеры) *снимает выделение* со всех коптеров.
|
||||
* `Select all` - выделят все коптеры в таблице.
|
||||
* `Deselect all` - снимает выделение со всех коптеров в таблице.
|
||||
|
||||
---
|
||||
|
||||
* `Remove selected drones` - удаляет выбранные коптеры из таблицы. **Внимание!** В случае, если клиент был подключен, будет произведено отключение. В случае если удалённый таким образом клиент исправно функционировал, он переподключится в кратчайшие сроки.
|
||||
|
||||
---
|
||||
|
||||
* `Configure columns` - открывает [встроенный конфигуратор](#column-preset-editor) наборов настроек столбцов таблицы.
|
||||
|
||||
### Боковая панель команд
|
||||
@@ -200,18 +224,6 @@
|
||||
* `port` - TCP порт, на который будут приниматься входящие соединения от клиентов. При использовании broadcast данный порт будет сконфигурирован у клиента автоматически. *Рекомендуется изменить значение по умолчанию в целях безопасности* (любое пятизначное и более число, если другое ПО не использует выбранный порт).
|
||||
* `buffer_size` - размер буфера при приёме и передаче данных. *Не рекомендуется изменять. Рекомендуется использовать единое значение у сервера и клиентов.*
|
||||
|
||||
#### Раздел TABLE
|
||||
|
||||
* `remove_disconnected` - Определяет поведение при разрыве связи с клиентом. При значении `True` вся информация о клиенте *будет удалена* как из внутренней памяти, так и *из таблицы*. *Это может привести к 'скачкам' таблицы при отключении клиентов.* При значении `False` отключённые клиенты *не будут* удалены из таблицы, но будут отображены с подсвечиванием ячейки в столбце `copter ID` красным цветом. Все данные будут сохранены. При переподключении клиента, он будет ассоциирован с той же строкой таблицы, а ячейка со значением `copter ID` вновь станет зелёного цвета.
|
||||
|
||||
##### Подраздел PRESETS
|
||||
|
||||
Не рекомендуется изменять данный раздел вручную - для редактирования данных параметров можно взаимодействовать с таблицей или используя встроенный диалог конфигурации таблицы.
|
||||
|
||||
* `current` - Название текущего выбранного набора настроек столбцов таблицы
|
||||
* `<название_набора>`
|
||||
* `<название_столбца>` - значение представляет собой список (через ",") из булевого значения (отображается ли столбец в таблице) и целого числа больше 0 (ширину столбца в пикселах)
|
||||
|
||||
#### Раздел CHECKS
|
||||
|
||||
В этом разделе задаются параметры проверок коптера, которые регулируются на стороне сервера. Доступны следующие параметры:
|
||||
@@ -239,6 +251,18 @@
|
||||
* `host` - имя хоста или IP адрес NTP сервера (локального или удаленного)
|
||||
* `port` - порт, используемый NTP сервером
|
||||
|
||||
#### Раздел TABLE
|
||||
|
||||
* `remove_disconnected` - Определяет поведение при разрыве связи с клиентом. При значении `True` вся информация о клиенте *будет удалена* как из внутренней памяти, так и *из таблицы*. *Это может привести к 'скачкам' таблицы при отключении клиентов.* При значении `False` отключённые клиенты *не будут* удалены из таблицы, но будут отображены с подсвечиванием ячейки в столбце `copter ID` красным цветом. Все данные будут сохранены. При переподключении клиента, он будет ассоциирован с той же строкой таблицы, а ячейка со значением `copter ID` вновь станет зелёного цвета.
|
||||
|
||||
##### Подраздел PRESETS
|
||||
|
||||
Не рекомендуется изменять данный раздел вручную - для редактирования данных параметров можно взаимодействовать с таблицей или используя встроенный диалог конфигурации таблицы.
|
||||
|
||||
* `current` - Название текущего выбранного набора настроек столбцов таблицы
|
||||
* `<название_набора>`
|
||||
* `<название_столбца>` - значение представляет собой список (через ",") из булевого значения (отображается ли столбец в таблице) и целого числа больше 0 (ширину столбца в пикселах)
|
||||
|
||||
## Дополнительные операции и окна
|
||||
|
||||
### Visual land
|
||||
|
||||
@@ -1,10 +1,10 @@
|
||||
# Быстрый старт
|
||||
# Быстрый старт на квадрокоптере Клевер
|
||||
|
||||
## Список оборудования
|
||||
|
||||
Данное ПО предназначено для управления несколькими квадрокоптерами с компьютера-сервера. Для полноценной работы необходимо следующее оборудование:
|
||||
|
||||
* Один или несколько квадрокоптеров, работающих на базе ПО [Клевер](https://github.com/copterexpress/clever).
|
||||
* Один или несколько квадрокоптеров, работающих на базе ПО [Клевер](https://github.com/CopterExpress/clover).
|
||||
* Компьютер с операционной системой Ubuntu 18.04.
|
||||
* Wifi роутер, работающий на частоте 2.4 ГГц, либо 5.8 ГГц, если эту частоту поддерживают wifi модули коптеров и компьютера.
|
||||
|
||||
@@ -24,36 +24,33 @@
|
||||
|
||||
Для управления одним или несколькими коптерами требуется подключение коптеров и сервера к одной сети. Для этого требуется отдельный wifi роутер с известным SSID и паролем.
|
||||
|
||||
Подключите компьютер, который будет использоваться в качестве сервера, к сети роутера и узнайте его ip адрес - он понадобится для дальнейшей настройки.
|
||||
|
||||
## Установка и запуск клиента
|
||||
|
||||
* Запишите образ на microSD карту, используя [Etcher](https://www.balena.io/etcher/).
|
||||
* Вставьте флешку в Raspberry Pi, включите коптер. Дождитесь появления сети `CLEVERSHOW-XXXX`.
|
||||
* Подключитесь к сети коптера, используя пароль `cleverwifi`.
|
||||
* Вставьте флешку в Raspberry Pi, включите коптер. Дождитесь появления сети `clever-show-XXXX`.
|
||||
* Подключитесь к сети коптера, используя пароль `cloverwifi`.
|
||||
* Подключитесь к Raspberry Pi на коптере с помощью ssh, используя статический ip `192.168.11.1`, имя пользователя `pi` и пароль `raspberry`.
|
||||
|
||||
```bash
|
||||
ssh pi@192.168.11.1
|
||||
```
|
||||
|
||||
* Перейдите в директорию клиента и выполните скрипт настройки клиента с указанными параметрами - название точки доступа (`SSID`), пароль точки доступа (`password`), имя коптера (`copter name`), ip сервера (`server ip`). Коптер переключится в режим клиента указанной точки доступа и настроит автозапуск клиента на Raspberry Pi.
|
||||
* После подключения выполните скрипт настройки клиента `client-setup` с указанными параметрами - название точки доступа (`SSID`), пароль точки доступа (`password`), имя коптера (`copter name`). Коптер переключится в режим клиента указанной точки доступа и настроит автозапуск клиента `clever-show` на Raspberry Pi.
|
||||
|
||||
```bash
|
||||
cd ~/clever-show/Drone
|
||||
sudo ./client_setup.sh <SSID> <password> <copter name> <server ip>
|
||||
sudo client-setup <SSID> <password> <copter name>
|
||||
```
|
||||
|
||||
* Теперь при запуске серверного приложения настроенные коптеры будут отображаться в виде таблицы. Также можно подключаться к Raspberry Pi на коптере по его имени с добавкой .local через `ssh` в указанной при настройке wifi сети, например `ssh pi@clever-1.local`, пароль `raspberry`.
|
||||
* Теперь при запуске серверного приложения настроенные коптеры будут отображаться в виде таблицы. Также можно подключаться к Raspberry Pi на коптере по его имени с добавкой .local через `ssh` в указанной при настройке wifi сети, например `ssh pi@clover-1.local`, пароль `raspberry`.
|
||||
|
||||
> **Подробная документация по настройке клиентской части находится [здесь](client.md).**
|
||||
|
||||
## Установка и запуск сервера
|
||||
|
||||
* Установите [chrony](https://chrony.tuxfamily.org/index.html), [samba](https://help.ubuntu.ru/wiki/samba) и Python 3 на ваш компьютер:
|
||||
* Установите [chrony](https://chrony.tuxfamily.org/index.html) на ваш компьютер для синхронизации времени с коптерами:
|
||||
|
||||
```bash
|
||||
sudo apt install chrony python3 python3-pip
|
||||
sudo apt install chrony
|
||||
```
|
||||
|
||||
* Установите необходимые python-пакеты с помощью команды (запущенной из директории с исходным кодом)
|
||||
@@ -63,7 +60,7 @@ pip3 install -r requirements.txt
|
||||
```
|
||||
|
||||
* Подключитесь к wifi сети роутера, к которому подключены коптеры.
|
||||
* Скопируйте [файл настроек chrony](../../Server/chrony.conf) в `/etc/chrony/chrony.conf`. Если ip адрес сети начинается не с `192.168.`, то исправьте адрес после слова allow в скопированном файле настроек.
|
||||
* Скопируйте [файл настроек chrony](../../examples/chrony/server.conf) в `/etc/chrony/chrony.conf`. Если ip адрес сети начинается не с `192.168.`, то исправьте адрес после слова allow в скопированном файле настроек.
|
||||
* Перезапустите сервис chrony
|
||||
|
||||
```bash
|
||||
@@ -73,8 +70,8 @@ sudo systemctl restart chrony
|
||||
* Перейдите в директорию сервера из директории с исходным кодом и запустите сервер
|
||||
|
||||
```bash
|
||||
cd source-code-dir/Server
|
||||
python3 server_qt.py
|
||||
cd clever-show/server
|
||||
python3 server.py
|
||||
```
|
||||
|
||||
> **Подробная документация по настройке серверной части находится [здесь](server.md).**
|
||||
@@ -89,6 +86,6 @@ python3 server_qt.py
|
||||
|
||||
## Подготовка анимации
|
||||
|
||||
* Создайте анимацию объектов в Blender или воспользуйтесь [примерами](../../blender-addon/examples). Условная единица расстояния в Blender конвертируется в метры. Задержка между кадрами по-умолчанию в [настройках коптера](../../Drone/client_config.ini) равна 0.1 секунды (параметр frame_delay в разделе ANIMATION), будьте внимательны при настройке частоты кадров в анимации Blender. Следите за скоростями коптеров, чтобы они были не слишком большими: аддон выдаст предупреждение, но всё равно сконвертирует анимацию.
|
||||
* Создайте анимацию объектов в Blender или воспользуйтесь [примерами](../../examples/animations). Условная единица расстояния в Blender конвертируется в метры. Задержка между кадрами по-умолчанию в [настройках коптера](../../drone/config/client.ini) равна 0.1 секунды (параметр frame_delay в разделе ANIMATION), будьте внимательны при настройке частоты кадров в анимации Blender. Следите за скоростями коптеров, чтобы они были не слишком большими: аддон выдаст предупреждение, но всё равно сконвертирует анимацию.
|
||||
* Сконвертируйте анимацию с помощью [аддона для Blender](blender-addon.md).
|
||||
* Загрузите анимацию с помощью команды `Send animations` на [сервере](server.md#раздел-server).
|
||||
|
||||
43
drone/README.md
Normal file
@@ -0,0 +1,43 @@
|
||||
# clever-show drone client
|
||||
|
||||
Application for remote synchronized control of drones and failsafe drone protection module.
|
||||
|
||||
* `client.py` is the main drone communication and control module
|
||||
* `failsafe.py` is the drone protection module, which creates `/emergency_land` service and monitors the state of the drone in accordance with the logic specified in `[FAILSAFE]` item of `client.ini` settings file
|
||||
|
||||
## Requirements
|
||||
|
||||
* Ubuntu Bionic or Debian Stretch
|
||||
* ROS Melodic
|
||||
* Clover ROS package
|
||||
* Python 2.7
|
||||
* Time synchronization client
|
||||
|
||||
Can be used with built-in NTP client or with external package for time synchronization like `chrony` on Linux systems.
|
||||
|
||||
## Installation
|
||||
|
||||
```cmd
|
||||
pip install -r requirements.txt
|
||||
```
|
||||
|
||||
## Usage
|
||||
|
||||
Start roscore with clover package on the drone or on the PC with drone simulator.
|
||||
|
||||
Start client:
|
||||
|
||||
```cmd
|
||||
python client.py
|
||||
```
|
||||
|
||||
If you want to start failsafe module, execute in the other terminal:
|
||||
|
||||
```cmd
|
||||
python failsafe.py
|
||||
```
|
||||
|
||||
## Documentation
|
||||
|
||||
* English
|
||||
* [Russian](../docs/ru/client.md)
|
||||
@@ -2,49 +2,62 @@ import os
|
||||
import sys
|
||||
import time
|
||||
import math
|
||||
import rospy
|
||||
import numpy
|
||||
import psutil
|
||||
import logging
|
||||
import datetime
|
||||
import threading
|
||||
import subprocess
|
||||
from collections import namedtuple
|
||||
from watchdog.observers import Observer
|
||||
from watchdog.events import FileSystemEventHandler
|
||||
|
||||
# for backward compatibility with clever
|
||||
# Import rospy
|
||||
try:
|
||||
import rospy
|
||||
except ImportError:
|
||||
print("Can't import rospy! Please check your ROS installation.")
|
||||
exit()
|
||||
|
||||
import rospkg
|
||||
|
||||
# Import clever or clover package
|
||||
try:
|
||||
from clever import srv
|
||||
except ImportError:
|
||||
try:
|
||||
from clover import srv
|
||||
except ImportError:
|
||||
print("Can't import clever or clover")
|
||||
|
||||
import datetime
|
||||
import logging
|
||||
import threading
|
||||
import psutil
|
||||
import subprocess
|
||||
from collections import namedtuple
|
||||
from watchdog.observers import Observer
|
||||
from watchdog.events import FileSystemEventHandler
|
||||
print("Can't import clever or clover! Please check installation of clover ROS package.")
|
||||
exit()
|
||||
|
||||
# Import flight control
|
||||
try:
|
||||
from FlightLib import FlightLib
|
||||
import modules.flight as flight
|
||||
except ImportError:
|
||||
print("Can't import FlightLib")
|
||||
print("Can't import flight control module!")
|
||||
|
||||
# Import led control
|
||||
try:
|
||||
from FlightLib import LedLib
|
||||
import modules.led as led
|
||||
except ImportError:
|
||||
print("Can't import LedLib")
|
||||
print("Can't import led control module!")
|
||||
|
||||
import client
|
||||
# Add parent dir to PATH to import messaging_lib and config_lib
|
||||
current_dir = (os.path.dirname(os.path.realpath(__file__)))
|
||||
lib_dir = os.path.realpath(os.path.join(current_dir, '../lib'))
|
||||
sys.path.insert(0, lib_dir)
|
||||
|
||||
import messaging_lib as messaging
|
||||
import tasking_lib as tasking
|
||||
import animation_lib as animation
|
||||
|
||||
from mavros_mavlink import *
|
||||
import messaging
|
||||
import modules.client_core as client_core
|
||||
import modules.animation as animation
|
||||
import modules.mavros_wrapper as mavros
|
||||
import modules.tasking as tasking
|
||||
|
||||
from std_msgs.msg import Bool
|
||||
from geometry_msgs.msg import Point, Quaternion, TransformStamped
|
||||
from tf.transformations import quaternion_from_euler, euler_from_quaternion, quaternion_multiply
|
||||
import tf2_ros
|
||||
|
||||
from geographiclib.geodesic import Geodesic
|
||||
|
||||
Earth = Geodesic.WGS84
|
||||
@@ -85,62 +98,73 @@ logger = logging.getLogger(__name__)
|
||||
logger.setLevel(logging.DEBUG)
|
||||
logger.addHandler(handler)
|
||||
|
||||
animation_logger = logging.getLogger('animation_lib')
|
||||
animation_logger = logging.getLogger('modules.animation')
|
||||
animation_logger.setLevel(logging.INFO)
|
||||
animation_logger.addHandler(handler)
|
||||
|
||||
client_logger = logging.getLogger('client')
|
||||
client_logger = logging.getLogger('modules.client_core')
|
||||
client_logger.setLevel(logging.DEBUG)
|
||||
client_logger.addHandler(handler)
|
||||
|
||||
messaging_logger = logging.getLogger('messaging_lib')
|
||||
messaging_logger = logging.getLogger('messaging')
|
||||
messaging_logger.setLevel(logging.INFO)
|
||||
messaging_logger.addHandler(handler)
|
||||
|
||||
tasking_logger = logging.getLogger('tasking_lib')
|
||||
tasking_logger = logging.getLogger('modules.tasking')
|
||||
tasking_logger.setLevel(logging.INFO)
|
||||
tasking_logger.addHandler(handler)
|
||||
|
||||
flightlib_logger = logging.getLogger('FlightLib')
|
||||
flightlib_logger.setLevel(logging.INFO)
|
||||
flightlib_logger.addHandler(handler)
|
||||
flight_logger = logging.getLogger('modules.flight')
|
||||
flight_logger.setLevel(logging.INFO)
|
||||
flight_logger.addHandler(handler)
|
||||
|
||||
mavros_mavlink_logger = logging.getLogger('mavros_mavlink')
|
||||
mavros_mavlink_logger = logging.getLogger('modules.mavros_wrapper')
|
||||
mavros_mavlink_logger.setLevel(logging.INFO)
|
||||
mavros_mavlink_logger.addHandler(handler)
|
||||
|
||||
|
||||
class CopterClient(client.Client):
|
||||
class CopterClient(client_core.Client):
|
||||
def __init__(self, config_path="config/client.ini"):
|
||||
super(CopterClient, self).__init__(config_path)
|
||||
self.load_config()
|
||||
if self.config.clover_dir == 'auto':
|
||||
self.check_clover_dir()
|
||||
self.telemetry = None
|
||||
self.animation = animation.Animation(self.config, "animation.csv")
|
||||
|
||||
def load_config(self):
|
||||
super(CopterClient, self).load_config()
|
||||
|
||||
def check_clover_dir(self):
|
||||
rospack = rospkg.RosPack()
|
||||
try:
|
||||
path = rospack.get_path('clever')
|
||||
except rospkg.common.ResourceNotFound:
|
||||
try:
|
||||
path = rospack.get_path('clover')
|
||||
except rospkg.common.ResourceNotFound:
|
||||
path = 'error'
|
||||
self.config.set('', 'clover_dir', path, write=True)
|
||||
if path.count("/pi/"):
|
||||
self.server_connection.whoami = "pi"
|
||||
|
||||
def on_broadcast_bind(self):
|
||||
repair_chrony(self.config.server_host)
|
||||
|
||||
def start(self, task_manager_instance):
|
||||
rospy.loginfo("Init ROS node")
|
||||
rospy.init_node('clever_show_client', anonymous=True)
|
||||
if self.config.led_use:
|
||||
from FlightLib import LedLib
|
||||
LedLib.init_led(self.config.led_pin)
|
||||
task_manager_instance.start()
|
||||
start_subscriber()
|
||||
mavros.start_subscriber()
|
||||
self.telemetry = Telemetry()
|
||||
self.telemetry.start_loop()
|
||||
if self.config.copter_frame_id == "floor":
|
||||
if self.config.flight_frame_id == "floor":
|
||||
self.start_floor_frame_broadcast()
|
||||
elif self.config.copter_frame_id == "gps":
|
||||
elif self.config.flight_frame_id == "gps":
|
||||
self.start_gps_frame_broadcast()
|
||||
client_thread = threading.Thread(target=super(CopterClient, self).start, name="Client thread")
|
||||
client_thread.daemon = True
|
||||
client_thread.start()
|
||||
#super(CopterClient, self).start()
|
||||
|
||||
def start_floor_frame_broadcast(self):
|
||||
if self.config.floor_frame_parent == "gps":
|
||||
@@ -153,7 +177,7 @@ class CopterClient(client.Client):
|
||||
math.radians(self.config.floor_frame_rotation[1]),
|
||||
math.radians(self.config.floor_frame_rotation[2])))
|
||||
trans.header.frame_id = self.config.floor_frame_parent
|
||||
trans.child_frame_id = self.config.copter_frame_id
|
||||
trans.child_frame_id = self.config.flight_frame_id
|
||||
static_broadcaster.sendTransform(trans)
|
||||
|
||||
def start_gps_frame_broadcast(self):
|
||||
@@ -172,7 +196,7 @@ class CopterClient(client.Client):
|
||||
def gps_frame_broadcast_loop(self):
|
||||
rate = rospy.Rate(1)
|
||||
while not rospy.is_shutdown():
|
||||
telem = FlightLib.get_telemetry_locked(frame_id = "map")
|
||||
telem = flight.get_telemetry_locked(frame_id = "map")
|
||||
if telem is not None:
|
||||
if math.isnan(telem.lat) or math.isnan(telem.lon) or math.isnan(telem.x) or math.isnan(telem.y):
|
||||
logger.info("Can't get position from telemetry")
|
||||
@@ -338,7 +362,7 @@ def _response_id(*args, **kwargs):
|
||||
if new_id is not None:
|
||||
old_id = copter.client_id
|
||||
if new_id != old_id:
|
||||
copter.config.set('PRIVATE', 'id', new_id, write=True)
|
||||
copter.config.set('', 'id', new_id, write=True)
|
||||
copter.client_id = new_id
|
||||
if new_id != '/hostname':
|
||||
if copter.config.system_restart_after_rename:
|
||||
@@ -359,11 +383,11 @@ def _response_id(*args, **kwargs):
|
||||
|
||||
@messaging.request_callback("selfcheck")
|
||||
def _response_selfcheck(*args, **kwargs):
|
||||
if check_state_topic(wait_new_status=True):
|
||||
check = FlightLib.selfcheck()
|
||||
if mavros.check_state_topic(wait_new_status=True):
|
||||
check = flight.selfcheck()
|
||||
return check if check else "OK"
|
||||
else:
|
||||
stop_subscriber()
|
||||
mavros.stop_subscriber()
|
||||
return "NOT_CONNECTED_TO_FCU"
|
||||
|
||||
|
||||
@@ -381,33 +405,33 @@ def _response_animation_id(*args, **kwargs):
|
||||
|
||||
@messaging.request_callback("batt_voltage")
|
||||
def _response_batt(*args, **kwargs):
|
||||
if check_state_topic(wait_new_status=True):
|
||||
return FlightLib.get_telemetry_locked('body').voltage
|
||||
if mavros.check_state_topic(wait_new_status=True):
|
||||
return flight.get_telemetry_locked('body').voltage
|
||||
else:
|
||||
stop_subscriber()
|
||||
mavros.stop_subscriber()
|
||||
return float('nan')
|
||||
|
||||
|
||||
@messaging.request_callback("cell_voltage")
|
||||
def _response_cell(*args, **kwargs):
|
||||
if check_state_topic(wait_new_status=True):
|
||||
return FlightLib.get_telemetry_locked('body').cell_voltage
|
||||
if mavros.check_state_topic(wait_new_status=True):
|
||||
return flight.get_telemetry_locked('body').cell_voltage
|
||||
else:
|
||||
stop_subscriber()
|
||||
mavros.stop_subscriber()
|
||||
return float('nan')
|
||||
|
||||
|
||||
@messaging.request_callback("sys_status")
|
||||
def _response_sys_status(*args, **kwargs):
|
||||
return get_sys_status()
|
||||
return mavros.get_sys_status()
|
||||
|
||||
|
||||
@messaging.request_callback("cal_status")
|
||||
def _response_cal_status(*args, **kwargs):
|
||||
if check_state_topic(wait_new_status=True):
|
||||
return get_calibration_status()
|
||||
if mavros.check_state_topic(wait_new_status=True):
|
||||
return mavros.get_calibration_status()
|
||||
else:
|
||||
stop_subscriber()
|
||||
mavros.stop_subscriber()
|
||||
return "NOT_CONNECTED_TO_FCU"
|
||||
|
||||
|
||||
@@ -415,24 +439,24 @@ def _response_cal_status(*args, **kwargs):
|
||||
def _response_position(*args, **kwargs):
|
||||
telem = copter.telemetry.ros_telemetry
|
||||
return "{:.2f} {:.2f} {:.2f} {:.1f} {}".format(
|
||||
telem.x, telem.y, telem.z, math.degrees(telem.yaw), copter.config.copter_frame_id)
|
||||
telem.x, telem.y, telem.z, math.degrees(telem.yaw), copter.config.flight_frame_id)
|
||||
|
||||
|
||||
@messaging.request_callback("calibrate_gyro")
|
||||
def _calibrate_gyro(*args, **kwargs):
|
||||
calibrate('gyro')
|
||||
return get_calibration_status()
|
||||
mavros.calibrate('gyro')
|
||||
return mavros.get_calibration_status()
|
||||
|
||||
|
||||
@messaging.request_callback("calibrate_level")
|
||||
def _calibrate_level(*args, **kwargs):
|
||||
calibrate('level')
|
||||
return get_calibration_status()
|
||||
mavros.calibrate('level')
|
||||
return mavros.get_calibration_status()
|
||||
|
||||
|
||||
@messaging.request_callback("load_params")
|
||||
def _load_params(*args, **kwargs):
|
||||
result = load_param_file('temp.params')
|
||||
result = mavros.load_param_file('temp.params')
|
||||
logger.info("Load parameters to FCU success: {}".format(result))
|
||||
return result
|
||||
|
||||
@@ -451,9 +475,9 @@ def _command_update_animation(*args, **kwargs):
|
||||
|
||||
@messaging.message_callback("move_start")
|
||||
def _command_move_start_to_current_position(*args, **kwargs):
|
||||
offset = numpy.array(copter.config.private_offset) + numpy.array(copter.config.copter_common_offset)
|
||||
offset = numpy.array(copter.config.animation_private_offset) + numpy.array(copter.config.animation_common_offset)
|
||||
try:
|
||||
xs, ys, zs = copter.animation.get_start_point(copter.config.ratio, offset)
|
||||
xs, ys, zs = copter.animation.get_start_point(copter.config.animation_ratio, offset)
|
||||
except ValueError:
|
||||
logger.error("Can't get start point. Check animation file!")
|
||||
else:
|
||||
@@ -461,38 +485,36 @@ def _command_move_start_to_current_position(*args, **kwargs):
|
||||
telem = copter.telemetry.ros_telemetry
|
||||
logger.debug("telemetry x = {}, y = {}".format(telem.x, telem.y))
|
||||
if valid([telem.x, telem.y, telem.z]):
|
||||
copter.config.set('PRIVATE', 'offset',
|
||||
[telem.x - xs, telem.y - ys, copter.config.private_offset[2]], write=True)
|
||||
logger.info("Set start delta: {:.2f} {:.2f}".format(copter.config.private_offset[0],
|
||||
copter.config.private_offset[1]))
|
||||
copter.config.set('animation', 'private_offset',
|
||||
[telem.x - xs, telem.y - ys, copter.config.animation_private_offset[2]], write=True)
|
||||
logger.info("Set start delta: {:.2f} {:.2f}".format(copter.config.animation_private_offset[0],
|
||||
copter.config.animation_private_offset[1]))
|
||||
else:
|
||||
logger.error("Wrong telemetry")
|
||||
|
||||
|
||||
@messaging.message_callback("reset_start")
|
||||
def _command_reset_start(*args, **kwargs):
|
||||
copter.config.set('PRIVATE', 'offset',
|
||||
[0, 0, copter.config.private_offset[2]], write=True)
|
||||
logger.info("Reset start to {:.2f} {:.2f}".format(copter.config.private_offset[0],
|
||||
copter.config.private_offset[1]))
|
||||
copter.config.set('animation', 'private_offset', [0, 0, copter.config.animation_private_offset[2]], write=True)
|
||||
logger.info("Reset start to {:.2f} {:.2f}".format(copter.config.animation_private_offset[0], copter.config.animation_private_offset[1]))
|
||||
|
||||
|
||||
@messaging.message_callback("set_z_to_ground")
|
||||
def _command_set_z(*args, **kwargs):
|
||||
telem = copter.telemetry.ros_telemetry
|
||||
if valid([telem.x, telem.y, telem.z]):
|
||||
copter.config.set('PRIVATE', 'offset',
|
||||
[copter.config.private_offset[0], copter.config.private_offset[1], telem.z], write=True)
|
||||
logger.info("Set z offset to {:.2f}".format(copter.config.private_offset[2]))
|
||||
copter.config.set('animation', 'private_offset',
|
||||
[copter.config.animation_private_offset[0], copter.config.animation_private_offset[1], telem.z], write=True)
|
||||
logger.info("Set z offset to {:.2f}".format(copter.config.animation_private_offset[2]))
|
||||
else:
|
||||
logger.error("Wrong telemetry")
|
||||
|
||||
|
||||
@messaging.message_callback("reset_z_offset")
|
||||
def _command_reset_z(*args, **kwargs):
|
||||
copter.config.set('PRIVATE', 'offset',
|
||||
[copter.config.private_offset[0], copter.config.private_offset[1], 0], write=True)
|
||||
logger.info("Reset z offset to {:.2f}".format(copter.config.private_offset[2]))
|
||||
copter.config.set('animation', 'private_offset',
|
||||
[copter.config.animation_private_offset[0], copter.config.animation_private_offset[1], 0], write=True)
|
||||
logger.info("Reset z offset to {:.2f}".format(copter.config.animation_private_offset[2]))
|
||||
|
||||
|
||||
@messaging.message_callback("update_repo")
|
||||
@@ -504,13 +526,13 @@ def _command_update_repo(*args, **kwargs):
|
||||
|
||||
@messaging.message_callback("reboot_all")
|
||||
def _command_reboot_all(*args, **kwargs):
|
||||
reboot_fcu()
|
||||
mavros.reboot_fcu()
|
||||
execute_command("reboot")
|
||||
|
||||
|
||||
@messaging.message_callback("reboot_fcu")
|
||||
def _command_reboot(*args, **kwargs):
|
||||
reboot_fcu()
|
||||
mavros.reboot_fcu()
|
||||
|
||||
|
||||
@messaging.message_callback("service_restart")
|
||||
@@ -530,22 +552,20 @@ def _command_chrony_repair(*args, **kwargs):
|
||||
|
||||
@messaging.message_callback("led_test")
|
||||
def _command_led_test(*args, **kwargs):
|
||||
LedLib.chase(255, 255, 255)
|
||||
time.sleep(2)
|
||||
LedLib.off()
|
||||
led.set_effect(effect='flash', r=255, g=255, b=255)
|
||||
|
||||
|
||||
@messaging.message_callback("led_fill")
|
||||
def _command_led_fill(*args, **kwargs):
|
||||
r = kwargs.get("red", 0)
|
||||
g = kwargs.get("green", 0)
|
||||
b = kwargs.get("blue", 0)
|
||||
LedLib.fill(r, g, b)
|
||||
red = kwargs.get("red", 0)
|
||||
green = kwargs.get("green", 0)
|
||||
blue = kwargs.get("blue", 0)
|
||||
led.set_effect(r=red, g=green, b=blue)
|
||||
|
||||
|
||||
@messaging.message_callback("flip")
|
||||
def _copter_flip(*args, **kwargs):
|
||||
FlightLib.flip(frame_id=copter.config.copter_frame_id)
|
||||
flight.flip(frame_id=copter.config.flight_frame_id)
|
||||
|
||||
|
||||
@messaging.message_callback("takeoff")
|
||||
@@ -553,8 +573,8 @@ def _command_takeoff(*args, **kwargs):
|
||||
logger.info("Takeoff at {}".format(datetime.datetime.now()))
|
||||
task_manager.add_task(0, 0, animation.takeoff,
|
||||
task_kwargs={
|
||||
"z": copter.config.copter_takeoff_height,
|
||||
"timeout": copter.config.copter_takeoff_time,
|
||||
"z": copter.config.flight_takeoff_height,
|
||||
"timeout": copter.config.flight_takeoff_time,
|
||||
"safe_takeoff": False,
|
||||
"use_leds": copter.config.led_use & copter.config.led_takeoff_indication,
|
||||
})
|
||||
@@ -569,16 +589,16 @@ def _command_takeoff_z(*args, **kwargs):
|
||||
except ValueError:
|
||||
logger.error("takeoff_z: Wrong z argument!")
|
||||
else:
|
||||
telem = FlightLib.get_telemetry_locked(copter.config.copter_frame_id)
|
||||
telem = flight.get_telemetry_locked(copter.config.flight_frame_id)
|
||||
if valid([telem.x, telem.y, telem.z]):
|
||||
logger.info("Takeoff to z = {} at {}".format(z, datetime.datetime.now()))
|
||||
task_manager.add_task(0, 0, FlightLib.reach_point,
|
||||
task_manager.add_task(0, 0, flight.reach_point,
|
||||
task_kwargs={
|
||||
"x": telem.x,
|
||||
"y": telem.y,
|
||||
"z": z,
|
||||
"frame_id": copter.config.copter_frame_id,
|
||||
"timeout": copter.config.copter_takeoff_time,
|
||||
"frame_id": copter.config.flight_frame_id,
|
||||
"timeout": copter.config.flight_takeoff_time,
|
||||
"auto_arm": True,
|
||||
})
|
||||
else:
|
||||
@@ -590,22 +610,26 @@ def _command_land(*args, **kwargs):
|
||||
task_manager.reset()
|
||||
task_manager.add_task(0, 0, animation.land,
|
||||
task_kwargs={
|
||||
"z": copter.config.copter_takeoff_height,
|
||||
"timeout": copter.config.copter_land_timeout,
|
||||
"frame_id": copter.config.copter_frame_id,
|
||||
"z": copter.config.flight_takeoff_height,
|
||||
"timeout": copter.config.flight_land_timeout,
|
||||
"frame_id": copter.config.flight_frame_id,
|
||||
"use_leds": copter.config.led_use & copter.config.led_land_indication,
|
||||
})
|
||||
|
||||
|
||||
@messaging.message_callback("emergency_land")
|
||||
def _emergency_land(*args, **kwargs):
|
||||
logger.info(FlightLib.emergency_land().message)
|
||||
try:
|
||||
result = flight.emergency_land()
|
||||
logger.info(result.message)
|
||||
except rospy.ServiceException:
|
||||
logger.error("Can't execute emergency land: service is unavailable!")
|
||||
|
||||
|
||||
@messaging.message_callback("disarm")
|
||||
def _command_disarm(*args, **kwargs):
|
||||
task_manager.reset()
|
||||
task_manager.add_task(-5, 0, FlightLib.arming_wrapper,
|
||||
task_manager.add_task(-5, 0, flight.arming_wrapper,
|
||||
task_kwargs={
|
||||
"state": False
|
||||
})
|
||||
@@ -645,7 +669,7 @@ def _play_animation(*args, **kwargs):
|
||||
return
|
||||
|
||||
# Get output frames
|
||||
offset = numpy.array(copter.config.private_offset) + numpy.array(copter.config.copter_common_offset)
|
||||
offset = numpy.array(copter.config.animation_private_offset) + numpy.array(copter.config.animation_common_offset)
|
||||
frames = copter.animation.get_scaled_output(copter.config.animation_ratio, offset)
|
||||
if not frames:
|
||||
logger.error("start: No frames in animation!")
|
||||
@@ -672,22 +696,22 @@ def _play_animation(*args, **kwargs):
|
||||
takeoff_time = start_time + start_delay
|
||||
task_manager.add_task(takeoff_time, 0, animation.takeoff,
|
||||
task_kwargs={
|
||||
"z": copter.config.copter_takeoff_height,
|
||||
"timeout": copter.config.copter_takeoff_time,
|
||||
"z": copter.config.flight_takeoff_height,
|
||||
"timeout": copter.config.flight_takeoff_time,
|
||||
"safe_takeoff": False,
|
||||
"use_leds": copter.config.led_use & copter.config.led_takeoff_indication,
|
||||
})
|
||||
# Fly to first point
|
||||
rfp_time = takeoff_time + copter.config.copter_takeoff_time
|
||||
rfp_time = takeoff_time + copter.config.flight_takeoff_time
|
||||
task_manager.add_task(rfp_time, 0, animation.execute_frame,
|
||||
task_kwargs={
|
||||
"frame": frames[0],
|
||||
"frame_id": copter.config.copter_frame_id,
|
||||
"frame_id": copter.config.flight_frame_id,
|
||||
"use_leds": copter.config.led_use,
|
||||
"flight_func": FlightLib.reach_point,
|
||||
"flight_func": flight.reach_point,
|
||||
})
|
||||
# Calculate first frame start time
|
||||
frame_time = rfp_time + copter.config.copter_reach_first_point_time
|
||||
frame_time = rfp_time + copter.config.flight_reach_first_point_time
|
||||
|
||||
elif start_action == 'fly':
|
||||
# Calculate start time
|
||||
@@ -695,31 +719,31 @@ def _play_animation(*args, **kwargs):
|
||||
task_manager.add_task(arm_time, 0, animation.execute_frame,
|
||||
task_kwargs={
|
||||
"frame": frames[0],
|
||||
"frame_id": copter.config.copter_frame_id,
|
||||
"frame_id": copter.config.flight_frame_id,
|
||||
"use_leds": copter.config.led_use,
|
||||
"flight_func": FlightLib.navto,
|
||||
"flight_func": flight.navto,
|
||||
"auto_arm": True,
|
||||
})
|
||||
# Calculate first frame start time
|
||||
frame_time = arm_time + copter.config.copter_arming_time
|
||||
frame_time = arm_time + copter.config.flight_arming_time
|
||||
logger.debug("Start queue {}".format(task_manager.task_queue))
|
||||
# Play animation file
|
||||
for frame in frames:
|
||||
task_manager.add_task(frame_time, 0, animation.execute_frame,
|
||||
task_kwargs={
|
||||
"frame": frame,
|
||||
"frame_id": copter.config.copter_frame_id,
|
||||
"frame_id": copter.config.flight_frame_id,
|
||||
"use_leds": copter.config.led_use,
|
||||
"flight_func": FlightLib.navto,
|
||||
"flight_func": flight.navto,
|
||||
})
|
||||
frame_time += frame.delay
|
||||
# Calculate land_time
|
||||
land_time = frame_time + copter.config.copter_land_delay
|
||||
land_time = frame_time + copter.config.flight_land_delay
|
||||
# Land
|
||||
task_manager.add_task(land_time, 0, animation.land,
|
||||
task_kwargs={
|
||||
"timeout": copter.config.copter_land_timeout,
|
||||
"frame_id": copter.config.copter_frame_id,
|
||||
"timeout": copter.config.flight_land_timeout,
|
||||
"frame_id": copter.config.flight_frame_id,
|
||||
"use_leds": copter.config.led_use & copter.config.led_land_indication,
|
||||
})
|
||||
|
||||
@@ -776,7 +800,7 @@ class Telemetry:
|
||||
return "{} V{}".format(copter.config.config_name, copter.config.config_version)
|
||||
|
||||
def get_start_position(self):
|
||||
offset = numpy.array(copter.config.private_offset) + numpy.array(copter.config.copter_common_offset)
|
||||
offset = numpy.array(copter.config.animation_private_offset) + numpy.array(copter.config.animation_common_offset)
|
||||
try:
|
||||
x, y, z = copter.animation.get_start_point(copter.config.animation_ratio, offset)
|
||||
except ValueError:
|
||||
@@ -790,7 +814,7 @@ class Telemetry:
|
||||
start_action = copter.animation.get_start_action(
|
||||
copter.config.animation_start_action, self.ros_telemetry.z,
|
||||
copter.config.animation_takeoff_level, copter.config.animation_ground_level,
|
||||
copter.config.animation_ratio, offset)
|
||||
copter.config.animation_ratio, offset, self.fcu_status)
|
||||
return [x,y,z,yaw,start_action,start_delay]
|
||||
|
||||
@classmethod
|
||||
@@ -800,9 +824,9 @@ class Telemetry:
|
||||
|
||||
battery_v = ros_telemetry.voltage
|
||||
|
||||
batt_empty_param = get_param('BAT_V_EMPTY')
|
||||
batt_charged_param = get_param('BAT_V_CHARGED')
|
||||
batt_cells_param = get_param('BAT_N_CELLS')
|
||||
batt_empty_param = mavros.get_param('BAT_V_EMPTY')
|
||||
batt_charged_param = mavros.get_param('BAT_V_CHARGED')
|
||||
batt_cells_param = mavros.get_param('BAT_N_CELLS')
|
||||
|
||||
if batt_empty_param.success and batt_charged_param.success and batt_cells_param.success:
|
||||
batt_empty = batt_empty_param.value.real
|
||||
@@ -818,7 +842,7 @@ class Telemetry:
|
||||
|
||||
@classmethod
|
||||
def get_selfcheck(cls):
|
||||
check = FlightLib.selfcheck()
|
||||
check = flight.selfcheck()
|
||||
if not check:
|
||||
check = "OK"
|
||||
return check
|
||||
@@ -830,7 +854,7 @@ class Telemetry:
|
||||
except AttributeError:
|
||||
return 'NO_POS'
|
||||
if not math.isnan(x):
|
||||
return x, y, z, math.degrees(ros_telemetry.yaw), copter.config.copter_frame_id
|
||||
return x, y, z, math.degrees(ros_telemetry.yaw), copter.config.flight_frame_id
|
||||
return 'NO_POS'
|
||||
|
||||
def get_ros_telemetry(self):
|
||||
@@ -839,7 +863,7 @@ class Telemetry:
|
||||
def update_telemetry_fast(self):
|
||||
self.last_task = task_manager.get_current_task()
|
||||
try:
|
||||
self.ros_telemetry = FlightLib.get_telemetry_locked(copter.config.copter_frame_id)
|
||||
self.ros_telemetry = flight.get_telemetry_locked(copter.config.flight_frame_id)
|
||||
if self.ros_telemetry.connected:
|
||||
self.armed = self.ros_telemetry.armed
|
||||
self.mode = self.ros_telemetry.mode
|
||||
@@ -863,8 +887,8 @@ class Telemetry:
|
||||
self.config_version = self.get_config_version()
|
||||
self.start_position = self.get_start_position()
|
||||
try:
|
||||
self.calibration_status = get_calibration_status()
|
||||
self.fcu_status = get_sys_status()
|
||||
self.calibration_status = mavros.get_calibration_status()
|
||||
self.fcu_status = mavros.get_sys_status()
|
||||
self.battery = self.get_battery(self.ros_telemetry)
|
||||
except rospy.ServiceException:
|
||||
rospy.logdebug("Some service is unavailable")
|
||||
@@ -919,7 +943,7 @@ class Telemetry:
|
||||
logger.info("Clear task manager because of {}".format(log_msg))
|
||||
logger.info("Mode: {} | armed: {} | last task: {} ".format(mode, armed, last_task))
|
||||
task_manager.reset()
|
||||
FlightLib.reset_delta()
|
||||
flight.reset_delta()
|
||||
self._tasks_cleared = True
|
||||
self._interruption_counter = 0
|
||||
else:
|
||||
@@ -1,5 +1,8 @@
|
||||
config_name = string(default='client')
|
||||
config_version = float(default=1.0)
|
||||
# Available options: /hostname ; /default ; /ip ; any string 63 characters length
|
||||
id = string(default=/hostname, max=63)
|
||||
clover_dir = string(default=auto)
|
||||
|
||||
[SERVER]
|
||||
port = integer(default=25000, min=1)
|
||||
@@ -15,9 +18,76 @@ transmit = boolean(default=True)
|
||||
frequency = float(default=1.0, min=0)
|
||||
log_resources = boolean(default=False)
|
||||
|
||||
[POSITION WATCHDOG]
|
||||
enabled = boolean(default=True)
|
||||
log_state = boolean(default=True)
|
||||
[FLIGHT]
|
||||
frame_id = string(default=map)
|
||||
arming_time = float(default=0.5)
|
||||
takeoff_height = float(default=1.0)
|
||||
takeoff_time = float(default=5.0, min=0)
|
||||
reach_first_point_time = float(default=5.0, min=0)
|
||||
land_delay = float(default=1.0, min=0)
|
||||
land_timeout = float(default=10.0, min=0)
|
||||
|
||||
[FLOOR FRAME]
|
||||
# Available options: map, aruco_map, gps, floor
|
||||
parent = string(default=map)
|
||||
# Frame translation (x, y, z)
|
||||
# __list__ x y z
|
||||
translation = float_list(default=list(0.0, 0.0, 0.0), min=3, max=3)
|
||||
# Frame rotation (roll, pitch, yaw) in degrees
|
||||
# __list__ roll pitch yaw
|
||||
rotation = float_list(default=list(0.0, 0.0, 0.0), min=3, max=3)
|
||||
|
||||
[GPS FRAME]
|
||||
lat = string(default=0)
|
||||
lon = string(default=0)
|
||||
yaw = float(default=0)
|
||||
|
||||
[ANIMATION]
|
||||
# Available options:
|
||||
# 'auto' - automatic action selection from 'takeoff' or 'fly' based on current copter level
|
||||
# if (start animation point z) - (current height of copter) > (takeoff level) then
|
||||
# start_action is set to 'takeoff', else start_action is set to 'fly'
|
||||
# 'takeoff' - takeoff to first output animation point after static_begin_time then execute 'takeoff logic'
|
||||
# 'fly' - execute animation frames after static_begin_time
|
||||
start_action = string(default=auto)
|
||||
# Takeoff level to set start action automatically
|
||||
takeoff_level = float(default=0.5)
|
||||
# Available options:
|
||||
# * 'current' - current height of copter
|
||||
# * z coordinate in meters
|
||||
ground_level = string(default=current)
|
||||
# Frame delay in seconds
|
||||
frame_delay = float(default=0.1, min=0.01)
|
||||
# Available options:
|
||||
# * 'animation' - take yaw from animation
|
||||
# * 'nan' - don't change yaw during flight
|
||||
# * a number in degrees
|
||||
yaw = string(default=nan)
|
||||
# Animation ratio (x, y, z)
|
||||
# __list__ x y z
|
||||
ratio = float_list(default=list(1.0, 1.0, 1.0), min=3, max=3)
|
||||
# Drone's animation individual offset (x, y, z)
|
||||
# __list__ x y z
|
||||
private_offset = float_list(default=list(0, 0, 0), min=3, max=3)
|
||||
# Drone's animation common offset
|
||||
# __list__ x y z
|
||||
common_offset = float_list(default=list(0, 0, 0), min=3, max=3)
|
||||
# Flags for output frames
|
||||
[[OUTPUT]]
|
||||
static_begin = boolean(default=False)
|
||||
takeoff = boolean(default=True)
|
||||
route = boolean(default=True)
|
||||
land = boolean(default=False)
|
||||
static_end = boolean(default=False)
|
||||
|
||||
[LED]
|
||||
use = boolean(default=False)
|
||||
takeoff_indication = boolean(default=True)
|
||||
land_indication = boolean(default=True)
|
||||
|
||||
[FAILSAFE]
|
||||
enabled = boolean(default=False)
|
||||
log_state = boolean(default=False)
|
||||
# Available options: emergency_land, land, disarm
|
||||
action = string(default=emergency_land)
|
||||
# Time to get vision position after arm
|
||||
@@ -37,72 +107,9 @@ disarm_timeout = float(default=10.0, min=0)
|
||||
thrust = float(default=0.45, min=0, max=1)
|
||||
decrease_thrust_after = float(default=5.0, min=0)
|
||||
|
||||
[COPTER]
|
||||
frame_id = string(default=map)
|
||||
arming_time = float(default=0.5)
|
||||
takeoff_height = float(default=1.0)
|
||||
takeoff_time = float(default=5.0, min=0)
|
||||
reach_first_point_time = float(default=5.0, min=0)
|
||||
land_delay = float(default=1.0, min=0)
|
||||
land_timeout = float(default=10.0, min=0)
|
||||
# __list__ x y z
|
||||
common_offset = float_list(default=list(0, 0, 0), min=3, max=3)
|
||||
|
||||
[FLOOR FRAME]
|
||||
parent = string(default=map)
|
||||
# Frame translation (x, y, z)
|
||||
# __list__ x y z
|
||||
translation = float_list(default=list(0.0, 0.0, 0.0), min=3, max=3)
|
||||
# Frame rotation (roll, pitch, yaw) in degrees
|
||||
# __list__ roll pitch yaw
|
||||
rotation = float_list(default=list(0.0, 0.0, 0.0), min=3, max=3)
|
||||
|
||||
[GPS FRAME]
|
||||
lat = string(default=0)
|
||||
lon = string(default=0)
|
||||
yaw = float(default=0)
|
||||
|
||||
[ANIMATION]
|
||||
# Available options:
|
||||
# 'auto' - automatic action selection from 'takeoff' or 'fly' based on current copter level
|
||||
# 'takeoff' - takeoff to first output animation point after static_begin_time then execute 'takeoff logic'
|
||||
# 'fly' - execute animation frames after static_begin_time
|
||||
start_action = string(default=auto)
|
||||
takeoff_level = float(default=0.5)
|
||||
ground_level = float(default=0)
|
||||
frame_delay = float(default=0.1, min=0.01)
|
||||
# Animation ratio (x, y, z)
|
||||
# __list__ x y z
|
||||
ratio = float_list(default=list(1.0, 1.0, 1.0), min=3, max=3)
|
||||
# Available options:
|
||||
# 'animation' - take yaw from animation
|
||||
# 'nan' - don't change yaw during flight
|
||||
# or a number in degrees
|
||||
yaw = string(default=180.0)
|
||||
[[OUTPUT]]
|
||||
static_begin = boolean(default=False)
|
||||
takeoff = boolean(default=True)
|
||||
route = boolean(default=True)
|
||||
land = boolean(default=False)
|
||||
static_end = boolean(default=False)
|
||||
|
||||
[LED]
|
||||
use = boolean(default=False)
|
||||
pin = integer(default=21, min=0, max=100)
|
||||
count = integer(default=60, min=1)
|
||||
takeoff_indication = boolean(default=True)
|
||||
land_indication = boolean(default=True)
|
||||
|
||||
[PRIVATE]
|
||||
# Available options: /hostname ; /default ; /ip ; any string 63 characters length
|
||||
id = string(default=/hostname, max=63) #TODO our re check
|
||||
# Drone's individual offset (x, y, z)
|
||||
# __list__ x y z
|
||||
offset = float_list(default=list(0, 0, 0), min=3, max=3)
|
||||
|
||||
[SYSTEM]
|
||||
change_hostname = boolean(default=True)
|
||||
restart_after_rename = boolean(default=True)
|
||||
change_hostname = boolean(default=False)
|
||||
restart_after_rename = boolean(default=False)
|
||||
|
||||
[NTP]
|
||||
use = boolean(default=False)
|
||||
@@ -8,9 +8,9 @@ import threading
|
||||
|
||||
# for backward compatibility with clever
|
||||
try:
|
||||
from clever import SetAttitude
|
||||
from clever import srv
|
||||
except ImportError:
|
||||
from clover import SetAttitude
|
||||
from clover import srv
|
||||
|
||||
from sensor_msgs.msg import Range
|
||||
from mavros_msgs.msg import State, PositionTarget
|
||||
@@ -19,23 +19,23 @@ from std_msgs.msg import Bool
|
||||
from std_srvs.srv import Trigger, TriggerResponse
|
||||
from geometry_msgs.msg import PoseStamped
|
||||
|
||||
import inspect # Add parent dir to PATH to import messaging_lib
|
||||
current_dir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||
parent_dir = os.path.dirname(current_dir)
|
||||
sys.path.insert(0, parent_dir)
|
||||
# Add parent dir to PATH to import messaging_lib and config_lib
|
||||
current_dir = (os.path.dirname(os.path.realpath(__file__)))
|
||||
lib_dir = os.path.realpath(os.path.join(current_dir, '../lib'))
|
||||
sys.path.insert(0, lib_dir)
|
||||
|
||||
from config import ConfigManager
|
||||
|
||||
config = ConfigManager()
|
||||
config.load_config_and_spec("config/client.ini")
|
||||
|
||||
watchdog_is_enabled = config.position_watchdog_enabled
|
||||
log_state = config.position_watchdog_log_state
|
||||
vision_pose_delay_after_arm = config.position_watchdog_vision_pose_delay_after_arm
|
||||
visual_pose_timeout = config.position_watchdog_vision_pose_timeout
|
||||
pos_delta_max = config.position_watchdog_position_delta_max
|
||||
watchdog_action = config.position_watchdog_action
|
||||
timeout_to_disarm = config.position_watchdog_disarm_timeout
|
||||
watchdog_is_enabled = config.failsafe_enabled
|
||||
log_state = config.failsafe_log_state
|
||||
vision_pose_delay_after_arm = config.failsafe_vision_pose_delay_after_arm
|
||||
visual_pose_timeout = config.failsafe_vision_pose_timeout
|
||||
pos_delta_max = config.failsafe_position_delta_max
|
||||
watchdog_action = config.failsafe_action
|
||||
timeout_to_disarm = config.failsafe_disarm_timeout
|
||||
emergency_land_thrust = config.emergency_land_thrust
|
||||
emergency_land_decrease_thrust_after = config.emergency_land_decrease_thrust_after
|
||||
|
||||
@@ -58,7 +58,7 @@ logger.addHandler(handler)
|
||||
|
||||
set_mode = rospy.ServiceProxy('/mavros/set_mode', SetMode)
|
||||
arming = rospy.ServiceProxy('/mavros/cmd/arming', CommandBool)
|
||||
set_attitude = rospy.ServiceProxy('/set_attitude', SetAttitude)
|
||||
set_attitude = rospy.ServiceProxy('/set_attitude', srv.SetAttitude)
|
||||
|
||||
visual_pose_last_timestamp = 0
|
||||
armed = False
|
||||
@@ -4,21 +4,23 @@ import copy
|
||||
import math
|
||||
import time
|
||||
import numpy
|
||||
import rospy
|
||||
import logging
|
||||
import threading
|
||||
|
||||
try:
|
||||
from FlightLib import FlightLib
|
||||
except ImportError:
|
||||
print("Can't import FlightLib")
|
||||
try:
|
||||
from FlightLib import LedLib
|
||||
except ImportError:
|
||||
print("Can't import LedLib")
|
||||
|
||||
logger = logging.getLogger(__name__)
|
||||
|
||||
# Import flight control
|
||||
try:
|
||||
import modules.flight as flight
|
||||
except ImportError:
|
||||
logger.debug("Can't import flight control module!")
|
||||
|
||||
# Import led control
|
||||
try:
|
||||
import modules.led as led
|
||||
except ImportError:
|
||||
logger.debug("Can't import led control module!")
|
||||
|
||||
interrupt_event = threading.Event()
|
||||
|
||||
def moving(f1, f2, delta, x=True, y=True, z=True):
|
||||
@@ -319,15 +321,23 @@ class Animation(object):
|
||||
return ground_level <= self.get_scaled_output_min_z(ratio, offset)
|
||||
|
||||
def get_start_action(self, start_action, current_height, takeoff_level,
|
||||
ground_level, ratio=(1,1,1), offset=(0,0,0)):
|
||||
ground_level, ratio=(1,1,1), offset=(0,0,0), state="STANDBY"):
|
||||
# Check output frames
|
||||
if not self.output_frames:
|
||||
return 'error: empty output frames'
|
||||
if math.isnan(current_height):
|
||||
return 'error: bad current_height'
|
||||
return 'error: bad copter height'
|
||||
# Check that bottom point of animation is higher than ground level
|
||||
if ground_level > self.get_scaled_output_min_z(ratio, offset):
|
||||
return 'error: some animation points are lower than ground level'
|
||||
if ground_level == 'current':
|
||||
ground_level = current_height
|
||||
try:
|
||||
ground_level = float(ground_level)
|
||||
except ValueError:
|
||||
return 'error in [ANIMATION] ground_level parameter'
|
||||
if state != "ACTIVE" and ground_level > self.get_scaled_output_min_z(ratio, offset):
|
||||
return 'error: some animation points are lower than ground level for {:.2f}m (max)'.format(
|
||||
ground_level - self.get_scaled_output_min_z(ratio, offset)
|
||||
)
|
||||
# Select start action
|
||||
if start_action == 'auto':
|
||||
if self.get_start_point(ratio, offset)[2] - current_height > takeoff_level:
|
||||
@@ -337,7 +347,7 @@ class Animation(object):
|
||||
elif start_action in ('takeoff', 'fly'):
|
||||
return start_action
|
||||
else:
|
||||
return 'error'
|
||||
return 'error in [ANIMATION] start_action parameter'
|
||||
|
||||
# Need for tests
|
||||
def save_corrected_animation(self):
|
||||
@@ -350,36 +360,40 @@ class Animation(object):
|
||||
|
||||
try:
|
||||
def execute_frame(frame, frame_id='aruco_map', use_leds=True,
|
||||
flight_func=FlightLib.navto, auto_arm=False, flight_kwargs=None, interrupter=interrupt_event):
|
||||
flight_func=flight.navto, auto_arm=False, flight_kwargs=None, interrupter=interrupt_event):
|
||||
if flight_kwargs is None:
|
||||
flight_kwargs = {}
|
||||
if frame.pose_is_valid():
|
||||
flight_func(x=frame.x, y=frame.y, z=frame.z, yaw=frame.yaw, frame_id=frame_id, auto_arm=auto_arm, interrupter=interrupt_event, **flight_kwargs)
|
||||
else:
|
||||
logger.debug("Frame pose is not valid for flying")
|
||||
logger.error("Frame pose is not valid for flying")
|
||||
if use_leds:
|
||||
if frame.get_color:
|
||||
LedLib.fill(*color)
|
||||
try:
|
||||
red, green, blue = frame.get_color()
|
||||
except ValueError:
|
||||
logger.error("Can't get frame color!")
|
||||
else:
|
||||
led.set_effect(r=red, g=green, b=blue)
|
||||
|
||||
def takeoff(z=1.5, safe_takeoff=True, frame_id='map', timeout=5.0, use_leds=True,
|
||||
interrupter=interrupt_event):
|
||||
if use_leds:
|
||||
LedLib.wipe_to(255, 0, 0, interrupter=interrupter)
|
||||
result = FlightLib.takeoff(height=z, timeout_takeoff=timeout, frame_id=frame_id,
|
||||
led.set_effect(effect='wipe', r=255, g=0, b=0)
|
||||
result = flight.takeoff(height=z, timeout_takeoff=timeout, frame_id=frame_id,
|
||||
emergency_land=safe_takeoff, interrupter=interrupter)
|
||||
if result == 'not armed' or result == 'timeout':
|
||||
if result == 'not armed':
|
||||
raise Exception('STOP') # Raise exception to clear task_manager if copter can't arm
|
||||
if use_leds:
|
||||
LedLib.blink(0, 255, 0, wait=50, interrupter=interrupter)
|
||||
led.set_effect(effect='flash', r=0, g=255, b=0)
|
||||
|
||||
|
||||
def land(z=1.5, descend=False, timeout=5.0, frame_id='aruco_map', use_leds=True,
|
||||
interrupter=interrupt_event):
|
||||
if use_leds:
|
||||
LedLib.blink(255, 0, 0, interrupter=interrupter)
|
||||
FlightLib.land(z=z, descend=descend, timeout_land=timeout, frame_id_land=frame_id, interrupter=interrupter)
|
||||
led.set_effect(effect='blink', r=255, g=0, b=0)
|
||||
flight.land(z=z, descend=descend, timeout_land=timeout, frame_id_land=frame_id, interrupter=interrupter)
|
||||
if use_leds:
|
||||
LedLib.off()
|
||||
led.set_effect(r=0, g=0, b=0)
|
||||
|
||||
except NameError:
|
||||
print("Can't create flying functions")
|
||||
@@ -10,14 +10,14 @@ import selectors2 as selectors
|
||||
|
||||
from contextlib import closing
|
||||
|
||||
import inspect # Add parent dir to PATH to import messaging_lib
|
||||
current_dir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||
parent_dir = os.path.dirname(current_dir)
|
||||
sys.path.insert(0, parent_dir)
|
||||
# Add parent dir to PATH to import messaging_lib and config_lib
|
||||
current_dir = (os.path.dirname(os.path.realpath(__file__)))
|
||||
lib_dir = os.path.realpath(os.path.join(current_dir, '../../lib'))
|
||||
sys.path.insert(0, lib_dir)
|
||||
|
||||
logger = logging.getLogger(__name__)
|
||||
|
||||
import messaging_lib as messaging
|
||||
import messaging
|
||||
from config import ConfigManager
|
||||
|
||||
active_client = None # needs to be refactored: Singleton \ factory callbacks
|
||||
@@ -28,7 +28,7 @@ class Client(object):
|
||||
self.selector = selectors.DefaultSelector()
|
||||
self.client_socket = None
|
||||
|
||||
self.server_connection = messaging.ConnectionManager("pi")
|
||||
self.server_connection = messaging.ConnectionManager()
|
||||
|
||||
self.connected = False
|
||||
self.client_id = None
|
||||
@@ -43,10 +43,10 @@ class Client(object):
|
||||
def load_config(self):
|
||||
self.config.load_config_and_spec(self.config_path)
|
||||
|
||||
config_id = self.config.private_id.lower()
|
||||
config_id = self.config.id.lower()
|
||||
if config_id == '/default':
|
||||
self.client_id = 'copter' + str(random.randrange(9999)).zfill(4)
|
||||
self.config.set('PRIVATE', 'id', self.client_id, write=True) # set and write
|
||||
self.config.set('', 'id', self.client_id, write=True) # set and write
|
||||
elif config_id == '/hostname':
|
||||
self.client_id = socket.gethostname()
|
||||
elif config_id == '/ip':
|
||||
@@ -223,6 +223,10 @@ def _response_config(*args, **kwargs):
|
||||
response.update({"configspec": dict(active_client.config.config.configspec)})
|
||||
return response
|
||||
|
||||
@messaging.request_callback("clover_dir")
|
||||
def _response_clover_dir(*args, **kwargs):
|
||||
return active_client.config.clover_dir
|
||||
|
||||
@messaging.request_callback("id")
|
||||
def _response_id(*args, **kwargs):
|
||||
new_id = kwargs.get("new_id", None)
|
||||
@@ -29,7 +29,7 @@ arming = rospy.ServiceProxy('/mavros/cmd/arming', CommandBool)
|
||||
landing = rospy.ServiceProxy('/land', Trigger)
|
||||
emergency_land = rospy.ServiceProxy('/emergency_land', Trigger)
|
||||
|
||||
services_list = ['/navigate', '/set_position', '/set_rates', '/mavros/set_mode',
|
||||
services_list = ['/navigate', '/set_position', '/set_rates', '/mavros/set_mode',
|
||||
'/get_telemetry', '/mavros/cmd/arming', '/land', '/mavros/param/get']
|
||||
|
||||
logger.info("Proxy services inited")
|
||||
4
drone/modules/led.py
Normal file
@@ -0,0 +1,4 @@
|
||||
import rospy
|
||||
from clover.srv import SetLEDEffect
|
||||
|
||||
set_effect = rospy.ServiceProxy('led/set_effect', SetLEDEffect)
|
||||
@@ -136,7 +136,7 @@ def load_param_file(px4_file):
|
||||
try:
|
||||
px4_params = open(px4_file)
|
||||
except IOError:
|
||||
logger.error("File {} can't be opened".format(filepath))
|
||||
logger.error("File {} can't be opened".format(px4_file))
|
||||
result = False
|
||||
else:
|
||||
with open(px4_file) as px4_params:
|
||||
@@ -2,3 +2,4 @@ selectors2
|
||||
psutil
|
||||
configobj
|
||||
watchdog
|
||||
geographiclib
|
||||
@@ -4,12 +4,15 @@ import shutil
|
||||
from pytest import approx
|
||||
import pytest
|
||||
|
||||
# Add parent dir to PATH to import config
|
||||
import inspect
|
||||
current_dir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||
parent_dir = os.path.dirname(current_dir)
|
||||
sys.path.insert(0, parent_dir)
|
||||
sys.path.insert(0, os.path.join(parent_dir,"Drone"))
|
||||
# Add parent dir to PATH to import messaging_lib and config_lib
|
||||
current_dir = (os.path.dirname(os.path.realpath(__file__)))
|
||||
root_dir = os.path.realpath(os.path.join(current_dir,'../..'))
|
||||
lib_dir = os.path.realpath(os.path.join(root_dir, 'lib'))
|
||||
modules_dir = os.path.realpath(os.path.join(root_dir, 'drone/modules'))
|
||||
sys.path.insert(0, lib_dir)
|
||||
sys.path.insert(0, modules_dir)
|
||||
|
||||
# print("PATH: {}".format(sys.path))
|
||||
|
||||
from config import ConfigManager
|
||||
|
||||
@@ -23,29 +26,32 @@ if not os.path.exists(spec_path):
|
||||
else:
|
||||
print("Successfully created the directory {}".format(spec_path))
|
||||
|
||||
shutil.copy("../Drone/config/spec/configspec_client.ini", spec_path)
|
||||
configspec_path = os.path.realpath(os.path.join(root_dir,"drone/config/spec/configspec_client.ini"))
|
||||
shutil.copy(configspec_path, spec_path)
|
||||
|
||||
config = ConfigManager()
|
||||
config.load_config_and_spec(os.path.join(config_path,'client.ini'))
|
||||
|
||||
assert config.config_name == "client"
|
||||
|
||||
import animation_lib
|
||||
import animation
|
||||
|
||||
a = animation_lib.Animation()
|
||||
a = animation.Animation()
|
||||
|
||||
assets_dir = os.path.realpath(os.path.join(root_dir, 'drone/tests/assets'))
|
||||
|
||||
def test_animation_1():
|
||||
a.update_frames(config, "animation_1.csv")
|
||||
a.update_frames(config, os.path.join(assets_dir, 'animation_1.csv'))
|
||||
assert a.id == 'basic'
|
||||
assert approx(a.original_frames[0].get_pos()) == [0,0,0]
|
||||
assert a.original_frames[0].get_color() == [204,2,0]
|
||||
assert a.original_frames[0].pose_is_valid()
|
||||
assert animation_lib.get_numbers(a.static_begin_frames) == range(1,11)
|
||||
assert animation_lib.get_numbers(a.takeoff_frames) == range(11,21)
|
||||
assert animation_lib.get_numbers(a.route_frames) == range(21,31)
|
||||
assert animation_lib.get_numbers(a.land_frames) == range(31, 41)
|
||||
assert animation_lib.get_numbers(a.static_end_frames) == range(41, 51)
|
||||
assert animation_lib.get_numbers(a.output_frames) == range(11,31)
|
||||
assert animation.get_numbers(a.static_begin_frames) == range(1,11)
|
||||
assert animation.get_numbers(a.takeoff_frames) == range(11,21)
|
||||
assert animation.get_numbers(a.route_frames) == range(21,31)
|
||||
assert animation.get_numbers(a.land_frames) == range(31, 41)
|
||||
assert animation.get_numbers(a.static_end_frames) == range(41, 51)
|
||||
assert animation.get_numbers(a.output_frames) == range(11,31)
|
||||
assert approx(a.static_begin_time) == 1
|
||||
assert approx(a.takeoff_time) == 1
|
||||
assert approx(a.output_frames_min_z) == 0.1
|
||||
@@ -54,17 +60,17 @@ def test_animation_1():
|
||||
assert approx(a.get_start_point(ratio=[1,2,3], offset=[4,5,6])) == [4.,5.,6.3]
|
||||
|
||||
def test_animation_2():
|
||||
a.update_frames(config, "animation_2.csv")
|
||||
a.update_frames(config, os.path.join(assets_dir, 'animation_2.csv'))
|
||||
assert a.id == 'parad'
|
||||
assert approx(a.original_frames[271].get_pos()) == [-1.00519,2.65699,0.24386]
|
||||
assert a.original_frames[271].get_color() == [7,255,0]
|
||||
assert a.original_frames[271].pose_is_valid()
|
||||
assert animation_lib.get_numbers(a.static_begin_frames) == range(271)
|
||||
assert animation_lib.get_numbers(a.takeoff_frames) == range(271,285)
|
||||
assert animation_lib.get_numbers(a.route_frames) == range(285,1065)
|
||||
assert animation_lib.get_numbers(a.land_frames) == []
|
||||
assert animation_lib.get_numbers(a.static_end_frames) == []
|
||||
assert animation_lib.get_numbers(a.output_frames) == range(271, 1065)
|
||||
assert animation.get_numbers(a.static_begin_frames) == range(271)
|
||||
assert animation.get_numbers(a.takeoff_frames) == range(271,285)
|
||||
assert animation.get_numbers(a.route_frames) == range(285,1065)
|
||||
assert animation.get_numbers(a.land_frames) == []
|
||||
assert animation.get_numbers(a.static_end_frames) == []
|
||||
assert animation.get_numbers(a.output_frames) == range(271, 1065)
|
||||
assert approx(a.static_begin_time) == 27.1
|
||||
assert approx(a.takeoff_time) == 1.4
|
||||
assert approx(a.output_frames_min_z) == 0.24386
|
||||
@@ -73,16 +79,16 @@ def test_animation_2():
|
||||
assert approx(a.get_start_point(ratio=[1,2,3], offset=[4,5,6])) == [2.99481, 10.31398, 6.73158]
|
||||
|
||||
def test_animation_3():
|
||||
a.update_frames(config, "animation_3.csv")
|
||||
a.update_frames(config, os.path.join(assets_dir, 'animation_3.csv'))
|
||||
assert a.id == 'route'
|
||||
assert approx(a.original_frames[9].get_pos()) == [0.97783,0.0,1.0]
|
||||
assert a.original_frames[9].get_color() == [0,204,2]
|
||||
assert a.original_frames[9].pose_is_valid()
|
||||
assert animation_lib.get_numbers(a.static_begin_frames) == []
|
||||
assert animation_lib.get_numbers(a.takeoff_frames) == []
|
||||
assert animation_lib.get_numbers(a.route_frames) == range(20,31)
|
||||
assert animation_lib.get_numbers(a.land_frames) == []
|
||||
assert animation_lib.get_numbers(a.static_end_frames) == []
|
||||
assert animation.get_numbers(a.static_begin_frames) == []
|
||||
assert animation.get_numbers(a.takeoff_frames) == []
|
||||
assert animation.get_numbers(a.route_frames) == range(20,31)
|
||||
assert animation.get_numbers(a.land_frames) == []
|
||||
assert animation.get_numbers(a.static_end_frames) == []
|
||||
assert approx(a.static_begin_time) == 0
|
||||
assert approx(a.takeoff_time) == 0
|
||||
assert approx(a.output_frames_min_z) == 1
|
||||
@@ -91,17 +97,17 @@ def test_animation_3():
|
||||
assert approx(a.get_start_point(ratio=[1,2,3], offset=[4,5,6])) == [4,5,9]
|
||||
|
||||
def test_animation_4():
|
||||
a.update_frames(config, "animation_4.csv")
|
||||
a.update_frames(config, os.path.join(assets_dir, 'animation_4.csv'))
|
||||
assert a.id == 'two_drones_test'
|
||||
assert approx(a.original_frames[11].get_pos()) == [0.21774,1.4,1.0]
|
||||
assert a.original_frames[11].get_color() == [0,0,0]
|
||||
assert a.original_frames[11].pose_is_valid()
|
||||
assert animation_lib.get_numbers(a.static_begin_frames) == range(1,12)
|
||||
assert animation_lib.get_numbers(a.takeoff_frames) == []
|
||||
assert animation_lib.get_numbers(a.route_frames) == range(12,141)
|
||||
assert animation_lib.get_numbers(a.land_frames) == []
|
||||
assert animation_lib.get_numbers(a.static_end_frames) == range(141,161)
|
||||
assert animation_lib.get_numbers(a.output_frames) == range(12,141)
|
||||
assert animation.get_numbers(a.static_begin_frames) == range(1,12)
|
||||
assert animation.get_numbers(a.takeoff_frames) == []
|
||||
assert animation.get_numbers(a.route_frames) == range(12,141)
|
||||
assert animation.get_numbers(a.land_frames) == []
|
||||
assert animation.get_numbers(a.static_end_frames) == range(141,161)
|
||||
assert animation.get_numbers(a.output_frames) == range(12,141)
|
||||
assert approx(a.static_begin_time) == 1.1
|
||||
assert approx(a.takeoff_time) == 0
|
||||
assert approx(a.output_frames_min_z) == 1
|
||||
@@ -114,11 +120,11 @@ def test_animation_no_file():
|
||||
assert a.id == None
|
||||
assert a.original_frames == []
|
||||
assert a.output_frames == []
|
||||
assert animation_lib.get_numbers(a.static_begin_frames) == []
|
||||
assert animation_lib.get_numbers(a.takeoff_frames) == []
|
||||
assert animation_lib.get_numbers(a.route_frames) == []
|
||||
assert animation_lib.get_numbers(a.land_frames) == []
|
||||
assert animation_lib.get_numbers(a.static_end_frames) == []
|
||||
assert animation.get_numbers(a.static_begin_frames) == []
|
||||
assert animation.get_numbers(a.takeoff_frames) == []
|
||||
assert animation.get_numbers(a.route_frames) == []
|
||||
assert animation.get_numbers(a.land_frames) == []
|
||||
assert animation.get_numbers(a.static_end_frames) == []
|
||||
assert a.static_begin_time == 0
|
||||
assert a.takeoff_time == 0
|
||||
assert a.output_frames_min_z is None
|
||||
@@ -127,12 +133,12 @@ def test_animation_no_file():
|
||||
assert a.get_start_point(ratio=[1,2,3], offset=[4,5,6]) == []
|
||||
|
||||
|
||||
# print animation_lib.get_numbers(a.static_begin_frames)
|
||||
# print animation_lib.get_numbers(a.takeoff_frames)
|
||||
# print animation_lib.get_numbers(a.route_frames)
|
||||
# print animation_lib.get_numbers(a.land_frames)
|
||||
# print animation_lib.get_numbers(a.static_end_frames)
|
||||
# print animation_lib.get_numbers(a.output_frames)
|
||||
# print animation.get_numbers(a.static_begin_frames)
|
||||
# print animation.get_numbers(a.takeoff_frames)
|
||||
# print animation.get_numbers(a.route_frames)
|
||||
# print animation.get_numbers(a.land_frames)
|
||||
# print animation.get_numbers(a.static_end_frames)
|
||||
# print animation.get_numbers(a.output_frames)
|
||||
# print a.static_begin_time
|
||||
# print a.takeoff_time
|
||||
# print a.output_frames_min_z
|
||||
8
examples/chrony/client.conf
Normal file
@@ -0,0 +1,8 @@
|
||||
pool 127.0.0.1 iburst
|
||||
pool 0.ru.pool.ntp.org iburst minpoll 10
|
||||
pool 1.ru.pool.ntp.org iburst minpoll 10
|
||||
pool 2.ru.pool.ntp.org iburst minpoll 10
|
||||
pool 3.ru.pool.ntp.org iburst minpoll 10
|
||||
driftfile /var/lib/chrony/drift
|
||||
makestep 1.0 -1
|
||||
rtcsync
|
||||
@@ -8,4 +8,3 @@ allow 192.168.0.0/16
|
||||
makestep 1.0 3
|
||||
smoothtime 50000 0.01
|
||||
rtcsync
|
||||
|
||||
113
examples/configurations/gps_sim/client.ini
Normal file
@@ -0,0 +1,113 @@
|
||||
# This is generated config with default values
|
||||
# Modify to configure
|
||||
config_name = client
|
||||
config_version = 1.0
|
||||
|
||||
[SERVER]
|
||||
port = 25000
|
||||
host = 192.168.1.54
|
||||
buffer_size = 1024
|
||||
|
||||
[BROADCAST]
|
||||
use = True
|
||||
port = 8181
|
||||
|
||||
[TELEMETRY]
|
||||
transmit = True
|
||||
frequency = 1.0
|
||||
log_resources = False
|
||||
|
||||
[POSITION WATCHDOG]
|
||||
enabled = True
|
||||
log_state = True
|
||||
# Available options: emergency_land, land, disarm
|
||||
action = emergency_land
|
||||
# Time to get vision position after arm
|
||||
# No visual position will be checked
|
||||
# during this time after arming
|
||||
vision_pose_delay_after_arm = 3.0
|
||||
# Timeout for the last vision pose in /mavros/vision_pose/pose
|
||||
# Set 0 to disable vision pose check
|
||||
vision_pose_timeout = 0.0
|
||||
# Max delta between current position and setpoint
|
||||
# Set 0 to disable position delta check
|
||||
position_delta_max = 3.0
|
||||
# Time to disarm after action is triggered
|
||||
disarm_timeout = 10.0
|
||||
|
||||
[EMERGENCY LAND]
|
||||
thrust = 0.45
|
||||
decrease_thrust_after = 5.0
|
||||
|
||||
[COPTER]
|
||||
frame_id = floor
|
||||
arming_time = 0.5
|
||||
takeoff_height = 3.0
|
||||
takeoff_time = 10.0
|
||||
reach_first_point_time = 10.0
|
||||
land_delay = 1.0
|
||||
land_timeout = 10.0
|
||||
# __list__ x y z
|
||||
common_offset = 0.0, 0.0, 0.0
|
||||
|
||||
[FLOOR FRAME]
|
||||
parent = gps
|
||||
# Frame translation (x, y, z)
|
||||
# __list__ x y z
|
||||
translation = 0.0, 0.0, 5.0
|
||||
# Frame rotation (roll, pitch, yaw) in degrees
|
||||
# __list__ roll pitch yaw
|
||||
rotation = 0.0, 0.0, 0.0
|
||||
|
||||
[GPS FRAME]
|
||||
lat = 55.7032026
|
||||
lon = 37.7248114
|
||||
yaw = 0.0
|
||||
|
||||
[ANIMATION]
|
||||
# Available options:
|
||||
# 'auto' - automatic action selection from 'takeoff' or 'fly' based on current copter level
|
||||
# 'takeoff' - takeoff to first output animation point after static_begin_time then execute 'takeoff logic'
|
||||
# 'fly' - execute animation frames after static_begin_time
|
||||
start_action = auto
|
||||
takeoff_level = 0.5
|
||||
ground_level = -5.0
|
||||
frame_delay = 0.1
|
||||
# Animation ratio (x, y, z)
|
||||
# __list__ x y z
|
||||
ratio = 0.5, 0.5, 0.5
|
||||
# Available options:
|
||||
# 'animation' - take yaw from animation
|
||||
# 'nan' - don't change yaw during flight
|
||||
# or a number in degrees
|
||||
yaw = nan
|
||||
|
||||
[[OUTPUT]]
|
||||
static_begin = False
|
||||
takeoff = True
|
||||
route = True
|
||||
land = False
|
||||
static_end = False
|
||||
|
||||
[LED]
|
||||
use = False
|
||||
pin = 21
|
||||
count = 60
|
||||
takeoff_indication = True
|
||||
land_indication = True
|
||||
|
||||
[PRIVATE]
|
||||
# Available options: /hostname ; /default ; /ip ; any string 63 characters length
|
||||
id = /hostname
|
||||
# Drone's individual offset (x, y, z)
|
||||
# __list__ x y z
|
||||
offset = 0.0, 0.0, 0.0
|
||||
|
||||
[SYSTEM]
|
||||
change_hostname = True
|
||||
restart_after_rename = True
|
||||
|
||||
[NTP]
|
||||
use = False
|
||||
host = ntp1.stratum2.ru
|
||||
port = 123
|
||||
@@ -60,7 +60,10 @@ class ConfigManager:
|
||||
return self.config[section][option]
|
||||
|
||||
def set(self, section, option, value, write=False):
|
||||
self.config[section][option] = value
|
||||
if section:
|
||||
self.config[section][option] = value
|
||||
else:
|
||||
self.config[option] = value
|
||||
if write:
|
||||
self.write()
|
||||
|
||||
@@ -311,15 +314,15 @@ class ConfigManager:
|
||||
|
||||
if __name__ == '__main__':
|
||||
cfg = ConfigManager()
|
||||
cfg.load_from_file('Drone/config/client.ini')
|
||||
# cfg.load_from_file('Server/config/server.ini')
|
||||
#cfg.load_from_file('Drone/config/spec/configspec_client.ini')
|
||||
cfg.load_from_file('drone/config/client.ini')
|
||||
# cfg.load_from_file('server/config/server.ini')
|
||||
#cfg.load_from_file('drone/config/spec/configspec_client.ini')
|
||||
print(dict(cfg.full_dict(include_defaults=True)))
|
||||
cfg.config.pop("PRIVATE", None)
|
||||
print(cfg.config)
|
||||
|
||||
|
||||
# cfg.load_config_and_spec('Drone/config/client.ini')
|
||||
# cfg.load_config_and_spec('drone/config/client.ini')
|
||||
# #print(cfg.config.comments)
|
||||
# #print(cfg.server_host)
|
||||
# cfg.server_host = '192.168.1.103'
|
||||
@@ -338,7 +341,7 @@ if __name__ == '__main__':
|
||||
import pprint
|
||||
#pprint.pprint(cfg.full_dict)
|
||||
# cfg2 = ConfigManager()
|
||||
# #cfg2.load_from_dict({"PRIVATE": {"offset": [1, 2, 3]}}, configspec='Drone/config/spec/configspec_client.ini')
|
||||
# #cfg2.load_from_dict({"PRIVATE": {"offset": [1, 2, 3]}}, configspec='drone/config/spec/configspec_client.ini')
|
||||
# cfg2.load_from_dict({"PRIVATE": {"id": "heh"}})
|
||||
# #pprint.pprint(cfg2.full_dict)
|
||||
# #cfg.merge(cfg2)
|
||||
@@ -350,7 +353,7 @@ if __name__ == '__main__':
|
||||
|
||||
# #print(cfg.full_dict)
|
||||
#
|
||||
# #cfg.load_from_dict(cfg.full_dict, 'Drone/config/client.ini')
|
||||
# #cfg.load_from_dict(cfg.full_dict, 'drone/config/client.ini')
|
||||
# #print(cfg.config.initial_comment, cfg.config.final_comment)
|
||||
# #cfg.write()
|
||||
#
|
||||
27
server/README.md
Normal file
@@ -0,0 +1,27 @@
|
||||
# clever-show server
|
||||
|
||||
Application for creating and running drone shows, adjusting drones, animations and music.
|
||||
|
||||
## Requirements
|
||||
|
||||
* python 3.6+
|
||||
* Time synchronization with connected drones.
|
||||
|
||||
Can be used with built-in NTP server or with external package for time synchronization like `chrony` on Linux systems.
|
||||
|
||||
## Installation
|
||||
|
||||
```cmd
|
||||
pip3 install -r requirements.txt
|
||||
```
|
||||
|
||||
## Usage
|
||||
|
||||
```cmd
|
||||
python3 server.py
|
||||
```
|
||||
|
||||
## Documentation
|
||||
|
||||
* English
|
||||
* [Russian](../docs/ru/server.md)
|
||||
@@ -5,8 +5,28 @@ config_version = float(default='1.0')
|
||||
port = integer(default=25000)
|
||||
buffer_size = integer(default=1024)
|
||||
|
||||
[CLIENT]
|
||||
clever_dir = string(default=/home/pi/catkin_ws/src/clever/clover)
|
||||
[CHECKS]
|
||||
check_git_version = boolean(default=True)
|
||||
check_current_position = boolean(default=True)
|
||||
# in percents; set 0 to disable this check
|
||||
battery_min = float(default=50.0, min=0, max=100)
|
||||
# in meters; set 0 to disable this check
|
||||
start_pos_delta_max = float(default=1.0, min=0)
|
||||
# in seconds
|
||||
time_delta_max = float(default=1.0, min=0)
|
||||
|
||||
[BROADCAST]
|
||||
send = boolean(default=True)
|
||||
listen = boolean(default=True)
|
||||
port = integer(default=8181)
|
||||
send_ip = string(default=255.255.255.255)
|
||||
# delay for message sending in seconds
|
||||
delay = float(default=3.0, min=0)
|
||||
|
||||
[NTP]
|
||||
use = boolean(default=False)
|
||||
host = string(default=ntp1.stratum2.ru)
|
||||
port = integer(default=123)
|
||||
|
||||
[TABLE]
|
||||
# True -> clients are removed on disconnection
|
||||
@@ -30,26 +50,3 @@ config_version = float(default='1.0')
|
||||
time_delta = preset_param(default=list(True, 70))
|
||||
[[[__many__]]]
|
||||
__many__ = preset_param
|
||||
|
||||
[CHECKS]
|
||||
check_git_version = boolean(default=True)
|
||||
check_current_position = boolean(default=True)
|
||||
# in percents; set 0 to disable this check
|
||||
battery_min = float(default=50.0, min=0, max=100)
|
||||
# in meters; set 0 to disable this check
|
||||
start_pos_delta_max = float(default=1.0, min=0)
|
||||
# in seconds
|
||||
time_delta_max = float(default=1.0, min=0)
|
||||
|
||||
[BROADCAST]
|
||||
send = boolean(default=True)
|
||||
listen = boolean(default=True)
|
||||
port = integer(default=8181)
|
||||
send_ip = string(default=255.255.255.255)
|
||||
# delay for message sending in seconds
|
||||
delay = float(default=5.0, min=0)
|
||||
|
||||
[NTP]
|
||||
use = boolean(default=False)
|
||||
host = string(default=ntp1.stratum2.ru)
|
||||
port = integer(default=123)
|
||||
|
Before Width: | Height: | Size: 37 KiB After Width: | Height: | Size: 37 KiB |
|
Before Width: | Height: | Size: 264 KiB After Width: | Height: | Size: 264 KiB |
BIN
server/icons/test.png
Normal file
|
After Width: | Height: | Size: 33 KiB |
0
server/modules/__init__.py
Normal file
@@ -1,3 +1,5 @@
|
||||
import os
|
||||
import sys
|
||||
import pickle
|
||||
import logging
|
||||
from ast import literal_eval
|
||||
@@ -10,14 +12,12 @@ from PyQt5.QtGui import QCursor, QKeySequence
|
||||
from PyQt5.QtWidgets import QAbstractItemView, QTreeView, QMenu, QAction, QMessageBox, QInputDialog, QFileDialog, \
|
||||
QShortcut
|
||||
|
||||
import config_editor
|
||||
import modules.ui.config_editor as config_editor
|
||||
|
||||
import sys
|
||||
import os, inspect # Add parent dir to PATH to import messaging_lib
|
||||
|
||||
current_dir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||
parent_dir = os.path.dirname(current_dir)
|
||||
sys.path.insert(0, parent_dir)
|
||||
# Add parent dir to PATH to import messaging_lib and config_lib
|
||||
current_dir = (os.path.dirname(os.path.realpath(__file__)))
|
||||
lib_dir = os.path.realpath(os.path.join(current_dir, '../../lib'))
|
||||
sys.path.insert(0, lib_dir)
|
||||
|
||||
import config
|
||||
|
||||
@@ -8,8 +8,8 @@ from PyQt5.QtGui import QCursor
|
||||
from PyQt5.QtWidgets import QTableView, QMessageBox, QMenu, QAction, QWidgetAction, QListWidget, \
|
||||
QAbstractItemView, QListWidgetItem, QVBoxLayout, QHBoxLayout, QPushButton, QInputDialog, QLineEdit, QApplication
|
||||
|
||||
from config_editor_models import ConfigDialog
|
||||
import copter_table_models as table
|
||||
from modules.config_editor_models import ConfigDialog
|
||||
import modules.copter_table_models as table
|
||||
|
||||
|
||||
def save_preset(config, current, header_dict):
|
||||
@@ -10,13 +10,13 @@ import selectors
|
||||
import collections
|
||||
import traceback
|
||||
|
||||
import inspect # Add parent dir to PATH to import messaging_lib and config_lib
|
||||
# Add parent dir to PATH to import messaging_lib and config_lib
|
||||
current_dir = (os.path.dirname(os.path.realpath(__file__)))
|
||||
lib_dir = os.path.realpath(os.path.join(current_dir, '../../lib'))
|
||||
sys.path.insert(0, lib_dir)
|
||||
|
||||
current_dir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||
parent_dir = os.path.dirname(current_dir)
|
||||
sys.path.insert(0, parent_dir)
|
||||
|
||||
import messaging_lib as messaging
|
||||
# Import modules from lib dir
|
||||
import messaging
|
||||
from config import ConfigManager
|
||||
|
||||
random.seed()
|
||||
@@ -38,7 +38,7 @@ ConfigOption = collections.namedtuple("ConfigOption", ["section", "option", "val
|
||||
|
||||
|
||||
class Server(messaging.Singleton):
|
||||
def __init__(self, server_id=None, config_path="config/server.ini"):
|
||||
def __init__(self, config_path="../config/server.ini", server_id=None):
|
||||
self.id = server_id if server_id else str(random.randint(0, 9999)).zfill(4)
|
||||
self.time_started = 0
|
||||
|
||||
@@ -286,6 +286,7 @@ class Client(messaging.ConnectionManager):
|
||||
def __init__(self, ip):
|
||||
super().__init__()
|
||||
self.copter_id = None
|
||||
self.clover_dir = None
|
||||
self.connected = False
|
||||
|
||||
self.clients[ip] = self
|
||||
@@ -316,9 +317,15 @@ class Client(messaging.ConnectionManager):
|
||||
old_id = self.copter_id
|
||||
self.copter_id = value
|
||||
|
||||
if old_id is None:
|
||||
self.get_response("clover_dir", self._got_clover_dir)
|
||||
|
||||
if old_id is None and self.on_first_connect:
|
||||
self.on_first_connect(self)
|
||||
|
||||
def _got_clover_dir(self, _client, value):
|
||||
self.clover_dir = value
|
||||
|
||||
def close(self, inner=False):
|
||||
self.connected = False
|
||||
|
||||
0
server/modules/ui/__init__.py
Normal file
@@ -2,7 +2,7 @@ from PyQt5.QtCore import pyqtSlot
|
||||
from PyQt5.QtGui import QKeySequence
|
||||
from PyQt5 import QtWidgets
|
||||
|
||||
import visual_land
|
||||
import modules.ui.visual_land as visual_land
|
||||
import math
|
||||
import logging
|
||||
import sys
|
||||
@@ -8,30 +8,33 @@ import asyncio
|
||||
import platform
|
||||
import itertools
|
||||
import subprocess
|
||||
from functools import partial, wraps
|
||||
|
||||
from functools import partial, wraps
|
||||
from quamash import QEventLoop
|
||||
|
||||
# Import server routines
|
||||
from modules.server_core import Server, Client, now
|
||||
|
||||
# Import modules from lib, that was added to PATH on the previous step
|
||||
import messaging
|
||||
import config as cfg
|
||||
from lib import b_partial
|
||||
|
||||
# Import PyQt5 related functions
|
||||
from PyQt5 import QtWidgets, QtMultimedia, QtCore
|
||||
from PyQt5.QtGui import QPixmap, QIcon
|
||||
from PyQt5.QtCore import Qt, pyqtSlot, QUrl
|
||||
|
||||
from PyQt5.QtWidgets import QFileDialog, QMessageBox, QApplication, QInputDialog, QLineEdit, QStatusBar, \
|
||||
QSplashScreen, QProgressBar
|
||||
from quamash import QEventLoop
|
||||
|
||||
# Importing gui form
|
||||
from server_gui import Ui_MainWindow
|
||||
# Import gui form
|
||||
from modules.ui.server_gui import Ui_MainWindow
|
||||
|
||||
from server import Server, Client, now
|
||||
|
||||
import messaging_lib as messaging
|
||||
import config as cfg
|
||||
|
||||
import copter_table_models as table
|
||||
from copter_table import CopterTableWidget, HeaderEditDialog
|
||||
from visual_land_dialog import VisualLandDialog
|
||||
from config_editor_models import ConfigDialog
|
||||
|
||||
from lib import b_partial
|
||||
# Import gui logic
|
||||
import modules.copter_table_models as table
|
||||
from modules.copter_table import CopterTableWidget, HeaderEditDialog
|
||||
from modules.visual_land_dialog import VisualLandDialog
|
||||
from modules.config_editor_models import ConfigDialog
|
||||
|
||||
startup_cwd = os.getcwd()
|
||||
|
||||
@@ -378,7 +381,7 @@ class MainWindow(QtWidgets.QMainWindow):
|
||||
data = str(value)
|
||||
self.model.update_data(row, col, data, table.ModelDataRole)
|
||||
|
||||
def _send_files(self, files, copters=None, client_path="", client_filename="", match_id=False, callback=None):
|
||||
def _send_files(self, files, copters=None, client_path="", client_filename="", match_id=False, callback=None, clover_dir=False):
|
||||
if copters is None:
|
||||
copters = self.model.user_selected()
|
||||
copters = list(copters)
|
||||
@@ -401,12 +404,19 @@ class MainWindow(QtWidgets.QMainWindow):
|
||||
filename = client_filename.format(num, filename) or filename
|
||||
|
||||
for copter in to_send:
|
||||
copter.client.send_file(file, os.path.join(client_path, filename))
|
||||
if clover_dir:
|
||||
if copter.client.clover_dir != 'error':
|
||||
path_to_send = os.path.realpath(os.path.join(copter.client.clover_dir, client_path))
|
||||
else:
|
||||
logging.error("Can't send files to clover ROS package on {}".format(copter.copter_id))
|
||||
else:
|
||||
path_to_send = client_path
|
||||
copter.client.send_file(file, os.path.join(path_to_send, filename))
|
||||
if callback is not None:
|
||||
callback(copter)
|
||||
|
||||
def send_files(self, prompt, ext_filter, copters=None, client_path="", client_filename="", match_id=False,
|
||||
onefile=False, callback=None):
|
||||
onefile=False, callback=None, clover_dir=False):
|
||||
if onefile:
|
||||
file = QFileDialog.getOpenFileName(self, prompt, filter=ext_filter)[0]
|
||||
files = [file] if file else []
|
||||
@@ -416,10 +426,10 @@ class MainWindow(QtWidgets.QMainWindow):
|
||||
if not files:
|
||||
return
|
||||
|
||||
self._send_files(files, copters, client_path, client_filename, match_id, callback)
|
||||
self._send_files(files, copters, client_path, client_filename, match_id, callback, clover_dir)
|
||||
|
||||
def send_directory_files(self, prompt, extensions=(), copters=None, client_path="", client_filename="",
|
||||
match_id=False, callback=None):
|
||||
match_id=False, callback=None, clover_dir=False):
|
||||
path = QFileDialog.getExistingDirectory(self, prompt)
|
||||
|
||||
if not path:
|
||||
@@ -431,7 +441,7 @@ class MainWindow(QtWidgets.QMainWindow):
|
||||
patterns = [path+'/*.*']
|
||||
|
||||
files = multi_glob(*patterns)
|
||||
self._send_files(files, copters, client_path, client_filename, match_id, callback)
|
||||
self._send_files(files, copters, client_path, client_filename, match_id, callback, clover_dir)
|
||||
|
||||
def request_any_file(self, client_path=None, copters=None):
|
||||
if client_path is None:
|
||||
@@ -485,25 +495,21 @@ class MainWindow(QtWidgets.QMainWindow):
|
||||
@pyqtSlot()
|
||||
def send_calibrations(self):
|
||||
self.send_directory_files("Select directory with calibrations", ('.yaml', ), match_id=True,
|
||||
client_path=os.path.join(self.server.config.client_clever_dir,"camera_info/"),
|
||||
client_filename="calibration.yaml") # TODO callback to reload clever?
|
||||
|
||||
# from os.path import expanduser # TODO on client
|
||||
# home = expanduser("~") -> "~catkin_ws/src/clever/clever/camera_info/"
|
||||
client_path="camera_info", client_filename="calibration.yaml", clover_dir=True)
|
||||
|
||||
@pyqtSlot()
|
||||
def send_aruco(self):
|
||||
def callback(copter):
|
||||
copter.client.send_message("service_restart", kwargs={"name": "clever"})
|
||||
copter.client.send_message("service_restart", kwargs={"name": "clover"})
|
||||
|
||||
self.send_files("Select aruco map configuration file", "Aruco map files (*.txt)", onefile=True,
|
||||
client_path=os.path.abspath(os.path.join(self.server.config.client_clever_dir,"../aruco_pose/map/")),
|
||||
client_filename="animation_map.txt", callback=callback)
|
||||
client_path="../aruco_pose/map/", client_filename="animation_map.txt",
|
||||
callback=callback, clover_dir=True)
|
||||
|
||||
@pyqtSlot()
|
||||
def send_launch(self):
|
||||
self.send_directory_files("Select directory with launch files", ('.launch', '.yaml'), match_id=False,
|
||||
client_path=os.path.join(self.server.config.client_clever_dir,"launch/")) # TODO clever restart callback?
|
||||
client_path="launch", clover_dir=True)
|
||||
|
||||
@pyqtSlot()
|
||||
def send_fcu_parameters(self):
|
||||
@@ -546,7 +552,6 @@ class MainWindow(QtWidgets.QMainWindow):
|
||||
@pyqtSlot()
|
||||
def restart_clever_show(self):
|
||||
for copter in self.model.user_selected():
|
||||
copter.client.send_message("service_restart", kwargs={"name": "visual_pose_watchdog"})
|
||||
copter.client.send_message("service_restart", kwargs={"name": "clever-show"})
|
||||
|
||||
@pyqtSlot()
|
||||
@@ -623,7 +628,7 @@ class MainWindow(QtWidgets.QMainWindow):
|
||||
def save_callback():
|
||||
config.write()
|
||||
|
||||
ConfigDialog().call_config_dialog(config, save_callback, restart, name="Server config")
|
||||
ConfigDialog().call_config_dialog(config, save_callback, restart, name="server config")
|
||||
|
||||
def register_callbacks(self):
|
||||
@messaging.message_callback("telemetry")
|
||||
@@ -683,7 +688,7 @@ if __name__ == "__main__":
|
||||
|
||||
# app.exec_()
|
||||
with loop:
|
||||
server = ServerQt()
|
||||
server = ServerQt(config_path="config/server.ini")
|
||||
window = MainWindow(server)
|
||||
|
||||
Client.on_first_connect = window.new_client_connected
|
||||
@@ -1,7 +1,7 @@
|
||||
import os
|
||||
import shutil
|
||||
import config
|
||||
from Server.copter_table_models import CopterDataModel
|
||||
from server.copter_table_models import CopterDataModel
|
||||
|
||||
from config import ConfigManager, ConfigObj
|
||||
|
||||