Compare commits
48 Commits
vuepress
...
strict-war
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
d715206fbe | ||
|
|
9fc07c9479 | ||
|
|
075779d81f | ||
|
|
fcfa1c2a30 | ||
|
|
7f1d89110b | ||
|
|
2f261c6a20 | ||
|
|
673343f042 | ||
|
|
8d9dc1d122 | ||
|
|
f567ba689c | ||
|
|
cbdc93d1c3 | ||
|
|
c4cd157f7c | ||
|
|
9692c030f1 | ||
|
|
dd01353533 | ||
|
|
afa81e8ee2 | ||
|
|
8cef6be840 | ||
|
|
07cac29937 | ||
|
|
7df4cb2589 | ||
|
|
f1d2f45a9e | ||
|
|
addc600f48 | ||
|
|
608c09f3a5 | ||
|
|
1e68369053 | ||
|
|
80730fd7b3 | ||
|
|
031c8b5305 | ||
|
|
d0ab69df7f | ||
|
|
4562bf3b57 | ||
|
|
00aef350ea | ||
|
|
2796917bd0 | ||
|
|
da3f570225 | ||
|
|
1cb257b6a1 | ||
|
|
16d29fed80 | ||
|
|
2418c259a8 | ||
|
|
38b9b7215d | ||
|
|
f1215347f6 | ||
|
|
b3f46e47ec | ||
|
|
a053d0a3fc | ||
|
|
8838c0b8bf | ||
|
|
2a0f4155ef | ||
|
|
620f10118d | ||
|
|
6762b251c9 | ||
|
|
59d9274c9b | ||
|
|
c145789be1 | ||
|
|
180c892eaa | ||
|
|
da065a79f5 | ||
|
|
d1f0fe5aa9 | ||
|
|
d3eed2cba9 | ||
|
|
6356292c6f | ||
|
|
4cf91dd73d | ||
|
|
88c1b85608 |
2
.github/workflows/docs.yml
vendored
@@ -55,7 +55,7 @@ jobs:
|
||||
- name: Download older PDFs
|
||||
if: ${{ !steps.generate-pdf.outputs.GITBOOK_PDF_OK }}
|
||||
run: |
|
||||
rm _book/clover*.pdf
|
||||
rm -f _book/clover*.pdf
|
||||
wget --no-verbose https://clover.coex.tech/clover_ru.pdf -P _book/
|
||||
wget --no-verbose https://clover.coex.tech/clover_en.pdf -P _book/
|
||||
- name: Deploy
|
||||
|
||||
3
.gitignore
vendored
@@ -7,6 +7,3 @@ package-lock.json
|
||||
clover_blocks/programs/*.*
|
||||
!clover_blocks/programs/examples/*
|
||||
/.vscode/
|
||||
docs/.vuepress/.cache/
|
||||
docs/.vuepress/.temp/
|
||||
docs/.vuepress/dist
|
||||
|
||||
@@ -4,6 +4,8 @@ project(aruco_pose)
|
||||
## Compile as C++11, supported in ROS Kinetic and newer
|
||||
add_compile_options(-std=c++11)
|
||||
|
||||
add_compile_options(-Wall -Wextra -Werror)
|
||||
|
||||
## Find catkin macros and libraries
|
||||
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
|
||||
## is used, also find other catkin packages
|
||||
@@ -83,11 +85,10 @@ add_message_files(
|
||||
)
|
||||
|
||||
## Generate services in the 'srv' folder
|
||||
# add_service_files(
|
||||
# FILES
|
||||
# Service1.srv
|
||||
# Service2.srv
|
||||
# )
|
||||
add_service_files(
|
||||
FILES
|
||||
SetMarkers.srv
|
||||
)
|
||||
|
||||
## Generate actions in the 'action' folder
|
||||
# add_action_files(
|
||||
|
||||
@@ -51,6 +51,7 @@ It's recommended to run it within the same nodelet manager with the camera nodel
|
||||
|
||||
* `image_raw` (*sensor_msgs/Image*) – camera image
|
||||
* `camera_info` (*sensor_msgs/CameraInfo*) – camera calibration info
|
||||
* `map_markers` (*aruco_pose/MarkerArray*) – list of markers to disable TF transform publishing
|
||||
|
||||
#### Published
|
||||
|
||||
@@ -97,6 +98,7 @@ See examples in [`map`](map/) directory.
|
||||
#### Published
|
||||
|
||||
* `~pose` (*geometry_msgs/PoseWithCovarianceStamped*) – estimated map pose
|
||||
* `~map` (*aruco_pose/MarkerArray*) – list of markers in the loaded map
|
||||
* `~image` (*sensor_msgs/Image*) – planarized map image
|
||||
* `~visualization` (*visualization_msgs/MarkerArray*) – markers map visualization for rviz
|
||||
* `~debug` (*sensor_msgs/Image*) – debug image with detected markers and map axis
|
||||
|
||||
@@ -10,6 +10,8 @@ gen = ParameterGenerator()
|
||||
|
||||
gen.add("enabled", bool_t, 0, "if detection enabled", True)
|
||||
|
||||
gen.add("length", double_t, 0, "markers' side length", min=0, max=10)
|
||||
|
||||
gen.add("adaptiveThreshConstant", double_t, 0,
|
||||
"Constant for adaptive thresholding before finding contours",
|
||||
p.adaptiveThreshConstant, 0, 100)
|
||||
|
||||
@@ -1,3 +1,4 @@
|
||||
# id length x y z rot_z rot_y rot_x
|
||||
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
|
||||
|
||||
@@ -1,3 +1,4 @@
|
||||
# id length x y z rot_z rot_y rot_x
|
||||
107 0.33 0 0 0 0 0 0
|
||||
106 0.33 0.77 0 0 0 0 0
|
||||
105 0.33 0 0.77 0 0 0 0
|
||||
|
||||
@@ -1,3 +1,4 @@
|
||||
# id length x y z rot_z rot_y rot_x
|
||||
14 0.365 0.000 0.0 0 0 0 0
|
||||
15 0.365 1.335 0.0 0 0 0 0
|
||||
30 0.365 2.865 0.0 0 0 0 0
|
||||
|
||||
@@ -48,6 +48,7 @@
|
||||
#include <aruco_pose/Marker.h>
|
||||
#include <aruco_pose/MarkerArray.h>
|
||||
#include <aruco_pose/DetectorConfig.h>
|
||||
#include <aruco_pose/SetMarkers.h>
|
||||
|
||||
#include "utils.h"
|
||||
#include <memory>
|
||||
@@ -69,8 +70,10 @@ private:
|
||||
image_transport::CameraSubscriber img_sub_;
|
||||
ros::Publisher markers_pub_, vis_markers_pub_;
|
||||
ros::Subscriber map_markers_sub_;
|
||||
ros::ServiceServer set_markers_srv_;
|
||||
bool estimate_poses_, send_tf_, auto_flip_;
|
||||
double length_;
|
||||
ros::Duration transform_timeout_;
|
||||
std::unordered_map<int, double> length_override_;
|
||||
std::string frame_id_prefix_, known_tilt_;
|
||||
Mat camera_matrix_, dist_coeffs_;
|
||||
@@ -97,6 +100,7 @@ public:
|
||||
ros::shutdown();
|
||||
}
|
||||
readLengthOverride(nh_priv_);
|
||||
transform_timeout_ = ros::Duration(nh_priv_.param("transform_timeout", 0.02));
|
||||
|
||||
known_tilt_ = nh_priv_.param<std::string>("known_tilt", "");
|
||||
auto_flip_ = nh_priv_.param("auto_flip", false);
|
||||
@@ -114,6 +118,8 @@ public:
|
||||
dyn_srv_ = std::make_shared<dynamic_reconfigure::Server<aruco_pose::DetectorConfig>>(nh_priv_);
|
||||
dyn_srv_->setCallback(std::bind(&ArucoDetect::paramCallback, this, std::placeholders::_1, std::placeholders::_2));
|
||||
|
||||
set_markers_srv_ = nh_priv_.advertiseService("set_length_override", &ArucoDetect::setMarkers, this);
|
||||
|
||||
debug_pub_ = it_priv.advertise("debug", 1);
|
||||
markers_pub_ = nh_priv_.advertise<aruco_pose::MarkerArray>("markers", 1);
|
||||
vis_markers_pub_ = nh_priv_.advertise<visualization_msgs::MarkerArray>("visualization", 1);
|
||||
@@ -172,7 +178,7 @@ private:
|
||||
if (!known_tilt_.empty()) {
|
||||
try {
|
||||
snap_to = tf_buffer_->lookupTransform(msg->header.frame_id, known_tilt_,
|
||||
msg->header.stamp, ros::Duration(0.02));
|
||||
msg->header.stamp, transform_timeout_);
|
||||
} catch (const tf2::TransformException& e) {
|
||||
NODELET_WARN_THROTTLE(5, "can't snap: %s", e.what());
|
||||
}
|
||||
@@ -346,6 +352,29 @@ private:
|
||||
}
|
||||
}
|
||||
|
||||
bool setMarkers(aruco_pose::SetMarkers::Request& req, aruco_pose::SetMarkers::Response& res)
|
||||
{
|
||||
for (auto const& marker : req.markers) {
|
||||
if (marker.id > 999) {
|
||||
res.message = "Invalid marker id: " + std::to_string(marker.id);
|
||||
ROS_ERROR("%s", res.message.c_str());
|
||||
return true;
|
||||
}
|
||||
if (!std::isfinite(marker.length) || marker.length <= 0) {
|
||||
res.message = "Invalid marker " + std::to_string(marker.id) + " length: " + std::to_string(marker.length);
|
||||
ROS_ERROR("%s", res.message.c_str());
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
for (auto const& marker : req.markers) {
|
||||
length_override_[marker.id] = marker.length;
|
||||
}
|
||||
|
||||
res.success = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
void mapMarkersCallback(const aruco_pose::MarkerArray& msg)
|
||||
{
|
||||
map_markers_ids_.clear();
|
||||
@@ -356,7 +385,8 @@ private:
|
||||
|
||||
void paramCallback(aruco_pose::DetectorConfig &config, uint32_t level)
|
||||
{
|
||||
enabled_ = config.enabled;
|
||||
enabled_ = config.enabled && config.length > 0;
|
||||
length_ = config.length;
|
||||
parameters_->adaptiveThreshConstant = config.adaptiveThreshConstant;
|
||||
parameters_->adaptiveThreshWinSizeMin = config.adaptiveThreshWinSizeMin;
|
||||
parameters_->adaptiveThreshWinSizeMax = config.adaptiveThreshWinSizeMax;
|
||||
|
||||
@@ -89,7 +89,7 @@ public:
|
||||
|
||||
// TODO: why image_transport doesn't work here?
|
||||
img_pub_ = nh_priv_.advertise<sensor_msgs::Image>("image", 1, true);
|
||||
markers_pub_ = nh_priv_.advertise<aruco_pose::MarkerArray>("markers", 1, true);
|
||||
markers_pub_ = nh_priv_.advertise<aruco_pose::MarkerArray>("map", 1, true);
|
||||
|
||||
board_ = cv::makePtr<cv::aruco::Board>();
|
||||
board_->dictionary = cv::aruco::getPredefinedDictionary(
|
||||
|
||||
7
aruco_pose/srv/SetMarkers.srv
Normal file
@@ -0,0 +1,7 @@
|
||||
# * Add or change markers in the map
|
||||
# * Change markers' properties, e. g. lengths
|
||||
|
||||
Marker[] markers # if length or pose is nan - remove from map
|
||||
---
|
||||
bool success
|
||||
string message
|
||||
@@ -143,7 +143,7 @@ def test_map_image(node):
|
||||
assert img.encoding in ('mono8', 'rgb8')
|
||||
|
||||
def test_map_markers(node):
|
||||
markers = rospy.wait_for_message('aruco_map/markers', MarkerArray, timeout=5)
|
||||
markers = rospy.wait_for_message('aruco_map/map', MarkerArray, timeout=5)
|
||||
assert markers.markers[0].id == 1
|
||||
assert markers.markers[1].id == 2
|
||||
assert markers.markers[2].id == 3
|
||||
|
||||
@@ -4,6 +4,8 @@ project(clover)
|
||||
## Compile as C++11, supported in ROS Kinetic and newer
|
||||
add_compile_options(-std=c++11)
|
||||
|
||||
add_compile_options(-Wall -Wextra -Werror)
|
||||
|
||||
## Find catkin macros and libraries
|
||||
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
|
||||
## is used, also find other catkin packages
|
||||
@@ -24,6 +26,7 @@ find_package(catkin REQUIRED COMPONENTS
|
||||
tf2_ros
|
||||
image_transport
|
||||
cv_bridge
|
||||
dynamic_reconfigure
|
||||
)
|
||||
|
||||
list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}/cmake")
|
||||
@@ -126,10 +129,9 @@ generate_messages(
|
||||
## and list every .cfg file to be processed
|
||||
|
||||
## Generate dynamic reconfigure parameters in the 'cfg' folder
|
||||
# generate_dynamic_reconfigure_options(
|
||||
# cfg/DynReconf1.cfg
|
||||
# cfg/DynReconf2.cfg
|
||||
# )
|
||||
generate_dynamic_reconfigure_options(
|
||||
cfg/Flow.cfg
|
||||
)
|
||||
|
||||
###################################
|
||||
## catkin specific configuration ##
|
||||
@@ -211,6 +213,8 @@ add_dependencies(clover_led ${PROJECT_NAME}_generate_messages_cpp)
|
||||
|
||||
add_dependencies(shell ${PROJECT_NAME}_generate_messages_cpp)
|
||||
|
||||
add_dependencies(${PROJECT_NAME} ${PROJECT_NAME}_gencfg)
|
||||
|
||||
## Rename C++ executable without prefix
|
||||
## The above recommended prefix causes long target names, the following renames the
|
||||
## target back to the shorter version for ease of user use
|
||||
|
||||
10
clover/cfg/Flow.cfg
Normal file
@@ -0,0 +1,10 @@
|
||||
#!/usr/bin/env python
|
||||
PACKAGE = "clover"
|
||||
|
||||
from dynamic_reconfigure.parameter_generator_catkin import *
|
||||
|
||||
gen = ParameterGenerator()
|
||||
|
||||
gen.add("enabled", bool_t, 0, "if optical flow enabled", True)
|
||||
|
||||
exit(gen.generate(PACKAGE, "clover", "Flow"))
|
||||
@@ -15,12 +15,13 @@
|
||||
<node name="aruco_detect" pkg="nodelet" if="$(eval aruco_detect and not disable)" type="nodelet" args="load aruco_pose/aruco_detect main_camera_nodelet_manager" output="screen" clear_params="true" respawn="true">
|
||||
<remap from="image_raw" to="main_camera/image_raw"/>
|
||||
<remap from="camera_info" to="main_camera/camera_info"/>
|
||||
<remap from="map_markers" to="aruco_map/markers"/>
|
||||
<remap from="map_markers" to="aruco_map/map"/>
|
||||
<param name="estimate_poses" value="true"/>
|
||||
<param name="send_tf" value="true"/>
|
||||
<param name="known_tilt" value="map" if="$(eval placement == 'floor')"/>
|
||||
<param name="known_tilt" value="map_flipped" if="$(eval placement == 'ceiling')"/>
|
||||
<param name="length" value="$(arg length)"/>
|
||||
<param name="transform_timeout" value="0.1"/>
|
||||
<!-- aruco detector parameters -->
|
||||
<param name="cornerRefinementMethod" value="2"/> <!-- contour refinement -->
|
||||
<param name="minMarkerPerimeterRate" value="0.075"/> <!-- 0.075 for 320x240, 0.0375 for 640x480 -->
|
||||
|
||||
@@ -39,6 +39,7 @@
|
||||
<depend>tf2_web_republisher</depend>
|
||||
<depend condition="$ROS_PYTHON_VERSION == 2">python-lxml</depend>
|
||||
<depend condition="$ROS_PYTHON_VERSION == 3">python3-lxml</depend>
|
||||
<depend>dynamic_reconfigure</depend>
|
||||
<exec_depend>python-pymavlink</exec_depend>
|
||||
<!-- Use test_depend for packages you need only for testing: -->
|
||||
<!-- <test_depend>gtest</test_depend> -->
|
||||
|
||||
87
clover/src/autotest/autotest_aruco.py
Executable file
@@ -0,0 +1,87 @@
|
||||
#!/usr/bin/env python3
|
||||
|
||||
import rospy
|
||||
import math
|
||||
import signal
|
||||
import sys
|
||||
import dynamic_reconfigure.client
|
||||
from clover import srv
|
||||
from std_srvs.srv import Trigger
|
||||
from sensor_msgs.msg import Range
|
||||
from aruco_pose.msg import MarkerArray
|
||||
from util import handle_response
|
||||
|
||||
rospy.init_node('autotest_aruco', disable_signals=True) # disable signals to allow interrupting with ctrl+c
|
||||
|
||||
flow_client = dynamic_reconfigure.client.Client('optical_flow')
|
||||
get_telemetry = rospy.ServiceProxy('get_telemetry', srv.GetTelemetry)
|
||||
navigate = handle_response(rospy.ServiceProxy('navigate', srv.Navigate))
|
||||
land = handle_response(rospy.ServiceProxy('land', Trigger))
|
||||
|
||||
def interrupt(sig, frame):
|
||||
print('\nInterrupted, landing...')
|
||||
land()
|
||||
sys.exit(0)
|
||||
|
||||
signal.signal(signal.SIGINT, interrupt)
|
||||
|
||||
def print_current_map_position():
|
||||
telem = get_telemetry()
|
||||
dist = rospy.wait_for_message('rangefinder/range', Range).range
|
||||
print('Map position:\tx={:.1f}\ty={:.1f}\tz={:.1f}\tyaw={:.1f}\tdist={:.2f}'.format(telem.x, telem.y, telem.z, telem.yaw, dist))
|
||||
|
||||
def navigate_wait(x=0, y=0, z=0, yaw=float('nan'), yaw_rate=0, speed=0.5, \
|
||||
frame_id='body', tolerance=0.2, auto_arm=False):
|
||||
|
||||
res = navigate(x=x, y=y, z=z, yaw=yaw, yaw_rate=yaw_rate, speed=speed, \
|
||||
frame_id=frame_id, auto_arm=auto_arm)
|
||||
|
||||
if not res.success:
|
||||
return res
|
||||
|
||||
while not rospy.is_shutdown():
|
||||
telem = get_telemetry(frame_id='navigate_target')
|
||||
if math.sqrt(telem.x ** 2 + telem.y ** 2 + telem.z ** 2) < tolerance:
|
||||
return res
|
||||
rospy.sleep(0.2)
|
||||
|
||||
markers = rospy.wait_for_message('aruco_map/map', MarkerArray, timeout=3)
|
||||
left = min(marker.pose.position.x for marker in markers.markers)
|
||||
bottom = min(marker.pose.position.y for marker in markers.markers)
|
||||
width = max(marker.pose.position.x for marker in markers.markers)
|
||||
height = max(marker.pose.position.y for marker in markers.markers)
|
||||
center_x = left + width / 2
|
||||
center_y = bottom + height / 2
|
||||
|
||||
print('Map rect: %g %g - %g %g' % (left, bottom, width, height))
|
||||
|
||||
input('Take off and hover 1 m [enter] ')
|
||||
navigate_wait(x=0, y=0, z=1, frame_id='body', auto_arm=True)
|
||||
print_current_map_position()
|
||||
|
||||
input('Go to corner %g %g 1.5 speed 1 [enter] ' % (width, height))
|
||||
navigate_wait(x=width, y=height, z=1.5, speed=1, frame_id='aruco_map')
|
||||
print_current_map_position()
|
||||
|
||||
input('Go to center %g %g 1.5 speed 5 [enter] ' % (center_x, center_y))
|
||||
navigate_wait(x=center_x, y=center_y, z=1.5, speed=5, frame_id='aruco_map')
|
||||
print_current_map_position()
|
||||
|
||||
input('Disable optical flow and keep hovering [enter] ')
|
||||
flow_client.update_configuration({'enabled': False})
|
||||
rospy.sleep(5)
|
||||
|
||||
input('Enable optical flow back [enter] ')
|
||||
flow_client.update_configuration({'enabled': True})
|
||||
|
||||
input('Go to side 1 %g 2 heading top [enter] ' % (center_y))
|
||||
navigate_wait(x=1, y=center_y, z=2, yaw=1.57, frame_id='aruco_map')
|
||||
print_current_map_position()
|
||||
|
||||
marker_id = markers.markers[0].id
|
||||
input('Go to marker %d z=1.5 [enter] ' % marker_id)
|
||||
navigate_wait(x=0, y=0, z=1.5, yaw=0, frame_id='aruco_%d' % marker_id)
|
||||
print_current_map_position()
|
||||
|
||||
input('Perform landing [enter] ')
|
||||
land()
|
||||
100
clover/src/autotest/autotest_flight.py
Executable file
@@ -0,0 +1,100 @@
|
||||
#!/usr/bin/env python3
|
||||
|
||||
import rospy
|
||||
import math
|
||||
from math import nan
|
||||
import signal
|
||||
import sys
|
||||
from clover import srv
|
||||
from std_srvs.srv import Trigger
|
||||
from sensor_msgs.msg import Range
|
||||
from util import handle_response
|
||||
|
||||
rospy.init_node('autotest_flight', disable_signals=True) # disable signals to allow interrupting with ctrl+c
|
||||
|
||||
get_telemetry = rospy.ServiceProxy('get_telemetry', srv.GetTelemetry)
|
||||
navigate = handle_response(rospy.ServiceProxy('navigate', srv.Navigate))
|
||||
navigate_global = handle_response(rospy.ServiceProxy('navigate_global', srv.NavigateGlobal))
|
||||
set_position = handle_response(rospy.ServiceProxy('set_position', srv.SetPosition))
|
||||
set_velocity = handle_response(rospy.ServiceProxy('set_velocity', srv.SetVelocity))
|
||||
set_attitude = handle_response(rospy.ServiceProxy('set_attitude', srv.SetAttitude))
|
||||
set_rates = handle_response(rospy.ServiceProxy('set_rates', srv.SetRates))
|
||||
land = handle_response(rospy.ServiceProxy('land', Trigger))
|
||||
|
||||
def interrupt(sig, frame):
|
||||
print('\nInterrupted, landing...')
|
||||
land()
|
||||
sys.exit(0)
|
||||
|
||||
signal.signal(signal.SIGINT, interrupt)
|
||||
|
||||
def navigate_wait(x=0, y=0, z=0, yaw=nan, yaw_rate=0, speed=0.5, \
|
||||
frame_id='body', tolerance=0.2, auto_arm=False):
|
||||
|
||||
res = navigate(x=x, y=y, z=z, yaw=yaw, yaw_rate=yaw_rate, speed=speed, \
|
||||
frame_id=frame_id, auto_arm=auto_arm)
|
||||
|
||||
if not res.success:
|
||||
return res
|
||||
|
||||
while not rospy.is_shutdown():
|
||||
telem = get_telemetry(frame_id='navigate_target')
|
||||
if math.sqrt(telem.x ** 2 + telem.y ** 2 + telem.z ** 2) < tolerance:
|
||||
return res
|
||||
rospy.sleep(0.2)
|
||||
|
||||
def print_distance():
|
||||
dist = rospy.wait_for_message('rangefinder/range', Range).range
|
||||
print('Distance: {:.2f}'.format(dist))
|
||||
|
||||
input('Take off and hover 1 m [enter] ')
|
||||
navigate_wait(z=1, frame_id='body', auto_arm=True)
|
||||
print_distance()
|
||||
start = get_telemetry()
|
||||
|
||||
input('Fly forward 2 m [enter] ')
|
||||
navigate_wait(x=2, frame_id='navigate_target')
|
||||
print_distance()
|
||||
|
||||
input('Climb 0.5 m [enter] ')
|
||||
navigate_wait(z=0.5, frame_id='navigate_target')
|
||||
print_distance()
|
||||
|
||||
input('Rotate left 90° [enter] ')
|
||||
navigate(yaw=math.pi / 2, frame_id='navigate_target')
|
||||
rospy.sleep(3)
|
||||
|
||||
input('Use set_velocity to fly forward 2 m speed 1 [enter]')
|
||||
set_velocity(vx=1, vy=0.0, vz=0, frame_id='body')
|
||||
rospy.sleep(2)
|
||||
set_position(frame_id='body')
|
||||
|
||||
input('Rotate right 90° [enter] ')
|
||||
navigate(yaw=-math.pi / 2, frame_id='navigate_target')
|
||||
rospy.sleep(3)
|
||||
|
||||
input('Use set_attitude to fly backwards [enter]')
|
||||
set_attitude(pitch=-0.3, roll=0, yaw=0, thrust=0.5, frame_id='body')
|
||||
rospy.sleep(0.3)
|
||||
set_position(frame_id='body')
|
||||
|
||||
input('Use set_attitude to fly right [enter]')
|
||||
set_attitude(pitch=0, roll=0.3, yaw=0, thrust=0.5, frame_id='body')
|
||||
rospy.sleep(0.5)
|
||||
set_position(frame_id='body')
|
||||
|
||||
input('Use set_rates to fly right [enter]')
|
||||
set_rates(roll_rate=1.2, thrust=0.5)
|
||||
rospy.sleep(0.4)
|
||||
set_position(frame_id='body')
|
||||
|
||||
input('Rotate 360° to the right using yaw_rate [enter]')
|
||||
set_position(x=nan, y=nan, z=nan, frame_id='body', yaw=nan, yaw_rate=-1)
|
||||
rospy.sleep(2 * math.pi)
|
||||
set_position(frame_id='body')
|
||||
|
||||
input('Return to start point [enter]')
|
||||
navigate_wait(x=start.x, y=start.y, z=start.z, yaw=start.yaw, speed=1, frame_id='map')
|
||||
|
||||
input('Land [enter]')
|
||||
land()
|
||||
72
clover/src/autotest/autotest_led.py
Executable file
@@ -0,0 +1,72 @@
|
||||
#!/usr/bin/env python3
|
||||
|
||||
import rospy
|
||||
import functools
|
||||
from clover.srv import SetLEDEffect
|
||||
from led_msgs.srv import SetLEDs
|
||||
from led_msgs.msg import LEDStateArray, LEDState
|
||||
from util import handle_response
|
||||
|
||||
rospy.init_node('autotest_led', disable_signals=True)
|
||||
|
||||
set_leds = handle_response(rospy.ServiceProxy('led/set_leds', SetLEDs))
|
||||
set_effect = handle_response(rospy.ServiceProxy('led/set_effect', SetLEDEffect))
|
||||
|
||||
led_count = len(rospy.wait_for_message('led/state', LEDStateArray, timeout=10).leds)
|
||||
print('LED count =', led_count)
|
||||
|
||||
print('== Testing effects ==')
|
||||
|
||||
input('Fill red [enter] ')
|
||||
set_effect(r=255, g=0, b=0)
|
||||
|
||||
input('Fill green [enter] ')
|
||||
set_effect(r=0, g=100, b=0)
|
||||
|
||||
input('Blink white [enter] ')
|
||||
set_effect(effect='blink', r=255, g=255, b=255)
|
||||
rospy.sleep(3)
|
||||
|
||||
input('Blink fast violet [enter] ')
|
||||
set_effect(effect='blink_fast', r=220, g=20, b=250)
|
||||
rospy.sleep(3)
|
||||
|
||||
input('Fade to blue [enter] ')
|
||||
set_effect(effect='fade', r=0, g=0, b=255)
|
||||
|
||||
input('Wipe to yellow [enter] ')
|
||||
set_effect(effect='wipe', r=255, g=255, b=40)
|
||||
|
||||
input('Flash red [enter] ')
|
||||
set_effect(effect='flash', r=255, g=0, b=0)
|
||||
rospy.sleep(1)
|
||||
|
||||
input('Rainbow [enter] ')
|
||||
set_effect(effect='rainbow')
|
||||
rospy.sleep(4)
|
||||
|
||||
input('Rainbow fill [enter] ')
|
||||
set_effect(effect='rainbow_fill')
|
||||
rospy.sleep(4)
|
||||
|
||||
input('Turn off [enter] ')
|
||||
set_effect()
|
||||
|
||||
print('== Testing low-level control ==')
|
||||
|
||||
input('Fill orange [enter] ')
|
||||
set_leds(leds=[LEDState(index=i, r=245, g=155, b=0) for i in range(led_count)])
|
||||
|
||||
input('Fill blue gradient [enter] ')
|
||||
set_leds(leds=[LEDState(index=i, r=0, g=20, b=int(255 * i / led_count)) for i in range(led_count)])
|
||||
|
||||
input('Animate green dot [enter] ')
|
||||
set_effect()
|
||||
for i in range(led_count):
|
||||
if i > 0:
|
||||
set_leds(leds=[LEDState(index=i - 1, r=0, g=0, b=0)])
|
||||
set_leds(leds=[LEDState(index=i, r=0, g=255, b=0)])
|
||||
rospy.sleep(0.05)
|
||||
|
||||
input('Turn off [enter] ')
|
||||
set_effect()
|
||||
11
clover/src/autotest/util.py
Normal file
@@ -0,0 +1,11 @@
|
||||
import functools
|
||||
|
||||
# decorator to handle response and print error message
|
||||
def handle_response(fn):
|
||||
@functools.wraps(fn)
|
||||
def wrapper(*args, **kwargs):
|
||||
res = fn(*args, **kwargs)
|
||||
if not res.success:
|
||||
print('\033[91mError:\033[0m {}'.format(res.message))
|
||||
return res
|
||||
return wrapper
|
||||
@@ -22,11 +22,13 @@
|
||||
#include <tf2/utils.h>
|
||||
#include <tf2_ros/transform_listener.h>
|
||||
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
|
||||
#include <dynamic_reconfigure/server.h>
|
||||
#include <mavros_msgs/OpticalFlowRad.h>
|
||||
#include <sensor_msgs/Imu.h>
|
||||
#include <geometry_msgs/Vector3Stamped.h>
|
||||
#include <geometry_msgs/PointStamped.h>
|
||||
#include <geometry_msgs/TwistStamped.h>
|
||||
#include <clover/FlowConfig.h>
|
||||
|
||||
using cv::Mat;
|
||||
|
||||
@@ -38,6 +40,7 @@ public:
|
||||
{}
|
||||
|
||||
private:
|
||||
bool enabled_;
|
||||
ros::Publisher flow_pub_, velo_pub_, shift_pub_;
|
||||
ros::Time prev_stamp_;
|
||||
std::string fcu_frame_id_, local_frame_id_;
|
||||
@@ -54,6 +57,7 @@ private:
|
||||
std::unique_ptr<tf2_ros::TransformListener> tf_listener_;
|
||||
bool calc_flow_gyro_;
|
||||
float flow_gyro_default_;
|
||||
std::shared_ptr<dynamic_reconfigure::Server<clover::FlowConfig>> dyn_srv_;
|
||||
|
||||
void onInit()
|
||||
{
|
||||
@@ -83,6 +87,12 @@ private:
|
||||
|
||||
img_sub_ = it.subscribeCamera("image_raw", 1, &OpticalFlow::flow, this);
|
||||
|
||||
dyn_srv_ = std::make_shared<dynamic_reconfigure::Server<clover::FlowConfig>>(nh_priv);
|
||||
dynamic_reconfigure::Server<clover::FlowConfig>::CallbackType cb;
|
||||
|
||||
cb = std::bind(&OpticalFlow::paramCallback, this, std::placeholders::_1, std::placeholders::_2);
|
||||
dyn_srv_->setCallback(cb);
|
||||
|
||||
NODELET_INFO("Optical Flow initialized");
|
||||
}
|
||||
|
||||
@@ -109,6 +119,8 @@ private:
|
||||
|
||||
void flow(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cinfo)
|
||||
{
|
||||
if (!enabled_) return;
|
||||
|
||||
parseCameraInfo(cinfo);
|
||||
|
||||
auto img = cv_bridge::toCvShare(msg, "mono8")->image;
|
||||
@@ -224,7 +236,6 @@ private:
|
||||
prev_ = curr_.clone();
|
||||
prev_stamp_ = msg->header.stamp;
|
||||
|
||||
publish_debug:
|
||||
// Publish debug image
|
||||
if (img_pub_.getNumSubscribers() > 0) {
|
||||
// publish debug image
|
||||
@@ -264,6 +275,14 @@ publish_debug:
|
||||
|
||||
return flow;
|
||||
}
|
||||
|
||||
void paramCallback(clover::FlowConfig &config, [[maybe_unused]] uint32_t level)
|
||||
{
|
||||
enabled_ = config.enabled;
|
||||
if (!enabled_) {
|
||||
prev_ = Mat(); // clear previous frame
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
PLUGINLIB_EXPORT_CLASS(OpticalFlow, nodelet::Nodelet)
|
||||
|
||||
@@ -503,10 +503,10 @@ inline void checkManualControl()
|
||||
|
||||
if (check_kill_switch) {
|
||||
// switch values: https://github.com/PX4/PX4-Autopilot/blob/c302514a0809b1765fafd13c014d705446ae1113/msg/manual_control_setpoint.msg#L3
|
||||
const uint8_t SWITCH_POS_NONE = 0; // switch is not mapped
|
||||
const uint8_t SWITCH_POS_ON = 1; // switch activated
|
||||
const uint8_t SWITCH_POS_MIDDLE = 2; // middle position
|
||||
const uint8_t SWITCH_POS_OFF = 3; // switch not activated
|
||||
[[maybe_unused]] const uint8_t SWITCH_POS_NONE = 0; // switch is not mapped
|
||||
[[maybe_unused]] const uint8_t SWITCH_POS_ON = 1; // switch activated
|
||||
[[maybe_unused]] const uint8_t SWITCH_POS_MIDDLE = 2; // middle position
|
||||
[[maybe_unused]] const uint8_t SWITCH_POS_OFF = 3; // switch not activated
|
||||
|
||||
const int KILL_SWITCH_BIT = 12; // https://github.com/PX4/Firmware/blob/c302514a0809b1765fafd13c014d705446ae1113/src/modules/mavlink/mavlink_messages.cpp#L3975
|
||||
uint8_t kill_switch = (manual_control.buttons & (0b11 << KILL_SWITCH_BIT)) >> KILL_SWITCH_BIT;
|
||||
@@ -691,7 +691,7 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
|
||||
// }
|
||||
|
||||
if (sp_type == POSITION || sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL || sp_type == VELOCITY || sp_type == ATTITUDE) {
|
||||
// destination point and/or yaw
|
||||
// destination point and/or attitude
|
||||
PoseStamped ps;
|
||||
ps.header.frame_id = frame_id;
|
||||
ps.header.stamp = stamp;
|
||||
@@ -700,7 +700,12 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
|
||||
ps.pose.position.z = z;
|
||||
ps.pose.orientation.w = 1.0; // Ensure quaternion is always valid
|
||||
|
||||
if (std::isnan(yaw)) {
|
||||
if (sp_type == ATTITUDE) {
|
||||
ps.pose.position.x = 0;
|
||||
ps.pose.position.y = 0;
|
||||
ps.pose.position.z = 0;
|
||||
ps.pose.orientation = tf::createQuaternionMsgFromRollPitchYaw(roll, pitch, yaw);
|
||||
} else if (std::isnan(yaw)) {
|
||||
setpoint_yaw_type = YAW_RATE;
|
||||
setpoint_yaw_rate = yaw_rate;
|
||||
} else if (std::isinf(yaw) && yaw > 0) {
|
||||
@@ -803,7 +808,7 @@ bool setRates(SetRates::Request& req, SetRates::Response& res) {
|
||||
return serve(RATES, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, req.pitch_rate, req.roll_rate, req.yaw_rate, NAN, NAN, req.thrust, NAN, "", req.auto_arm, res.success, res.message);
|
||||
}
|
||||
|
||||
bool land(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
|
||||
bool land([[maybe_unused]] std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
|
||||
{
|
||||
try {
|
||||
if (busy)
|
||||
|
||||
@@ -38,9 +38,9 @@ TransformStamped offset;
|
||||
|
||||
void publishZero(const ros::TimerEvent& e)
|
||||
{
|
||||
if (e.current_real - vpe.header.stamp < publish_zero_timout) return; // have vpe
|
||||
if (!vpe.header.stamp.isZero() && e.current_real - vpe.header.stamp < publish_zero_timout) return; // have vpe
|
||||
|
||||
if (e.current_real - pose.header.stamp < publish_zero_timout) { // have local position
|
||||
if (!pose.header.stamp.isZero() && e.current_real - pose.header.stamp < publish_zero_timout) { // have local position
|
||||
if (got_local_pos.isZero()) {
|
||||
ROS_INFO("got local position");
|
||||
got_local_pos = e.current_real;
|
||||
@@ -109,7 +109,7 @@ void callback(const T& msg)
|
||||
}
|
||||
}
|
||||
|
||||
bool reset(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
|
||||
bool reset([[maybe_unused]] std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
|
||||
{
|
||||
reset_flag = true;
|
||||
res.success = true;
|
||||
|
||||
@@ -25,7 +25,7 @@ param set SENS_FLOW_MINHGT 0.0
|
||||
param set SENS_FLOW_MAXHGT 4.0
|
||||
param set SENS_FLOW_MAXR 10.0
|
||||
|
||||
param set EKF2_AID_MASK 27 # gps + flow + vis pos + vis yaw
|
||||
param set EKF2_AID_MASK 26 # flow + vis pos + vis yaw
|
||||
param set EKF2_OF_DELAY 0
|
||||
param set EKF2_OF_QMIN 10
|
||||
param set EKF2_OF_N_MIN 0.05
|
||||
|
||||
@@ -1,83 +0,0 @@
|
||||
const sidebar = require('./sidebar');
|
||||
|
||||
const hostname = 'https://clover.coex.tech/';
|
||||
const allowedTags = ['font', 'center', 'nobr']; // allow using some deprecated and non-standard html tags
|
||||
|
||||
module.exports = {
|
||||
lang: 'en-US',
|
||||
title: 'Clover',
|
||||
description: 'Clover Drone Kit',
|
||||
// theme and its config
|
||||
theme: '@vuepress/theme-default',
|
||||
themeConfig: {
|
||||
logo: 'clover-logo.png',
|
||||
sidebar: {
|
||||
'/ru/': sidebar.readSummary("./ru/SUMMARY.md"),
|
||||
'/en/': sidebar.readSummary("./en/SUMMARY.md"),
|
||||
},
|
||||
sidebarDepth: 0,
|
||||
locales: {
|
||||
'/en/': {
|
||||
selectLanguageName: 'English',
|
||||
navbar: [
|
||||
{ text: 'Official Site', link: 'https://coex.tech' },
|
||||
{ text: 'Support Chat', link: 'https://t.me/COEXHelpdesk' },
|
||||
]
|
||||
},
|
||||
'/ru/': {
|
||||
selectLanguageName: 'Русский',
|
||||
tip: 'СОВЕТ',
|
||||
warning: 'ВНИМАНИЕ',
|
||||
danger: 'ОПАСНО',
|
||||
toggleDarkMode: 'Переключить темную тему',
|
||||
navbar: [
|
||||
{ text: 'Сайт', link: 'https://coex.tech' },
|
||||
{ text: 'Чат поддержки', link: 'https://t.me/COEXHelpdesk' },
|
||||
]
|
||||
},
|
||||
},
|
||||
toggleSidebar: true,
|
||||
repo: 'CopterExpress/clover',
|
||||
docsBranch: 'master',
|
||||
docsDir: 'docs',
|
||||
lastUpdated: false,
|
||||
contributors: false
|
||||
},
|
||||
pagePatterns: ['**/*.md', '!.vuepress', '!node_modules', '!ru/metodmaterials.md'],
|
||||
locales: {
|
||||
'/en/': {
|
||||
lang: 'en',
|
||||
title: 'Clover',
|
||||
description: 'Clover Drone Kit'
|
||||
},
|
||||
'/ru/': {
|
||||
lang: 'ru',
|
||||
title: 'Клевер',
|
||||
description: 'Конструктор квадрокоптера «Клевер»'
|
||||
}
|
||||
},
|
||||
markdown: {
|
||||
code: {
|
||||
lineNumbers: false
|
||||
},
|
||||
linkify: true,
|
||||
},
|
||||
extendsMarkdown(md) {
|
||||
md.use(require('markdown-it-attrs')); // to use custom headers anchors
|
||||
},
|
||||
bundlerConfig: {
|
||||
vuePluginOptions: {
|
||||
template: {
|
||||
compilerOptions: {
|
||||
isCustomElement: tag => allowedTags.includes(tag)
|
||||
}
|
||||
}
|
||||
}
|
||||
},
|
||||
plugins: [
|
||||
'@vuepress/plugin-search',
|
||||
'vuepress-plugin-copy-code2',
|
||||
['sitemap2', { hostname, excludeUrls: ['/', '/LANGS.html'] }],
|
||||
require('./rich-quotes')
|
||||
]
|
||||
}
|
||||
|
Before Width: | Height: | Size: 110 KiB |
@@ -1,37 +0,0 @@
|
||||
// Plugin to convert GitBook rich quotes to custom containers
|
||||
|
||||
const types = {
|
||||
info: 'tip',
|
||||
note: 'tip',
|
||||
tag: 'tip',
|
||||
comment: 'tip',
|
||||
hint: 'tip',
|
||||
success: 'tip',
|
||||
warning: 'warning',
|
||||
caution: 'warning',
|
||||
danger: 'danger',
|
||||
quote: 'tip'
|
||||
}
|
||||
|
||||
function replace(src) {
|
||||
return src.replace(/^> \*\*(.*?)\*\* (.*\n(>.*\n)*)/gm, function (match, type, text) {
|
||||
text = text.replace(/^>/gm, '');
|
||||
return `::: ${types[type.toLowerCase()]}\n${text}\n:::`;
|
||||
});
|
||||
}
|
||||
|
||||
module.exports = {
|
||||
name: 'vuepress-plugin-rich-quotes',
|
||||
extendsMarkdown: (md) => {
|
||||
var _render = md.render;
|
||||
|
||||
// TODO: a rough hack to replace rich quotes
|
||||
// TODO: use proper plugin api
|
||||
|
||||
md.render = function(src, env) {
|
||||
src = replace(src);
|
||||
return _render.call(md, src, env);
|
||||
}
|
||||
},
|
||||
|
||||
};
|
||||
@@ -1,50 +0,0 @@
|
||||
const fs = require('fs')
|
||||
|
||||
const regex = /(\s*?)\*\s\[(.*?)\]\((.*?)\)/;
|
||||
|
||||
exports.readSummary = function (path) {
|
||||
let sidebar = [];
|
||||
let lines = fs.readFileSync(path).toString().split('\n');
|
||||
let item = {};
|
||||
|
||||
for (let line of lines) {
|
||||
if (line.startsWith('#')) continue;
|
||||
if (!line.trim()) continue;
|
||||
|
||||
let match = regex.exec(line);
|
||||
if (!match) {
|
||||
console.log('cannot parse', line);
|
||||
continue;
|
||||
}
|
||||
level = match[1].length / 2;
|
||||
text = match[2];
|
||||
path = match[3].trim();
|
||||
|
||||
if (level == 0) {
|
||||
if (item.path) {
|
||||
// push new item
|
||||
if (item.children) {
|
||||
sidebar.push(item);
|
||||
} else {
|
||||
sidebar.push(item.path)
|
||||
}
|
||||
item = {};
|
||||
}
|
||||
item.text = text;
|
||||
item.path = path;
|
||||
item.collapsible = true;
|
||||
|
||||
} else if (level == 1 || level == 2) {
|
||||
if (!item.children) {
|
||||
item.children = [];
|
||||
if (item.path) item.children.push(item.path);
|
||||
}
|
||||
item.children.push(path);
|
||||
|
||||
} else {
|
||||
console.log('skip', text);
|
||||
}
|
||||
}
|
||||
|
||||
return sidebar;
|
||||
}
|
||||
@@ -1,49 +0,0 @@
|
||||
.big-clover {
|
||||
max-width: 80% !important;
|
||||
display: block;
|
||||
margin-left: auto;
|
||||
margin-right: auto;
|
||||
}
|
||||
|
||||
/* change image for dark theme */
|
||||
html .big-clover.dark { display: none; }
|
||||
html.dark .big-clover { display: none; }
|
||||
html.dark .big-clover.dark { display: block; }
|
||||
|
||||
img.logo {
|
||||
transform: scale(2.5) translateX(-5%);
|
||||
}
|
||||
|
||||
/* Centered images */
|
||||
img.center {
|
||||
display: block;
|
||||
margin-left: auto;
|
||||
margin-right: auto;
|
||||
}
|
||||
|
||||
/* Images with border */
|
||||
img.border {
|
||||
border: 1px #e9e9e9 solid;
|
||||
border-radius: 5px;
|
||||
}
|
||||
|
||||
html.dark img.border {
|
||||
border: none;
|
||||
background: #fffffa;
|
||||
}
|
||||
|
||||
table.versions td {
|
||||
text-align: center;
|
||||
background: white;
|
||||
}
|
||||
table.versions .subversion {
|
||||
font-size: 80%;
|
||||
}
|
||||
|
||||
.circle {
|
||||
width: 0.8em;
|
||||
height: 0.8em;
|
||||
border-radius: 50%;
|
||||
display: inline-block;
|
||||
margin-right: 0.5em;
|
||||
}
|
||||
@@ -1,4 +0,0 @@
|
||||
# Languages
|
||||
|
||||
* [English](en/)
|
||||
* [Русский](ru/)
|
||||
BIN
docs/assets/c305.jpg
Normal file
|
After Width: | Height: | Size: 40 KiB |
BIN
docs/assets/c4s/antennac4s.jpg
Normal file
|
After Width: | Height: | Size: 25 KiB |
BIN
docs/assets/c4s/arecibo_broken_c4s.jpg
Normal file
|
After Width: | Height: | Size: 299 KiB |
BIN
docs/assets/c4s/arecibo_c4s.jpg
Normal file
|
After Width: | Height: | Size: 152 KiB |
BIN
docs/assets/c4s/code_c4s.png
Normal file
|
After Width: | Height: | Size: 148 KiB |
BIN
docs/assets/c4s/drone_c4s.jpg
Normal file
|
After Width: | Height: | Size: 37 KiB |
BIN
docs/assets/c4s/logo_c4s.jpg
Normal file
|
After Width: | Height: | Size: 6.4 KiB |
BIN
docs/assets/c4s/module2_c4s.jpg
Normal file
|
After Width: | Height: | Size: 23 KiB |
BIN
docs/assets/c4s/module_c4s.jpg
Normal file
|
After Width: | Height: | Size: 28 KiB |
BIN
docs/assets/c4s/pic1_c4s.jpg
Normal file
|
After Width: | Height: | Size: 120 KiB |
BIN
docs/assets/c4s/pic2_c4s.jpg
Normal file
|
After Width: | Height: | Size: 121 KiB |
BIN
docs/assets/c4s/pic3_c4s.jpg
Normal file
|
After Width: | Height: | Size: 267 KiB |
BIN
docs/assets/c4s/pic4_c4s.jpg
Normal file
|
After Width: | Height: | Size: 175 KiB |
BIN
docs/assets/c4s/shot_c4s.jpg
Normal file
|
After Width: | Height: | Size: 265 KiB |
BIN
docs/assets/c4s/string_c4s.jpg
Normal file
|
After Width: | Height: | Size: 4.6 KiB |
BIN
docs/assets/c4s/white_noise_c4s.jpg
Normal file
|
After Width: | Height: | Size: 424 KiB |
BIN
docs/assets/clover-rescue-team/allsettings.png
Normal file
|
After Width: | Height: | Size: 33 KiB |
BIN
docs/assets/clover-rescue-team/bot1.jpg
Normal file
|
After Width: | Height: | Size: 54 KiB |
BIN
docs/assets/clover-rescue-team/bot2.png
Normal file
|
After Width: | Height: | Size: 99 KiB |
BIN
docs/assets/clover-rescue-team/bot3.jpg
Normal file
|
After Width: | Height: | Size: 48 KiB |
BIN
docs/assets/clover-rescue-team/bot4.png
Normal file
|
After Width: | Height: | Size: 70 KiB |
BIN
docs/assets/clover-rescue-team/bot5.jpg
Normal file
|
After Width: | Height: | Size: 67 KiB |
BIN
docs/assets/clover-rescue-team/bot6.jpg
Normal file
|
After Width: | Height: | Size: 80 KiB |
BIN
docs/assets/clover-rescue-team/bot7.jpg
Normal file
|
After Width: | Height: | Size: 42 KiB |
BIN
docs/assets/clover-rescue-team/m1.jpg
Normal file
|
After Width: | Height: | Size: 36 KiB |
BIN
docs/assets/clover-rescue-team/m2.jpg
Normal file
|
After Width: | Height: | Size: 35 KiB |
BIN
docs/assets/clover-rescue-team/m3.jpg
Normal file
|
After Width: | Height: | Size: 97 KiB |
BIN
docs/assets/clover-rescue-team/m4.jpg
Normal file
|
After Width: | Height: | Size: 34 KiB |
BIN
docs/assets/clover-rescue-team/m5.jpg
Normal file
|
After Width: | Height: | Size: 41 KiB |
BIN
docs/assets/clover-rescue-team/main.png
Normal file
|
After Width: | Height: | Size: 169 KiB |
BIN
docs/assets/clover-rescue-team/mockup.png
Normal file
|
After Width: | Height: | Size: 99 KiB |
BIN
docs/assets/clover-rescue-team/s1.png
Normal file
|
After Width: | Height: | Size: 1.7 KiB |
BIN
docs/assets/clover-rescue-team/s2.png
Normal file
|
After Width: | Height: | Size: 4.7 KiB |
BIN
docs/assets/clover-rescue-team/s3.png
Normal file
|
After Width: | Height: | Size: 8.1 KiB |
BIN
docs/assets/clover-rescue-team/s4.png
Normal file
|
After Width: | Height: | Size: 27 KiB |
BIN
docs/assets/clover-rescue-team/signup.png
Normal file
|
After Width: | Height: | Size: 39 KiB |
BIN
docs/assets/clover-rescue-team/status.png
Normal file
|
After Width: | Height: | Size: 5.0 KiB |
BIN
docs/assets/copter_cat/board_bottom_nums.png
Normal file
|
After Width: | Height: | Size: 111 KiB |
BIN
docs/assets/copter_cat/board_top_nums.png
Normal file
|
After Width: | Height: | Size: 113 KiB |
25
docs/assets/copter_cat/logo.svg
Normal file
@@ -0,0 +1,25 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<!DOCTYPE svg PUBLIC "-//W3C//DTD SVG 1.1//EN" "http://www.w3.org/Graphics/SVG/1.1/DTD/svg11.dtd">
|
||||
<!-- Creator: CorelDRAW 2019 (64-Bit) -->
|
||||
<svg xmlns="http://www.w3.org/2000/svg" xml:space="preserve" width="255.858mm" height="78.1171mm" version="1.1" style="shape-rendering:geometricPrecision; text-rendering:geometricPrecision; image-rendering:optimizeQuality; fill-rule:evenodd; clip-rule:evenodd"
|
||||
viewBox="0 0 5794.02 1769"
|
||||
xmlns:xlink="http://www.w3.org/1999/xlink"
|
||||
xmlns:xodm="http://www.corel.com/coreldraw/odm/2003">
|
||||
<defs>
|
||||
<style type="text/css">
|
||||
<![CDATA[
|
||||
.fil1 {fill:#1F1B20}
|
||||
.fil0 {fill:#1F1B20;fill-rule:nonzero}
|
||||
]]>
|
||||
</style>
|
||||
</defs>
|
||||
<g id="Слой_x0020_1">
|
||||
<metadata id="CorelCorpID_0Corel-Layer"/>
|
||||
<polygon class="fil0" points="3293.37,1768.99 2509.06,1768.97 2507.86,1661.12 3292.17,1660.65 "/>
|
||||
<polygon class="fil0" points="3133.99,231.57 2664.24,231.57 2556.99,123.72 3237.05,123.23 "/>
|
||||
<path class="fil0" d="M3647.51 123.72l1925.38 0 0 381.38 -107.85 -8.69 0 -264.84 -1809.74 0 -7.79 -107.85zm1925.38 676.77l0 968.51 -1653.42 0 -1.5 -108.34 1547.07 0.49 0 -850.17 107.85 -10.48z"/>
|
||||
<path class="fil0" d="M2142.36 123.72l-1925.38 0 0 381.38 107.85 -8.69 0 -264.84 1809.74 0 7.79 -107.85zm-1925.38 676.77l0 968.51 1654.08 0 1.5 -108.34 -1547.73 0.49 0 -850.17 -107.85 -10.48z"/>
|
||||
<path class="fil1" d="M2887.45 1229.18c-100.66,0 -189.34,-87.18 -244.46,-111.14 -55.12,-23.96 -215.7,-63.51 -215.7,-63.51 0,0 -88.67,-131.81 -110.24,-196.52 -21.57,-64.71 -38.35,-225.29 -38.35,-225.29 0,0 -28.76,-59.92 -38.35,-86.28 -9.59,-26.36 -19.17,-79.09 -19.17,-79.09l67.11 -59.92 -71.9 -21.57c0,0 -9.59,-131.82 -9.59,-184.54 0,-52.73 28.76,-201.32 28.76,-201.32 0,0 143.8,76.69 242.06,148.59 98.26,71.9 201.32,220.49 201.32,220.49 0,0 97.96,-32.96 220.19,-32.96 122.23,0 212.4,32.96 212.4,32.96 0,0 103.06,-148.59 201.32,-220.49 98.26,-71.9 242.06,-148.59 242.06,-148.59 29.86,154.29 35.16,239.28 25.77,366.69 -7.33,99.38 -20.22,164.6 -68.91,266.02 0,0 -16.78,146.2 -38.35,225.29 -21.57,79.09 -110.24,196.52 -110.24,196.52 0,0 -165.37,25.17 -221.69,53.92 -56.32,28.76 -153.38,120.73 -254.04,120.73zm-260.11 -471.35c0,0 -32.95,31.4 -32.95,71.54 0,40.15 29.36,76.45 29.36,76.45 0,0 30.97,-38.24 30.97,-73.59 0,-35.35 -27.38,-74.4 -27.38,-74.4zm-164.17 -37.15c0,0 84.84,-18.88 192.09,33.85 107.25,52.73 163.22,135.12 163.22,135.12 0,0 -122.28,71.58 -245.11,36.23 -122.83,-35.35 -110.2,-205.2 -110.2,-205.2zm687.07 37.15c0,0 32.95,31.4 32.95,71.54 0,40.15 -29.36,76.45 -29.36,76.45 0,0 -30.97,-38.24 -30.97,-73.59 0,-35.35 27.38,-74.4 27.38,-74.4zm164.17 -37.15c0,0 -84.84,-18.88 -192.09,33.85 -107.25,52.73 -163.22,135.12 -163.22,135.12 0,0 122.28,71.58 245.11,36.23 122.83,-35.35 110.2,-205.2 110.2,-205.2z"/>
|
||||
<path class="fil1" d="M2895.05 1398.42c0,0 -216.07,-1.19 -337.7,-47.93 -121.63,-46.74 -147.39,-68.91 -147.39,-68.91l-149.64 380.47 134.66 0 1.2 105.45 -411.02 0 0 -105.45 154.43 0 105.6 -464.95c0,0 -226.48,-22.77 -424.21,-81.49 -197.72,-58.72 -354.7,-127.02 -492.51,-133.01 -137.81,-5.99 -114.44,-2.99 -198.32,-7.79 -83.88,-4.79 -142.6,-47.92 -142.6,-82.68 0,-34.75 1.2,-59.32 1.2,-97.66 0,-38.35 32.36,-46.74 32.36,-46.74l-1.2 -29.96 -22.77 0c0,-8.09 12.58,-46.74 -53.93,-46.74 -66.51,0 -175.67,58.19 -233.67,77.89 -58,19.71 -552.43,-15.58 -644.7,-41.94 -92.27,-26.36 -64.71,-77.89 -45.54,-94.67 19.17,-16.78 539.25,-63.51 645.9,-56.32 106.65,7.19 329.54,44.34 329.54,44.34l0 -26.36 25.76 0 0 -25.76 12.58 0c0,0 2.39,-94.67 2.39,-134.21 0,-39.54 37.23,-60.33 65.31,-59.9 28.08,0.43 63.2,25.75 63.2,61.1 0,35.35 2.7,128.82 2.7,128.82l7.49 -0.15 0 25.02 32.95 0 0 27.56c0,0 253.15,-39.85 361,-45.84 107.85,-5.99 594.37,37.15 617.14,58.72 22.77,21.57 35.95,77.89 -39.55,100.66 -75.5,22.77 -581.19,57.52 -639.91,46.74 -58.72,-10.79 -173.73,-77.7 -243.26,-76.69 -69.53,1.01 -56.62,35.95 -56.62,45.54l-22.78 -0.9 -0.16 18.87c0,0 83.07,-1.13 121.42,16.84 38.35,17.97 115.72,50.26 168.44,62.24 52.72,11.98 568.01,-14.38 636.31,-28.76 68.3,-14.38 115.48,-40.16 115.48,-40.16 0,0 16.34,115.66 47.5,189.95 31.16,74.3 86.28,147.39 109.05,164.17 22.77,16.78 156.98,45.54 196.52,59.92 39.55,14.38 110.24,58.72 149.79,86.28 39.55,27.56 112.97,44.34 172.89,44.34 59.92,0 126.57,-16.78 166.12,-44.34 39.55,-27.56 110.24,-71.9 149.79,-86.28 39.55,-14.38 173.76,-43.14 196.52,-59.92 22.77,-16.78 77.89,-89.88 109.05,-164.17 31.16,-74.3 47.5,-189.95 47.5,-189.95 0,0 47.17,25.78 115.48,40.16 68.3,14.38 583.59,40.74 636.31,28.76 52.72,-11.98 130.1,-44.27 168.44,-62.24 38.35,-17.97 121.42,-16.84 121.42,-16.84l-0.16 -18.87 -22.78 0.9c0,-9.59 12.91,-44.53 -56.62,-45.54 -69.53,-1.01 -184.54,65.91 -243.26,76.69 -58.72,10.79 -564.41,-23.97 -639.91,-46.74 -75.5,-22.77 -62.31,-79.09 -39.55,-100.66 22.77,-21.57 509.29,-64.71 617.14,-58.72 107.85,5.99 361,45.84 361,45.84l0 -27.56 32.95 0 0 -25.02 7.49 0.15c0,0 2.7,-93.47 2.7,-128.82 0,-35.35 35.12,-60.67 63.2,-61.1 28.08,-0.43 65.31,20.36 65.31,59.9 0,39.54 2.39,134.21 2.39,134.21l12.58 0 0 25.76 25.76 0 0 26.36c0,0 222.89,-37.15 329.54,-44.34 106.65,-7.19 626.73,39.54 645.9,56.32 19.17,16.78 46.74,68.3 -45.54,94.67 -92.27,26.36 -586.7,61.65 -644.7,41.94 -58,-19.71 -167.17,-77.89 -233.67,-77.89 -66.51,0 -53.93,38.65 -53.93,46.74l-22.77 0 -1.2 29.96c0,0 32.36,8.4 32.36,46.74 0,38.35 1.2,62.91 1.2,97.66 0,34.75 -58.72,77.88 -142.6,82.68 -83.88,4.79 -60.52,1.79 -198.32,7.79 -137.81,5.99 -294.79,74.3 -492.51,133.01 -197.72,58.72 -424.21,81.49 -424.21,81.49l105.6 464.95 154.43 0 0 105.45 -411.02 0 1.2 -105.45 134.66 0 -149.64 -380.47c0,0 -25.76,22.17 -147.39,68.91 -121.63,46.74 -341.62,47.93 -341.62,47.93z"/>
|
||||
</g>
|
||||
</svg>
|
||||
|
After Width: | Height: | Size: 5.5 KiB |
BIN
docs/assets/djs-phoenix/1.png
Normal file
|
After Width: | Height: | Size: 26 KiB |
BIN
docs/assets/djs-phoenix/2.png
Normal file
|
After Width: | Height: | Size: 30 KiB |
BIN
docs/assets/djs-phoenix/3.png
Normal file
|
After Width: | Height: | Size: 295 KiB |
BIN
docs/assets/ftl/advanced_clover_simulation.png
Normal file
|
After Width: | Height: | Size: 301 KiB |
BIN
docs/assets/ftl/advanced_clover_simulation_cli.png
Normal file
|
After Width: | Height: | Size: 71 KiB |
BIN
docs/assets/ftl/advanced_clover_simulation_ros.jpg
Normal file
|
After Width: | Height: | Size: 19 KiB |
BIN
docs/assets/stereo/q320.jpg
Normal file
|
After Width: | Height: | Size: 25 KiB |
BIN
docs/assets/swarm_in_blocks/fpv.jpg
Normal file
|
After Width: | Height: | Size: 38 KiB |
BIN
docs/assets/swarm_in_blocks/swarm_preview.png
Normal file
|
After Width: | Height: | Size: 60 KiB |
BIN
docs/assets/swarm_in_blocks/vid.jpg
Normal file
|
After Width: | Height: | Size: 22 KiB |
|
Before Width: | Height: | Size: 88 KiB After Width: | Height: | Size: 88 KiB |
|
Before Width: | Height: | Size: 84 KiB After Width: | Height: | Size: 84 KiB |
|
Before Width: | Height: | Size: 29 KiB After Width: | Height: | Size: 29 KiB |
|
Before Width: | Height: | Size: 45 KiB After Width: | Height: | Size: 45 KiB |
|
Before Width: | Height: | Size: 17 KiB After Width: | Height: | Size: 17 KiB |
|
Before Width: | Height: | Size: 14 KiB After Width: | Height: | Size: 14 KiB |
|
Before Width: | Height: | Size: 14 KiB After Width: | Height: | Size: 14 KiB |
|
Before Width: | Height: | Size: 11 KiB After Width: | Height: | Size: 11 KiB |
|
Before Width: | Height: | Size: 40 KiB After Width: | Height: | Size: 40 KiB |
|
Before Width: | Height: | Size: 7.3 KiB After Width: | Height: | Size: 7.3 KiB |
|
Before Width: | Height: | Size: 47 KiB After Width: | Height: | Size: 47 KiB |
|
Before Width: | Height: | Size: 77 KiB After Width: | Height: | Size: 77 KiB |
|
Before Width: | Height: | Size: 12 KiB After Width: | Height: | Size: 12 KiB |
|
Before Width: | Height: | Size: 11 KiB After Width: | Height: | Size: 11 KiB |
|
Before Width: | Height: | Size: 13 KiB After Width: | Height: | Size: 13 KiB |
|
Before Width: | Height: | Size: 25 KiB After Width: | Height: | Size: 25 KiB |
|
Before Width: | Height: | Size: 14 KiB After Width: | Height: | Size: 14 KiB |
|
Before Width: | Height: | Size: 23 KiB After Width: | Height: | Size: 23 KiB |
|
Before Width: | Height: | Size: 16 KiB After Width: | Height: | Size: 16 KiB |
|
Before Width: | Height: | Size: 19 KiB After Width: | Height: | Size: 19 KiB |