Compare commits

...

14 Commits

Author SHA1 Message Date
Alexey Rogachevskiy
998796045c aruco_pose nodelet cleanup (#239)
* aruco_pose: Unhardcode contour refinement

Besides, this was basically a no-op anyway, since dynamic parameters
overwrote that anyway.

* aruco_pose: Late-construct objects that use ROS

* aruco_map: Don't create/store node handle

* aruco_pose: Don't assume dist_coeffs size

* aruco_pose: more const == more better

* aruco_pose: Be more obvious about changing variables

* aruco_pose: Fix building for Kinetic

* aruco_pose: Remove global add_definitions
2020-05-30 01:59:51 +03:00
Alexey Rogachevskiy
c5e954b56a optical_flow: Use functional-style parameter fetching 2020-05-30 01:58:14 +03:00
Alexey Rogachevskiy
2814fea9cd optical_flow: Pass nodelet callback queue to TransformListener 2020-05-30 01:58:14 +03:00
Alexey Rogachevskiy
b85326c02a optical_flow: Use cv::Mat(std::vector, bool) ctor for dist_coeffs_ 2020-05-30 01:58:14 +03:00
Alexey Rogachevskiy
98d5d50607 aruco_pose: Prevent OpenCV from crashing (#238)
* aruco_pose: Add tests that crash OpenCV

* aruco_pose: Don't try to interpolate single points
2020-05-30 01:57:14 +03:00
Alexey Rogachevskiy
69c46786de builder: Set apt retries to 3
This should lower the number of builds that failed due to
repositories being unstable
2020-05-29 21:25:58 +03:00
Oleg Kalachev
abb495275b docs: translate robocross-2019 article 2020-05-26 06:54:42 +03:00
Oleg Kalachev
044d6c6d33 docs: switch lpe and ekf2 settings in aruco map navigation articles 2020-05-21 21:01:16 +03:00
Alexey Rogachevskiy
22d5a356b6 clover: Update ros3djs, THREE.js 2020-05-18 16:25:56 +03:00
Alexey Rogachevskiy
c7828557ca standalone_install: Fail on error 2020-05-16 15:49:38 +03:00
Alexey Rogachevskiy
514c0f1b65 Flysky FS-A8S article (#229)
* docs: Add FS-A8S article draft

* docs: Fix image links

* docs/flysky_a8s: Make images appear smaller

* docs: Add animated images

* docs/flysky_a8s: Proofreading

* docs/flysky_a8s: Sync up header to summary entry

* docs/flysky_a8s: Add Flysky FS-A8S article (en)

* docs/flysky_a8s: More proofreading
2020-05-12 12:35:05 +03:00
Oleg Kalachev
6a79b8292a docs: little fix 2020-05-08 17:02:36 +03:00
Oleg Kalachev
10b6661266 docs: add images for ROS javascript article 2020-05-08 16:54:10 +03:00
Oleg Kalachev
7f2cb1c63e docs: add using ROS with javascript article 2020-05-08 16:51:15 +03:00
48 changed files with 56862 additions and 4372 deletions

View File

@@ -1,8 +1,6 @@
cmake_minimum_required(VERSION 3.0)
project(aruco_pose)
add_definitions(-std=c++11 -Wall -g)
## Compile as C++11, supported in ROS Kinetic and newer
add_compile_options(-std=c++11)
@@ -25,7 +23,7 @@ find_package(catkin REQUIRED COMPONENTS
)
find_package(OpenCV 3 REQUIRED COMPONENTS core imgproc calib3d)
if ("${OpenCV_VERSION_MINOR}" LESS "3")
if ("${OpenCV_VERSION_MINOR}" LESS "9")
message(STATUS "OpenCV version too low, using vendored ArUco package")
include(vendor/VendorOpenCV.cmake)
else()
@@ -229,4 +227,5 @@ if (CATKIN_ENABLE_TESTING)
add_rostest(test/test_parser_empty_map.test)
add_rostest(test/test_node_failure.test)
add_rostest(test/largemap.test)
add_rostest(test/crash_opencv.test)
endif()

View File

@@ -58,10 +58,9 @@ using cv::Mat;
class ArucoDetect : public nodelet::Nodelet {
private:
ros::NodeHandle nh_, nh_priv_;
tf2_ros::TransformBroadcaster br_;
tf2_ros::Buffer tf_buffer_;
tf2_ros::TransformListener tf_listener_{tf_buffer_};
std::unique_ptr<tf2_ros::TransformBroadcaster> br_;
std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
std::unique_ptr<tf2_ros::TransformListener> tf_listener_;
std::shared_ptr<dynamic_reconfigure::Server<aruco_pose::DetectorConfig>> dyn_srv_;
cv::Ptr<cv::aruco::Dictionary> dictionary_;
cv::Ptr<cv::aruco::DetectorParameters> parameters_;
@@ -81,30 +80,32 @@ private:
public:
virtual void onInit()
{
nh_ = getNodeHandle();
nh_priv_ = getPrivateNodeHandle();
ros::NodeHandle& nh_ = getNodeHandle();
ros::NodeHandle& nh_priv_ = getPrivateNodeHandle();
br_.reset(new tf2_ros::TransformBroadcaster());
tf_buffer_.reset(new tf2_ros::Buffer());
tf_listener_.reset(new tf2_ros::TransformListener(*tf_buffer_, nh_));
int dictionary;
nh_priv_.param("dictionary", dictionary, 2);
nh_priv_.param("estimate_poses", estimate_poses_, true);
nh_priv_.param("send_tf", send_tf_, true);
dictionary = nh_priv_.param("dictionary", 2);
estimate_poses_ = nh_priv_.param("estimate_poses", true);
send_tf_ = nh_priv_.param("send_tf", true);
if (estimate_poses_ && !nh_priv_.getParam("length", length_)) {
NODELET_FATAL("can't estimate marker's poses as ~length parameter is not defined");
ros::shutdown();
}
readLengthOverride();
readLengthOverride(nh_priv_);
nh_priv_.param<std::string>("known_tilt", known_tilt_, "");
nh_priv_.param("auto_flip", auto_flip_, false);
known_tilt_ = nh_priv_.param<std::string>("known_tilt", "");
auto_flip_ = nh_priv_.param("auto_flip", false);
nh_priv_.param<std::string>("frame_id_prefix", frame_id_prefix_, "aruco_");
frame_id_prefix_ = nh_priv_.param<std::string>("frame_id_prefix", "aruco_");
camera_matrix_ = cv::Mat::zeros(3, 3, CV_64F);
dist_coeffs_ = cv::Mat::zeros(8, 1, CV_64F);
dictionary_ = cv::aruco::getPredefinedDictionary(static_cast<cv::aruco::PREDEFINED_DICTIONARY_NAME>(dictionary));
parameters_ = cv::aruco::DetectorParameters::create();
parameters_->cornerRefinementMethod = cv::aruco::CORNER_REFINE_SUBPIX;
image_transport::ImageTransport it(nh_);
image_transport::ImageTransport it_priv(nh_priv_);
@@ -170,8 +171,8 @@ private:
if (!known_tilt_.empty()) {
try {
snap_to = tf_buffer_.lookupTransform(msg->header.frame_id, known_tilt_,
msg->header.stamp, ros::Duration(0.02));
snap_to = tf_buffer_->lookupTransform(msg->header.frame_id, known_tilt_,
msg->header.stamp, ros::Duration(0.02));
} catch (const tf2::TransformException& e) {
NODELET_WARN_THROTTLE(5, "can't snap: %s", e.what());
}
@@ -205,7 +206,7 @@ private:
if (map_markers_ids_.find(ids[i]) == map_markers_ids_.end()) {
transform.transform.rotation = marker.pose.orientation;
fillTranslation(transform.transform.translation, tvecs[i]);
br_.sendTransform(transform);
br_->sendTransform(transform);
}
}
}
@@ -326,10 +327,10 @@ private:
return frame_id_prefix_ + std::to_string(id);
}
void readLengthOverride()
void readLengthOverride(ros::NodeHandle& nh)
{
std::map<std::string, double> length_override;
nh_priv_.getParam("length_override", length_override);
nh.getParam("length_override", length_override);
for (auto const& item : length_override) {
length_override_[std::stoi(item.first)] = item.second;
}

View File

@@ -58,7 +58,6 @@ typedef message_filters::sync_policies::ExactTime<Image, CameraInfo, MarkerArray
class ArucoMap : public nodelet::Nodelet {
private:
ros::NodeHandle nh_, nh_priv_;
ros::Publisher img_pub_, pose_pub_, markers_pub_, vis_markers_pub_;
image_transport::Publisher debug_pub_;
message_filters::Subscriber<Image> image_sub_;
@@ -83,8 +82,8 @@ private:
public:
virtual void onInit()
{
nh_ = getNodeHandle();
nh_priv_ = getPrivateNodeHandle();
ros::NodeHandle &nh_ = getNodeHandle();
ros::NodeHandle &nh_priv_ = getPrivateNodeHandle();
image_transport::ImageTransport it_priv(nh_priv_);
@@ -96,19 +95,18 @@ public:
board_->dictionary = cv::aruco::getPredefinedDictionary(
static_cast<cv::aruco::PREDEFINED_DICTIONARY_NAME>(nh_priv_.param("dictionary", 2)));
camera_matrix_ = cv::Mat::zeros(3, 3, CV_64F);
dist_coeffs_ = cv::Mat::zeros(8, 1, CV_64F);
std::string type, map;
nh_priv_.param<std::string>("type", type, "map");
nh_priv_.param<std::string>("frame_id", transform_.child_frame_id, "aruco_map");
nh_priv_.param<std::string>("known_tilt", known_tilt_, "");
nh_priv_.param("auto_flip", auto_flip_, false);
nh_priv_.param("image_width", image_width_, 2000);
nh_priv_.param("image_height", image_height_, 2000);
nh_priv_.param("image_margin", image_margin_, 200);
nh_priv_.param("image_axis", image_axis_, true);
nh_priv_.param<std::string>("markers/frame_id", markers_parent_frame_, transform_.child_frame_id);
nh_priv_.param<std::string>("markers/child_frame_id_prefix", markers_frame_, "");
type = nh_priv_.param<std::string>("type", "map");
transform_.child_frame_id = nh_priv_.param<std::string>("frame_id", "aruco_map");
known_tilt_ = nh_priv_.param<std::string>("known_tilt", "");
auto_flip_ = nh_priv_.param("auto_flip", false);
image_width_ = nh_priv_.param("image_width" , 2000);
image_height_ = nh_priv_.param("image_height", 2000);
image_margin_ = nh_priv_.param("image_margin", 200);
image_axis_ = nh_priv_.param("image_axis", true);
markers_parent_frame_ = nh_priv_.param<std::string>("markers/frame_id", transform_.child_frame_id);
markers_frame_ = nh_priv_.param<std::string>("markers/child_frame_id_prefix", "");
// createStripLine();
@@ -116,7 +114,7 @@ public:
param(nh_priv_, "map", map);
loadMap(map);
} else if (type == "gridboard") {
createGridBoard();
createGridBoard(nh_priv_);
} else {
NODELET_FATAL("unknown type: %s", type.c_str());
ros::shutdown();
@@ -331,7 +329,7 @@ publish_debug:
NODELET_INFO("loading %s complete (%d markers)", filename.c_str(), static_cast<int>(board_->ids.size()));
}
void createGridBoard()
void createGridBoard(ros::NodeHandle& nh)
{
NODELET_INFO("generate gridboard");
NODELET_WARN("gridboard maps are deprecated");
@@ -339,15 +337,15 @@ publish_debug:
int markers_x, markers_y, first_marker;
double markers_side, markers_sep_x, markers_sep_y;
std::vector<int> marker_ids;
nh_priv_.param<int>("markers_x", markers_x, 10);
nh_priv_.param<int>("markers_y", markers_y, 10);
nh_priv_.param<int>("first_marker", first_marker, 0);
markers_x = nh.param("markers_x", 10);
markers_y = nh.param("markers_y", 10);
first_marker = nh.param("first_marker", 0);
param(nh_priv_, "markers_side", markers_side);
param(nh_priv_, "markers_sep_x", markers_sep_x);
param(nh_priv_, "markers_sep_y", markers_sep_y);
param(nh, "markers_side", markers_side);
param(nh, "markers_sep_x", markers_sep_x);
param(nh, "markers_sep_y", markers_sep_y);
if (nh_priv_.getParam("marker_ids", marker_ids)) {
if (nh.getParam("marker_ids", marker_ids)) {
if ((unsigned int)(markers_x * markers_y) != marker_ids.size()) {
NODELET_FATAL("~marker_ids length should be equal to ~markers_x * ~markers_y");
ros::shutdown();

View File

@@ -35,9 +35,7 @@ static void parseCameraInfo(const sensor_msgs::CameraInfoConstPtr& cinfo, cv::Ma
for (unsigned int i = 0; i < 3; ++i)
for (unsigned int j = 0; j < 3; ++j)
matrix.at<double>(i, j) = cinfo->K[3 * i + j];
for (unsigned int k = 0; k < cinfo->D.size(); k++)
dist.at<double>(k) = cinfo->D[k];
dist = cv::Mat(cinfo->D, true);
}
inline void rotatePoint(cv::Point3f& p, cv::Point3f origin, float angle)

Binary file not shown.

After

Width:  |  Height:  |  Size: 159 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 156 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 165 KiB

View File

@@ -0,0 +1,18 @@
import rospy
import pytest
from visualization_msgs.msg import MarkerArray as VisMarkerArray
@pytest.fixture
def node():
return rospy.init_node('aruco_pose_opencv_crash', anonymous=True)
def test_opencv_crashes_img01(node):
rospy.wait_for_message('aruco_detect_01/visualization', VisMarkerArray, timeout=5)
def test_opencv_crashes_img02(node):
rospy.wait_for_message('aruco_detect_02/visualization', VisMarkerArray, timeout=5)
def test_opencv_crashes_img03(node):
rospy.wait_for_message('aruco_detect_03/visualization', VisMarkerArray, timeout=5)

View File

@@ -0,0 +1,51 @@
<launch>
<arg name="corner_method" default="2"/>
<node pkg="image_publisher" type="image_publisher" name="imgpub_01" args="$(find aruco_pose)/test/crash_image_01.png">
<param name="frame_id" value="main_camera_optical"/>
<param name="publish_rate" value="10"/>
<param name="camera_info_url" value="file://$(find aruco_pose)/test/camera_info.yaml" />
</node>
<node pkg="image_publisher" type="image_publisher" name="imgpub_02" args="$(find aruco_pose)/test/crash_image_02.png">
<param name="frame_id" value="main_camera_optical"/>
<param name="publish_rate" value="10"/>
<param name="camera_info_url" value="file://$(find aruco_pose)/test/camera_info.yaml" />
</node>
<node pkg="image_publisher" type="image_publisher" name="imgpub_03" args="$(find aruco_pose)/test/crash_image_03.png">
<param name="frame_id" value="main_camera_optical"/>
<param name="publish_rate" value="10"/>
<param name="camera_info_url" value="file://$(find aruco_pose)/test/camera_info.yaml" />
</node>
<node pkg="nodelet" type="nodelet" name="nodelet_manager_01" args="manager"/>
<node pkg="nodelet" clear_params="true" type="nodelet" name="aruco_detect_01" args="load aruco_pose/aruco_detect nodelet_manager_01">
<remap from="image_raw" to="imgpub_01/image_raw"/>
<remap from="camera_info" to="imgpub_01/camera_info"/>
<param name="length" value="0.33"/>
<param name="cornerRefinementMethod" value="$(arg corner_method)"/>
</node>
<node pkg="nodelet" type="nodelet" name="nodelet_manager_02" args="manager"/>
<node pkg="nodelet" clear_params="true" type="nodelet" name="aruco_detect_02" args="load aruco_pose/aruco_detect nodelet_manager_02">
<remap from="image_raw" to="imgpub_02/image_raw"/>
<remap from="camera_info" to="imgpub_02/camera_info"/>
<param name="length" value="0.33"/>
<param name="cornerRefinementMethod" value="$(arg corner_method)"/>
</node>
<node pkg="nodelet" type="nodelet" name="nodelet_manager_03" args="manager"/>
<node pkg="nodelet" clear_params="true" type="nodelet" name="aruco_detect_03" args="load aruco_pose/aruco_detect nodelet_manager_03">
<remap from="image_raw" to="imgpub_03/image_raw"/>
<remap from="camera_info" to="imgpub_03/camera_info"/>
<param name="length" value="0.33"/>
<param name="cornerRefinementMethod" value="$(arg corner_method)"/>
</node>
<param name="test_module" value="$(find aruco_pose)/test/crash_opencv.py"/>
<test test-name="crash_opencv" pkg="ros_pytest" type="ros_pytest_runner"/>
</launch>

View File

@@ -924,6 +924,8 @@ static void _refineCandidateLines(std::vector<Point>& nContours, std::vector<Poi
// calculate the line :: who passes through the grouped points
Point3f lines[4];
for(int i=0; i<4; i++){
// Don't try to "interpolate" single points
if (cntPts[i].size() < 2) return;
lines[i]=_interpolate2Dline(cntPts[i]);
}

View File

@@ -57,6 +57,10 @@ my_travis_retry() {
return $result
}
echo_stamp "Increase apt retries"
echo "APT::Acquire::Retries \"3\";" > /etc/apt/apt.conf.d/80-retries
echo_stamp "Install apt keys & repos"
# TODO: This STDOUT consist 'OK'

View File

@@ -1,7 +1,7 @@
#!/bin/bash
# Perform a "standalone install" in a Docker container
set -e
# Step 1: Install pip
apt update
apt install -y curl

View File

@@ -34,9 +34,7 @@ class OpticalFlow : public nodelet::Nodelet
{
public:
OpticalFlow():
camera_matrix_(3, 3, CV_64F),
dist_coeffs_(8, 1, CV_64F),
tf_listener_(tf_buffer_)
camera_matrix_(3, 3, CV_64F)
{}
private:
@@ -52,8 +50,8 @@ private:
Mat hann_;
Mat prev_, curr_;
Mat camera_matrix_, dist_coeffs_;
tf2_ros::Buffer tf_buffer_;
tf2_ros::TransformListener tf_listener_;
std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
std::unique_ptr<tf2_ros::TransformListener> tf_listener_;
bool calc_flow_gyro_;
void onInit()
@@ -63,11 +61,14 @@ private:
image_transport::ImageTransport it(nh);
image_transport::ImageTransport it_priv(nh_priv);
nh.param<std::string>("mavros/local_position/tf/frame_id", local_frame_id_, "map");
nh.param<std::string>("mavros/local_position/tf/child_frame_id", fcu_frame_id_, "base_link");
nh_priv.param("roi", roi_px_, 128);
nh_priv.param("roi_rad", roi_rad_, 0.0);
nh_priv.param("calc_flow_gyro", calc_flow_gyro_, false);
tf_buffer_.reset(new tf2_ros::Buffer());
tf_listener_.reset(new tf2_ros::TransformListener(*tf_buffer_, nh));
local_frame_id_ = nh.param<std::string>("mavros/local_position/tf/frame_id", "map");
fcu_frame_id_ = nh.param<std::string>("mavros/local_position/tf/child_frame_id", "base_link");
roi_px_ = nh_priv.param("roi", 128);
roi_rad_ = nh_priv.param("roi_rad", 0.0);
calc_flow_gyro_ = nh_priv.param("calc_flow_gyro", false);
img_sub_ = it.subscribeCamera("image_raw", 1, &OpticalFlow::flow, this);
img_pub_ = it_priv.advertise("debug", 1);
@@ -91,9 +92,7 @@ private:
camera_matrix_.at<double>(i, j) = cinfo->K[3 * i + j];
}
}
for (int k = 0; k < cinfo->D.size(); k++) {
dist_coeffs_.at<double>(k) = cinfo->D[k];
}
dist_coeffs_ = cv::Mat(cinfo->D, true);
}
void drawFlow(Mat& frame, double x, double y, double quality) const
@@ -186,7 +185,7 @@ private:
flow_camera.vector.x = flow_y; // +y means counter-clockwise rotation around Y axis
flow_camera.vector.y = -flow_x; // +x means clockwise rotation around X axis
try {
tf_buffer_.transform(flow_camera, flow_fcu, fcu_frame_id_);
tf_buffer_->transform(flow_camera, flow_fcu, fcu_frame_id_);
} catch (const tf2::TransformException& e) {
// transform is not available yet
return;
@@ -200,7 +199,7 @@ private:
try {
auto flow_gyro_camera = calcFlowGyro(msg->header.frame_id, prev_stamp_, msg->header.stamp);
static geometry_msgs::Vector3Stamped flow_gyro_fcu;
tf_buffer_.transform(flow_gyro_camera, flow_gyro_fcu, fcu_frame_id_);
tf_buffer_->transform(flow_gyro_camera, flow_gyro_fcu, fcu_frame_id_);
flow_.integrated_xgyro = flow_gyro_fcu.vector.x;
flow_.integrated_ygyro = flow_gyro_fcu.vector.y;
flow_.integrated_zgyro = flow_gyro_fcu.vector.z;
@@ -247,8 +246,8 @@ private:
geometry_msgs::Vector3Stamped calcFlowGyro(const std::string& frame_id, const ros::Time& prev, const ros::Time& curr)
{
tf2::Quaternion prev_rot, curr_rot;
tf2::fromMsg(tf_buffer_.lookupTransform(frame_id, local_frame_id_, prev).transform.rotation, prev_rot);
tf2::fromMsg(tf_buffer_.lookupTransform(frame_id, local_frame_id_, curr, ros::Duration(0.1)).transform.rotation, curr_rot);
tf2::fromMsg(tf_buffer_->lookupTransform(frame_id, local_frame_id_, prev).transform.rotation, prev_rot);
tf2::fromMsg(tf_buffer_->lookupTransform(frame_id, local_frame_id_, curr, ros::Duration(0.1)).transform.rotation, curr_rot);
geometry_msgs::Vector3Stamped flow;
flow.header.frame_id = frame_id;

59075
clover/www/js/ros3d.js vendored

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

Binary file not shown.

After

Width:  |  Height:  |  Size: 52 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 52 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 61 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 62 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 53 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 58 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 69 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 64 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 65 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 26 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 69 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 61 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 58 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 130 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 121 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 70 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 97 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 266 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 266 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 280 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 143 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 155 KiB

BIN
docs/assets/js-ros.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 251 KiB

BIN
docs/assets/web-gcs.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 122 KiB

View File

@@ -11,6 +11,7 @@
* [Initial setup](setup.md)
* [Sensor calibration](calibration.md)
* [RC setup](radio.md)
* [Using FS-A8S](rc_flysky_a8s.md)
* [Flight modes](modes.md)
* [Power setup](power.md)
* [Failsafe configuration](failsafe.md)
@@ -41,7 +42,8 @@
* [Interfacing with a sonar](sonar.md)
* [Computer vision basics](camera.md)
* [Using rviz and rqt](rviz.md)
* [Software autorun](autolaunch.md)
* [Software autorun](autolaunch.md)
* [Using JavaScript](javascript.md)
* [ROS](ros.md)
* [MAVROS](mavros.md)
* Supplementary materials
@@ -87,4 +89,5 @@
* [Copter Hack 2019](copterhack2019.md)
* [Copter Hack 2018](copterhack2018.md)
* [Copter Hack 2017](copterhack2017.md)
* [Robocross-2019](robocross2019.md)
* [Camera calibration (legacy)](camera_calib.md)

View File

@@ -91,13 +91,6 @@ The marker map adheres to the [ROS coordinate system convention](http://www.ros.
In order to enable vision position estimation you should use the following [PX4 parameters](px4_parameters.md).
If you're using **EKF2** estimator (`SYS_MC_EST_GROUP` parameter is set to `ekf2`), make sure the following is set:
* `EKF2_AID_MASK` should have `vision position fusion` and `vision yaw fusion` flags set.
* Vision angle observations noise: `EKF2_EVA_NOISE` = 0.1 rad.
* Vision position observations noise: `EKF2_EVP_NOISE` = 0.1 m.
* `EKF2_EV_DELAY` = 0.
If you're using **LPE** (`SYS_MC_EST_GROUP` parameter is set to `local_position_estimator,attitude_estimator_q`):
* `LPE_FUSION` should have `vision position` and `land detector` flags set. We suggest unsetting the `baro` flag for indoor flights.
@@ -108,6 +101,13 @@ If you're using **LPE** (`SYS_MC_EST_GROUP` parameter is set to `local_position_
<!-- * Compass should not be fused: `ATT_W_MAG` = 0 -->
If you're using **EKF2** estimator (`SYS_MC_EST_GROUP` parameter is set to `ekf2`), make sure the following is set:
* `EKF2_AID_MASK` should have `vision position fusion` and `vision yaw fusion` flags set.
* Vision angle observations noise: `EKF2_EVA_NOISE` = 0.1 rad.
* Vision position observations noise: `EKF2_EVP_NOISE` = 0.1 m.
* `EKF2_EV_DELAY` = 0.
> **Hint** We recommend using **LPE** for marker-based navigation.
You may use [the `selfcheck.py` utility](selfcheck.md) to check your settings.

54
docs/en/javascript.md Normal file
View File

@@ -0,0 +1,54 @@
# Work with ROS from browser
Using the [`roslibjs`](http://wiki.ros.org/roslibjs) library it's possible to work with all the ROS resources (topics, services, parameters) from JavaScript code within the browser, which allows creating various interactive web applications for drone.
All the required software is preinstalled in [RPi image](image.md) for Clover.
## Example
An example of a web page, working with `roslib.js`:
```html
<html>
<script src="js/roslib.js"></script>
<script type="text/javascript">
// Establish roslibjs connection
var ros = new ROSLIB.Ros({ url: 'ws://' + location.hostname + ':9090' });
ros.on('connection', function () {
// Connection callback
alert('Connected');
});
// Declare get_telemetry service client
var getTelemetry = new ROSLIB.Service({ ros: ros, name : '/get_telemetry', serviceType : 'clover/GetTelemetry' });
// Call get_telemetry
getTelemetry.callService(new ROSLIB.ServiceRequest({ frame_id: 'map' }), function(result) {
// Service respond callback
alert('Telemetry: ' + JSON.stringify(result));
});
// Subscribe to `/mavros/state` topic
var stateSub = new ROSLIB.Topic({ ros : ros, name : '/mavros/state', messageType : 'mavros_msgs/State' });
stateSub.subscribe(function(msg) {
// Topic message callback
console.log('State: ', msg);
});
</script>
</html>
```
[Taking off, landing and all the rest operations](programming.md) can be implemented in a similar way.
The page should be placed in the `/home/pi/catkin_ws/src/clover/clover/www/` directory. After that, it will be available at `http://192.168.11.1/<page_name>.html`. When the page is opened, browser should show an alert with the drone telemetry and constantly print the state of the flight controller to the console.
<img src="../assets/js-ros.png" class="center zoom"/>
See additional information in [`roslibjs` tutorial](http://wiki.ros.org/roslibjs/Tutorials/BasicRosFunctionality).
## Web GCS
See an example of simplified web ground control station on Clover at http://192.168.11.1/gcs.html.
<img src="../assets/web-gcs.png" class="center zoom"/>

107
docs/en/rc_flysky_a8s.md Normal file
View File

@@ -0,0 +1,107 @@
# Using Flysky FS-A8S
The Flysky FS-A8S receiver is compatible with the Flysky FS-i6 and FS-i6x transmitters. The receiver can output both analog PPM and digital S.Bus/i-Bus signals to the flight controller.
S.Bus is the preferred protocol for the receiver.
## Making a cable
> **Note** You don't need to follow these steps if you already have the right cable; read on to learn [how to bind your transmitter](#rc_bind).
1. Gently remove the yellow wire from the receiver connector. Use sharp tweezers to lift up the plastic wire lock:
<div class="image-group">
<img src="../assets/flysky_a8s/01_remove_cable_fs.png" width=300 class="zoom border" alt="a8s wire removal 1">
<img src="../assets/flysky_a8s/02_remove_cable_fs.png" width=300 class="zoom border" alt="a8s wire removal 2">
</div>
2. [Pixracer only] Remove the green and brown wires from the 5-pin connector:
<div class="image-group">
<img src="../assets/flysky_a8s/03_remove_cable_pixracer.png" width=300 class="zoom border" alt="pixracer wire removal 1">
<img src="../assets/flysky_a8s/04_remove_cable_pixracer.png" width=300 class="zoom border" alt="pixracer wire removal 2">
</div>
3. [COEX Pix only] Remove the green wire (or blue if the green one is not present) from the 4-pin connector:
<div class="image-group">
<img src="../assets/flysky_a8s/05_remove_cable_coexpix.png" width=300 class="zoom border" alt="coexpix wire removal 1">
<img src="../assets/flysky_a8s/06_remove_cable_coexpix.png" width=300 class="zoom border" alt="coexpix wire removal 2">
</div>
4. Use side cutters to cut the Dupont connectors:
<div class="image-group">
<img src="../assets/flysky_a8s/07_wirecuts_1.png" width=300 class="zoom border" alt="wire cutting">
<img src="../assets/flysky_a8s/08_wirecuts_2.png" width=300 class="zoom border" alt="wire cuts">
</div>
5. Strip and tin 5-7 mm of wire from each side:
<img src="../assets/flysky_a8s/09_wirecuts_stripped.png" width=300 class="zoom border center" alt="tinning prep">
6. Put heat shrinking tubes on the wires:
<img src="../assets/flysky_a8s/10_heatshrink.png" width=300 class="zoom border center" alt="shrink tubing">
7. Solder the following wires:
* black wire from the receiver connector to the black wire from the flight controller connector;
* red wire from the receiver connector to the red wire from the flight controller connector;
* white wire from the receiver connector to the white (if you're using Pixracer) or yellow (if you're using COEX Pix) wire from the flight controller connector:
<img src="../assets/flysky_a8s/11_solder_scheme.png" width=300 class="zoom border center" alt="wire soldering">
8. Put the heat shrinking tubes on the solder joints and heat them:
<img src="../assets/flysky_a8s/12_heatshrink_heat.png" width=300 class="zoom border center" alt="shrink tube heating">
9. Twist your new cable:
<img src="../assets/flysky_a8s/13_cable_twist.png" width=300 class="zoom border center" alt="twisted cables">
Connect your receiver to the RC IN port on your flight controller:
<div class="image-group">
<img src="../assets/flysky_a8s/14_pixracer_rcin.png" width=300 class="zoom border center" alt="pixracer connection">
<img src="../assets/flysky_a8s/14_coexpix_rcin.png" width=300 class="zoom border center" alt="coex pix connection">
</div>
> **Hint** Double check that you're using the RC IN port on the COEX Pix:
<img src="../assets/coexpix-bottom.jpg" width=300 class="zoom border center" alt="coex pix pinout">
## Binding your transmitter {#rc_bind}
Do the following to bind your transmitter to the FS-A8S receiver:
1. Make sure your flight controller is powered off.
2. Hold the **BIND** button on the receiver:
<img src="../assets/flysky_a8s/15_bind_key.png" width=300 class="zoom border center" alt="bind key">
3. Turn on the flight controller. The LED light on the receiver should blink fast, about 3 times per second.
<img src="../assets/flysky_a8s/16_blink_fast.gif" width=300 class="zoom border center" alt="fast blink">
4. Hold the **BIND KEY** on your transmitter and power it on. You should see a message saying **RX Binding...**
<img src="../assets/flysky_a8s/17_controller_rxbind.png" width=300 class="zoom border center" alt="rx binding">
5. The LED light on the receiver should start blinking slowly, about once per second.
<img src="../assets/flysky_a8s/16_blink_slow.gif" width=300 class="zoom border center" alt="slow blink">
6. Turn your transmitter off and on again. The LED light on the receiver should glow steadily.
<img src="../assets/flysky_a8s/16_bind_indicator.png" width=300 class="zoom border center" alt="steady glow">
> **Note** This receiver does not send any telemetry data back to the transmitter. Your transmitter will not display any data like RSSI and drone battery level on its screen. In fact, there will be no indication that the transmitter is connected to the receiver. This is not a malfunction, the controls will still work.
## Changing the receiver mode (S.Bus/i-Bus)
Connect your flight controller to your computer and open QGroundControl. In it, open the Radio tab:
![qgc radio pane](../assets/flysky_a8s/18_qgc_radio.png)
If it shows zero channels under the transmitter image, hold the **BIND** key on the receiver for 2 seconds. You should then see 18 channels appear under the image:
![qgc radio with channels](../assets/flysky_a8s/19_qgc_channels.png)

25
docs/en/robocross2019.md Normal file
View File

@@ -0,0 +1,25 @@
# Robocross-2019
On July, 2019, for the fourth time in a row, the team Copter Express won the annual tests of unmanned vehicles "[Robocross](http://russianrobotics.ru/activities/robokross-2019/)". Tests are held at the GAZ test site near Nizhny Novgorod.
The main objective of the tests in the UAV category was to localize and destroy the target - the red balloon - autonomously.
## Video
<iframe width="560" height="315" src="https://www.youtube.com/embed/zMh5THdHuX8" frameborder="0" allow="accelerometer; autoplay; encrypted-media; gyroscope; picture-in-picture" allowfullscreen></iframe>
## Implementation
The team used an F450 frame based quadcopter and [Clover software platform](https://github.com/CopterExpress/clover). The final source code is available [on GitHub](https://github.com/CopterExpress/robocross2019/).
`robocross2019` ROS package is divided into two parts: `red_dead_detection` ROS nodelet recognizes the red ball, `ball.py` implements high-level flight logic.
## red_dead_detection
The `red_dead_detection` nodelet recognizes the red ball on the image from the forward looking quadcopter camera (`/front_camera/image_raw` and `/front_camera/camera_info` topics). The simplest method of filtering the image by color is applied. Then the nodelet calculates the geometric center of the detected segments, and performs camera distortion compensation (`cv::undistortPoints`).
Using the known focal lengths of the camera (from `camera_info`), the nodelet calculates the vector directed towards the target. The resulting vector is published to the topic `/red_dead_detection/direction`; its coordinate system (`frame_id` is associated with the front camera `front_camera_optical`).
## balloon.py
To fly towards the ball, the direction vector `red_dead_detection/direction` is used, which is set as a setpoint for the velocity of the drone. The yaw angle is also set towards the ball. The target is considered destroyed when the total area of red pixels is less than the threshold for a certain amount of camera frames.

View File

@@ -11,6 +11,7 @@
* [Первоначальная настройка](setup.md)
* [Калибровка датчиков](calibration.md)
* [Настройка пульта](radio.md)
* [Работа с FS-A8S](rc_flysky_a8s.md)
* [Полетные режимы](modes.md)
* [Настройка питания](power.md)
* [Настройка failsafe](failsafe.md)
@@ -42,6 +43,7 @@
* [Компьютерное зрение](camera.md)
* [Визуализация с помощью rviz](rviz.md)
* [Автозапуск ПО](autolaunch.md)
* [Использование JavaScript](javascript.md)
* [ROS](ros.md)
* [MAVROS](mavros.md)
* Дополнительные материалы

View File

@@ -91,23 +91,23 @@ rosrun aruco_pose genmap.py 0.33 2 4 1 1 0 > ~/catkin_ws/src/clover/aruco_pose/m
Для работы механизма Vision Position Estimation необходимы следующие [настройки PX4](px4_parameters.md).
При использовании **EKF2** (параметр `SYS_MC_EST_GROUP` = `ekf2`):
* В параметре `EKF2_AID_MASK` включены флажки `vision position fusion`, `vision yaw fusion`.
* Шум угла по зрению: `EKF2_EVA_NOISE` = 0.1 rad
* Шум позиции по зрению: `EKF2_EVP_NOISE` = 0.1 m
* `EKF2_EV_DELAY` = 0
При использовании **LPE** (параметр `SYS_MC_EST_GROUP` = `local_position_estimator, attitude_estimator_q`):
* В параметре `LPE_FUSION` включены флажки `vision position`, `land detector`. Флажок `baro` рекомендуется отключить.
* Вес угла по рысканью по зрению: `ATT_W_EXT_HDG` = 0.5
* Включена ориентация по Yaw по зрению: `ATT_EXT_HDG_M` = 1 `Vision`.
* Шумы позиции по зрению: `LPE_VIS_XY` = 0.1 m, `LPE_VIS_Z` = 0.1 m.
* `LPE_VIS_DELAY` = 0 sec
* `LPE_VIS_DELAY` = 0 sec.
<!-- * Выключен компас: `ATT_W_MAG` = 0 -->
При использовании **EKF2** (параметр `SYS_MC_EST_GROUP` = `ekf2`):
* В параметре `EKF2_AID_MASK` включены флажки `vision position fusion`, `vision yaw fusion`.
* Шум угла по зрению: `EKF2_EVA_NOISE` = 0.1 rad.
* Шум позиции по зрению: `EKF2_EVP_NOISE` = 0.1 m.
* `EKF2_EV_DELAY` = 0.
> **Hint** На данный момент для полета по маркерам рекомендуется использование **LPE**.
Для проверки правильности всех настроек можно [воспользоваться утилитой `selfcheck.py`](selfcheck.md).

54
docs/ru/javascript.md Normal file
View File

@@ -0,0 +1,54 @@
# Работа с ROS из браузера
С помощью библиотеки [`roslibjs`](http://wiki.ros.org/roslibjs) возможна работа со всеми ресурсами ROS (топики, сервисы, параметры) из JavaScript-кода внутри браузера, что позволяет создавать различные интерактивные браузерные приложения для коптера.
Все необходимое для работы с `roslibjs` предустановлено и настроено на [образе для RPi для Клевера](image.md).
## Пример
Пример HTML-кода страницы, работающей с `roslib.js`:
```html
<html>
<script src="js/roslib.js"></script>
<script type="text/javascript">
// Establish roslibjs connection
var ros = new ROSLIB.Ros({ url: 'ws://' + location.hostname + ':9090' });
ros.on('connection', function () {
// Connection callback
alert('Connected');
});
// Declare get_telemetry service client
var getTelemetry = new ROSLIB.Service({ ros: ros, name : '/get_telemetry', serviceType : 'clover/GetTelemetry' });
// Call get_telemetry
getTelemetry.callService(new ROSLIB.ServiceRequest({ frame_id: 'map' }), function(result) {
// Service respond callback
alert('Telemetry: ' + JSON.stringify(result));
});
// Subscribe to `/mavros/state` topic
var stateSub = new ROSLIB.Topic({ ros : ros, name : '/mavros/state', messageType : 'mavros_msgs/State' });
stateSub.subscribe(function(msg) {
// Topic message callback
console.log('State: ', msg);
});
</script>
</html>
```
[Взлет, посадка и все остальные операции](programming.md) могут быть осуществлены аналогичным образом.
Страница должна быть помещена в каталог `/home/pi/catkin_ws/src/clover/clover/www/`. После этого она станет доступна по адресу `http://192.168.11.1/<имя_страницы>.html`. При открытии страницы браузер должен показать окно с телеметрией дрона, а также постоянно выводить состояние полетного контроллера в консоль.
<img src="../assets/js-ros.png" class="center zoom"/>
Более подробную информацию смотрите в [туториале по `roslibjs`](http://wiki.ros.org/roslibjs/Tutorials/BasicRosFunctionality).
## Браузерная GCS
Смотрите также пример реализации упрощенной браузерной наземной станции (GCS) на Клевере по адресу http://192.168.11.1/gcs.html.
<img src="../assets/web-gcs.png" class="center zoom"/>

107
docs/ru/rc_flysky_a8s.md Normal file
View File

@@ -0,0 +1,107 @@
# Работа с приёмником Flysky FS-A8S
Приёмник Flysky FS-A8S совместим с пультами Flysky FS-i6 и FS-i6x. Связь с полётным контроллером может происходить как с использованием аналогового протокола PPM, так и при помощи цифровых протоколов S.Bus/i-Bus.
Для подключения к полётному контроллеру рекомендуется использовать протокол S.Bus.
## Изготовление кабеля для подключения к полётному контроллеру
> **Note** Если в вашем наборе уже есть кабель для подключения приёмника к полётному контроллеру, совместимому с вашим, переходите к [следующему этапу](#rc_bind).
1. Аккуратно извлеките жёлтый провод из коннектора, идущего к приёмнику. Для того, чтобы вытащить провод, приподнимите острым пинцетом замок коннектора:
<div class="image-group">
<img src="../assets/flysky_a8s/01_remove_cable_fs.png" width=300 class="zoom border" alt="a8s wire removal 1">
<img src="../assets/flysky_a8s/02_remove_cable_fs.png" width=300 class="zoom border" alt="a8s wire removal 2">
</div>
2. [При использовании полётного контроллера Pixracer] Извлеките 2 провода - зелёный и коричневый - из 5-пинового коннектора для полётного контроллера:
<div class="image-group">
<img src="../assets/flysky_a8s/03_remove_cable_pixracer.png" width=300 class="zoom border" alt="pixracer wire removal 1">
<img src="../assets/flysky_a8s/04_remove_cable_pixracer.png" width=300 class="zoom border" alt="pixracer wire removal 2">
</div>
3. [При использовании полётного контроллера COEX Pix] Извлеките зелёный (или синий, в зависимости от комплектации) провод из 4-пинового коннектора для полётного контроллера:
<div class="image-group">
<img src="../assets/flysky_a8s/05_remove_cable_coexpix.png" width=300 class="zoom border" alt="coexpix wire removal 1">
<img src="../assets/flysky_a8s/06_remove_cable_coexpix.png" width=300 class="zoom border" alt="coexpix wire removal 2">
</div>
4. С помощью бокорезов обрежьте концы кабелей с разъёмами Dupont (чёрными):
<div class="image-group">
<img src="../assets/flysky_a8s/07_wirecuts_1.png" width=300 class="zoom border" alt="wire cutting">
<img src="../assets/flysky_a8s/08_wirecuts_2.png" width=300 class="zoom border" alt="wire cuts">
</div>
5. Зачистите и залудите 5-7 мм провода с каждой стороны:
<img src="../assets/flysky_a8s/09_wirecuts_stripped.png" width=300 class="zoom border center" alt="tinning prep">
6. Наденьте термоусадочные трубки на провода:
<img src="../assets/flysky_a8s/10_heatshrink.png" width=300 class="zoom border center" alt="shrink tubing">
7. Спаяйте провода по следующей схеме:
* чёрный провод приёмника с чёрным проводом кабеля полётного контроллера;
* красный провод приёмника с красным проводом кабеля полётного контроллера;
* белый провод приёмника с белым (при использовании Pixracer) или жёлтым (при использовании COEX Pix) проводом кабеля полётного контроллера:
<img src="../assets/flysky_a8s/11_solder_scheme.png" width=300 class="zoom border center" alt="wire soldering">
8. Переместите термоусадочные трубки на места пайки и прогрейте их феном:
<img src="../assets/flysky_a8s/12_heatshrink_heat.png" width=300 class="zoom border center" alt="shrink tube heating">
9. Скрутите готовые кабели:
<img src="../assets/flysky_a8s/13_cable_twist.png" width=300 class="zoom border center" alt="twisted cables">
С помощью изготовленного кабеля подключите приёмник к полётному контроллеру к порту RC IN:
<div class="image-group">
<img src="../assets/flysky_a8s/14_pixracer_rcin.png" width=300 class="zoom border center" alt="pixracer connection">
<img src="../assets/flysky_a8s/14_coexpix_rcin.png" width=300 class="zoom border center" alt="coex pix connection">
</div>
> **Hint** Убедитесь, что провод, идущий в COEX Pix, подключен к порту RC IN:
<img src="../assets/coexpix-bottom.jpg" width=300 class="zoom border center" alt="coex pix pinout">
## Сопряжение приёмника с пультом {#rc_bind}
Для сопряжения приёмника с пультом:
1. Убедитесь, что полётный контроллер выключен.
2. Зажмите кнопку **BIND** на приёмнике:
<img src="../assets/flysky_a8s/15_bind_key.png" width=300 class="zoom border center" alt="bind key">
3. Включите полётный контроллер. Светодиод на приёмнике должен замигать с высокой частотой.
<img src="../assets/flysky_a8s/16_blink_fast.gif" width=300 class="zoom border center" alt="fast blink">
4. Зажмите клавишу **BIND KEY** на пульте и включите его. На пульте должно появиться сообщение **RX Binding...**
<img src="../assets/flysky_a8s/17_controller_rxbind.png" width=300 class="zoom border center" alt="rx binding">
5. Светодиод на приёмнике должен замигать с низкой частотой.
<img src="../assets/flysky_a8s/16_blink_slow.gif" width=300 class="zoom border center" alt="slow blink">
6. Выключите и включите пульт. Светодиод на приёмнике должен светиться непрерывно.
<img src="../assets/flysky_a8s/16_bind_indicator.png" width=300 class="zoom border center" alt="steady glow">
> **Note** Данный приёмник не передаёт телеметрию обратно на пульт. Это значит, что на экране пульта не будет отображаться информация об уровне сигнала и напряжении на приёмнике. Эта особенность приёмника не является неисправностью и не влияет на управление.
## Выбор режима приёмника
Откройте QGroundControl и подключите полётный контроллер к компьютеру. Откройте вкладку Radio:
![qgc radio pane](../assets/flysky_a8s/18_qgc_radio.png)
Если справа (под изображением пульта) не показано ни одного канала, зажмите кнопку **BIND** на приёмнике на 2 секунды. Должно появиться 18 каналов:
![qgc radio with channels](../assets/flysky_a8s/19_qgc_channels.png)