Compare commits

..

7 Commits

Author SHA1 Message Date
Oleg Kalachev
d715206fbe Enable strict warnings for aruco_pose 2022-06-02 16:32:30 +03:00
Oleg Kalachev
9fc07c9479 Remove unused in optical flow 2022-06-02 16:19:17 +03:00
Oleg Kalachev
075779d81f Mark unused in optical_flow 2022-06-02 16:17:04 +03:00
Oleg Kalachev
fcfa1c2a30 Mark unused variable in vpe_publisher 2022-06-02 16:08:49 +03:00
Oleg Kalachev
7f1d89110b Mark unused variables in simple_offboard 2022-06-02 14:39:24 +03:00
Oleg Kalachev
2f261c6a20 Enable all warnings, fail on warnings 2022-06-02 14:34:24 +03:00
Oleg Kalachev
673343f042 Enable -Wall and -Wextra for simple_offboard 2022-06-02 13:41:29 +03:00
105 changed files with 740 additions and 2523 deletions

1
.gitattributes vendored
View File

@@ -3,7 +3,6 @@ roslib.js linguist-vendored
eventemitter2.js linguist-vendored eventemitter2.js linguist-vendored
ros3d.js linguist-vendored ros3d.js linguist-vendored
three.min.js linguist-vendored three.min.js linguist-vendored
json-to-pretty-yaml.js linguist-vendored
aruco_pose/vendor/* linguist-vendored aruco_pose/vendor/* linguist-vendored
blockly/* linguist-vendored blockly/* linguist-vendored
highlight/* linguist-vendored highlight/* linguist-vendored

View File

@@ -16,36 +16,8 @@ jobs:
# docker run --rm -v $(pwd):/root/catkin_ws/src/clover ros:melodic-ros-base /root/catkin_ws/src/clover/builder/standalone-install.sh # docker run --rm -v $(pwd):/root/catkin_ws/src/clover ros:melodic-ros-base /root/catkin_ws/src/clover/builder/standalone-install.sh
noetic: noetic:
runs-on: ubuntu-latest runs-on: ubuntu-latest
container: ros:noetic-ros-base
defaults:
run:
working-directory: catkin_ws
shell: bash
steps: steps:
- uses: actions/checkout@v2 - uses: actions/checkout@v2
with: - name: Native Noetic build
path: catkin_ws/src/clover run: |
- name: Install requirements docker run --rm -v $(pwd):/root/catkin_ws/src/clover ros:noetic-ros-base /root/catkin_ws/src/clover/builder/standalone-install.sh
run: apt-get update && apt-get -y install python3-pip fakeroot python3-bloom debhelper dpkg-dev
- name: Install dependencies
run: rosdep update && rosdep install --from-paths src --ignore-src -y
- name: Install GeographicLib datasets
run: wget -qO- https://raw.githubusercontent.com/mavlink/mavros/master/mavros/scripts/install_geographiclib_datasets.sh | bash
- name: catkin_make
run: source /opt/ros/$ROS_DISTRO/setup.bash && catkin_make
- name: Run tests
run: source devel/setup.bash && catkin_make run_tests && catkin_test_results
- name: Build Debian packages
run: |
source devel/setup.bash
for file in `find . -name "package.xml"`; do
cd $(dirname ${file})
bloom-generate rosdebian --os-name ubuntu --os-version $(lsb_release -cs) --ros-distro $ROS_DISTRO
fakeroot debian/rules binary
cd -
done
- uses: actions/upload-artifact@v3
with:
name: debian-packages
path: catkin_ws/src/clover/*.deb
retention-days: 1

View File

@@ -4,21 +4,16 @@ on:
push: push:
branches: [ '*' ] branches: [ '*' ]
pull_request: pull_request:
branches: [ '*' ] branches: [ master ]
permissions:
contents: read
pages: write
id-token: write
defaults:
run:
shell: bash
jobs: jobs:
docs: docs:
runs-on: ubuntu-22.04 runs-on: ubuntu-18.04
steps: steps:
- name: Cancel previous runs
uses: styfle/cancel-workflow-action@0.9.1
with:
access_token: ${{ github.token }}
- uses: actions/checkout@v2 - uses: actions/checkout@v2
- name: Use Node.js - name: Use Node.js
uses: actions/setup-node@v1 uses: actions/setup-node@v1
@@ -63,23 +58,11 @@ jobs:
rm -f _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_ru.pdf -P _book/
wget --no-verbose https://clover.coex.tech/clover_en.pdf -P _book/ wget --no-verbose https://clover.coex.tech/clover_en.pdf -P _book/
- name: Upload artifact - name: Deploy
# if: ${{ github.event_name == 'push' && github.ref == 'refs/heads/master' }} uses: JamesIves/github-pages-deploy-action@4.1.3
uses: actions/upload-pages-artifact@v1 if: ${{ github.event_name == 'push' && github.ref == 'refs/heads/master' }}
with: with:
path: _book branch: gh-pages
folder: _book
deploy-docs: clean: true
if: ${{ github.event_name == 'push' && github.ref == 'refs/heads/master' }} single-commit: true # to avoid multiple copies of large pdf files
concurrency:
group: "pages"
cancel-in-progress: true
environment:
name: github-pages
url: ${{ steps.deployment.outputs.page_url }}
runs-on: ubuntu-latest
needs: docs
steps:
- name: Deploy to GitHub Pages
id: deployment
uses: actions/deploy-pages@v1

View File

@@ -20,7 +20,7 @@ Clover drone is used on a wide range of educational events, including [Copter Ha
Preconfigured image for Raspberry Pi with installed and configured software, ready to fly, is available [in the Releases section](https://github.com/CopterExpress/clover/releases). Preconfigured image for Raspberry Pi with installed and configured software, ready to fly, is available [in the Releases section](https://github.com/CopterExpress/clover/releases).
![GitHub Workflow Status](https://img.shields.io/github/actions/workflow/status/CopterExpress/clover/build-image.yaml?branch=master) ![GitHub Workflow Status](https://img.shields.io/github/workflow/status/CopterExpress/clover/CI)
![GitHub all releases](https://img.shields.io/github/downloads/CopterExpress/clover/total) ![GitHub all releases](https://img.shields.io/github/downloads/CopterExpress/clover/total)
Image features: Image features:

View File

@@ -4,6 +4,8 @@ project(aruco_pose)
## Compile as C++11, supported in ROS Kinetic and newer ## Compile as C++11, supported in ROS Kinetic and newer
add_compile_options(-std=c++11) add_compile_options(-std=c++11)
add_compile_options(-Wall -Wextra -Werror)
## Find catkin macros and libraries ## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages ## is used, also find other catkin packages
@@ -119,7 +121,6 @@ generate_messages(
## Generate dynamic reconfigure parameters in the 'cfg' folder ## Generate dynamic reconfigure parameters in the 'cfg' folder
generate_dynamic_reconfigure_options( generate_dynamic_reconfigure_options(
cfg/Detector.cfg cfg/Detector.cfg
cfg/Map.cfg
) )
################################### ###################################
@@ -251,5 +252,4 @@ if (CATKIN_ENABLE_TESTING)
add_rostest(test/test_node_failure.test) add_rostest(test/test_node_failure.test)
add_rostest(test/largemap.test) add_rostest(test/largemap.test)
add_rostest(test/crash_opencv.test) add_rostest(test/crash_opencv.test)
add_rostest(test/duplicate.test)
endif() endif()

View File

@@ -43,8 +43,7 @@ It's recommended to run it within the same nodelet manager with the camera nodel
* `~frame_id_prefix` (*string*) prefix for TF transforms names, marker's ID is appended (default: `aruco_`) * `~frame_id_prefix` (*string*) prefix for TF transforms names, marker's ID is appended (default: `aruco_`)
* `~length` (*double*) markers' sides length * `~length` (*double*) markers' sides length
* `~length_override` (*map*) lengths of markers with specified ids * `~length_override` (*map*) lengths of markers with specified ids
* `~known_vertical` (*string*) known vertical (Z axis) of all the markers as a frame * `~known_tilt` (*string*) known tilt (pitch and roll) of all the markers as a frame
* `~flip_vertical` flip vertical vector
### Topics ### Topics
@@ -72,12 +71,10 @@ It's recommended to run it within the same nodelet manager with the camera nodel
* `~map` path to text file with markers list * `~map` path to text file with markers list
* `~frame_id` published frame id (default: `aruco_map`) * `~frame_id` published frame id (default: `aruco_map`)
* `~known_vertical` known vertical (Z axis) of markers map as a frame * `~known_tilt` known tilt (pitch and roll) of markers map as a frame
* `~flip_vertical` flip vertical vector
* `~image_width` debug image width (default: 2000) * `~image_width` debug image width (default: 2000)
* `~image_height` debug image height (default: 2000) * `~image_height` debug image height (default: 2000)
* `~image_margin`  debug image margin (default: 200) * `~image_margin`  debug image margin (default: 200)
* `~image_axis` whether debug image should contain axis (default: true)
* `~dictionary` (*int*)  ArUco dictionary (default: 2) - should be the same as `dictionary` parameter of `aruco_detect` nodelet * `~dictionary` (*int*)  ArUco dictionary (default: 2) - should be the same as `dictionary` parameter of `aruco_detect` nodelet
Map file has one marker per line with the following line format: Map file has one marker per line with the following line format:

View File

@@ -1,14 +0,0 @@
#!/usr/bin/env python
PACKAGE = "aruco_pose"
from dynamic_reconfigure.parameter_generator_catkin import *
gen = ParameterGenerator()
gen.add("enabled", bool_t, 0, "if map detection enabled", True)
gen.add("map", str_t, 0, "full path for the map file")
gen.add("image_axis", bool_t, 0, "debug image axis", default=True)
exit(gen.generate(PACKAGE, "aruco_pose", "Map"))

View File

@@ -1,5 +1,5 @@
<?xml version="1.0"?> <?xml version="1.0"?>
<package format="3"> <package format="2">
<name>aruco_pose</name> <name>aruco_pose</name>
<version>0.23.0</version> <version>0.23.0</version>
<description>Positioning with ArUco markers</description> <description>Positioning with ArUco markers</description>
@@ -28,8 +28,6 @@
<depend>sensor_msgs</depend> <depend>sensor_msgs</depend>
<depend>rostest</depend> <depend>rostest</depend>
<depend>dynamic_reconfigure</depend> <depend>dynamic_reconfigure</depend>
<depend condition="$ROS_PYTHON_VERSION == 2">python-docopt</depend>
<depend condition="$ROS_PYTHON_VERSION == 3">python3-docopt</depend>
<test_depend>image_publisher</test_depend> <test_depend>image_publisher</test_depend>
<test_depend>ros_pytest</test_depend> <test_depend>ros_pytest</test_depend>

View File

@@ -71,12 +71,11 @@ private:
ros::Publisher markers_pub_, vis_markers_pub_; ros::Publisher markers_pub_, vis_markers_pub_;
ros::Subscriber map_markers_sub_; ros::Subscriber map_markers_sub_;
ros::ServiceServer set_markers_srv_; ros::ServiceServer set_markers_srv_;
bool estimate_poses_, send_tf_, flip_vertical_, auto_flip_, use_map_markers_; bool estimate_poses_, send_tf_, auto_flip_;
bool waiting_for_map_;
double length_; double length_;
ros::Duration transform_timeout_; ros::Duration transform_timeout_;
std::unordered_map<int, double> length_override_; std::unordered_map<int, double> length_override_;
std::string frame_id_prefix_, known_vertical_; std::string frame_id_prefix_, known_tilt_;
Mat camera_matrix_, dist_coeffs_; Mat camera_matrix_, dist_coeffs_;
aruco_pose::MarkerArray array_; aruco_pose::MarkerArray array_;
std::unordered_set<int> map_markers_ids_; std::unordered_set<int> map_markers_ids_;
@@ -96,8 +95,6 @@ public:
dictionary = nh_priv_.param("dictionary", 2); dictionary = nh_priv_.param("dictionary", 2);
estimate_poses_ = nh_priv_.param("estimate_poses", true); estimate_poses_ = nh_priv_.param("estimate_poses", true);
send_tf_ = nh_priv_.param("send_tf", true); send_tf_ = nh_priv_.param("send_tf", true);
use_map_markers_ = nh_priv_.param("use_map_markers", false);
waiting_for_map_ = use_map_markers_;
if (estimate_poses_ && !nh_priv_.getParam("length", length_)) { if (estimate_poses_ && !nh_priv_.getParam("length", length_)) {
NODELET_FATAL("can't estimate marker's poses as ~length parameter is not defined"); NODELET_FATAL("can't estimate marker's poses as ~length parameter is not defined");
ros::shutdown(); ros::shutdown();
@@ -105,8 +102,7 @@ public:
readLengthOverride(nh_priv_); readLengthOverride(nh_priv_);
transform_timeout_ = ros::Duration(nh_priv_.param("transform_timeout", 0.02)); transform_timeout_ = ros::Duration(nh_priv_.param("transform_timeout", 0.02));
known_vertical_ = nh_priv_.param("known_vertical", nh_priv_.param("known_tilt", std::string(""))); // known_tilt is an old name known_tilt_ = nh_priv_.param<std::string>("known_tilt", "");
flip_vertical_ = nh_priv_.param<bool>("flip_vertical", false);
auto_flip_ = nh_priv_.param("auto_flip", false); auto_flip_ = nh_priv_.param("auto_flip", false);
frame_id_prefix_ = nh_priv_.param<std::string>("frame_id_prefix", "aruco_"); frame_id_prefix_ = nh_priv_.param<std::string>("frame_id_prefix", "aruco_");
@@ -137,7 +133,6 @@ private:
void imageCallback(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr &cinfo) void imageCallback(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr &cinfo)
{ {
if (!enabled_) return; if (!enabled_) return;
if (waiting_for_map_) return;
Mat image = cv_bridge::toCvShare(msg, "bgr8")->image; Mat image = cv_bridge::toCvShare(msg, "bgr8")->image;
@@ -145,7 +140,7 @@ private:
vector<vector<cv::Point2f>> corners, rejected; vector<vector<cv::Point2f>> corners, rejected;
vector<cv::Vec3d> rvecs, tvecs; vector<cv::Vec3d> rvecs, tvecs;
vector<cv::Point3f> obj_points; vector<cv::Point3f> obj_points;
geometry_msgs::TransformStamped vertical; geometry_msgs::TransformStamped snap_to;
// Detect markers // Detect markers
cv::aruco::detectMarkers(image, dictionary_, corners, ids, parameters_, rejected); cv::aruco::detectMarkers(image, dictionary_, corners, ids, parameters_, rejected);
@@ -180,20 +175,18 @@ private:
} }
} }
if (!known_vertical_.empty()) { if (!known_tilt_.empty()) {
try { try {
vertical = tf_buffer_->lookupTransform(msg->header.frame_id, known_vertical_, snap_to = tf_buffer_->lookupTransform(msg->header.frame_id, known_tilt_,
msg->header.stamp, transform_timeout_); msg->header.stamp, transform_timeout_);
} catch (const tf2::TransformException& e) { } catch (const tf2::TransformException& e) {
NODELET_WARN_THROTTLE(5, "can't retrieve known vertical: %s", e.what()); NODELET_WARN_THROTTLE(5, "can't snap: %s", e.what());
} }
} }
} }
array_.markers.reserve(ids.size()); array_.markers.reserve(ids.size());
aruco_pose::Marker marker; aruco_pose::Marker marker;
vector<geometry_msgs::TransformStamped> transforms;
transforms.reserve(ids.size());
geometry_msgs::TransformStamped transform; geometry_msgs::TransformStamped transform;
transform.header.stamp = msg->header.stamp; transform.header.stamp = msg->header.stamp;
transform.header.frame_id = msg->header.frame_id; transform.header.frame_id = msg->header.frame_id;
@@ -206,38 +199,25 @@ private:
if (estimate_poses_) { if (estimate_poses_) {
fillPose(marker.pose, rvecs[i], tvecs[i]); fillPose(marker.pose, rvecs[i], tvecs[i]);
// apply known vertical (if enabled and vertical frame available) // snap orientation (if enabled and snap frame available)
if (!known_vertical_.empty() && !vertical.header.frame_id.empty()) { if (!known_tilt_.empty() && !snap_to.header.frame_id.empty()) {
applyVertical(marker.pose.orientation, vertical.transform.rotation, false, auto_flip_); snapOrientation(marker.pose.orientation, snap_to.transform.rotation, auto_flip_);
} }
// TODO: check IDs are unique
if (send_tf_) { if (send_tf_) {
transform.child_frame_id = getChildFrameId(ids[i]); transform.child_frame_id = getChildFrameId(ids[i]);
// check if such static transform is in the map // check if such static transform is in the map
if (map_markers_ids_.find(ids[i]) == map_markers_ids_.end()) { if (map_markers_ids_.find(ids[i]) == map_markers_ids_.end()) {
// check if a markers with that id is already added transform.transform.rotation = marker.pose.orientation;
bool send = true; fillTranslation(transform.transform.translation, tvecs[i]);
for (auto &t : transforms) { br_->sendTransform(transform);
if (t.child_frame_id == transform.child_frame_id) {
send = false;
break;
}
}
if (send) {
transform.transform.rotation = marker.pose.orientation;
fillTranslation(transform.transform.translation, tvecs[i]);
transforms.push_back(transform);
}
} }
} }
} }
array_.markers.push_back(marker); array_.markers.push_back(marker);
} }
if (send_tf_) {
br_->sendTransform(transforms);
}
} }
markers_pub_.publish(array_); markers_pub_.publish(array_);
@@ -400,13 +380,7 @@ private:
map_markers_ids_.clear(); map_markers_ids_.clear();
for (auto const& marker : msg.markers) { for (auto const& marker : msg.markers) {
map_markers_ids_.insert(marker.id); map_markers_ids_.insert(marker.id);
if (use_map_markers_) {
if (length_override_.find(marker.id) == length_override_.end()) {
length_override_[marker.id] = marker.length;
}
}
} }
waiting_for_map_ = false;
} }
void paramCallback(aruco_pose::DetectorConfig &config, uint32_t level) void paramCallback(aruco_pose::DetectorConfig &config, uint32_t level)

View File

@@ -19,13 +19,11 @@
#include <vector> #include <vector>
#include <fstream> #include <fstream>
#include <algorithm> #include <algorithm>
#include <memory>
#include <ros/ros.h> #include <ros/ros.h>
#include <nodelet/nodelet.h> #include <nodelet/nodelet.h>
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include <image_transport/image_transport.h> #include <image_transport/image_transport.h>
#include <cv_bridge/cv_bridge.h> #include <cv_bridge/cv_bridge.h>
#include <dynamic_reconfigure/server.h>
#include <tf/transform_datatypes.h> #include <tf/transform_datatypes.h>
#include <tf2_ros/buffer.h> #include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h> #include <tf2_ros/transform_listener.h>
@@ -43,7 +41,6 @@
#include <aruco_pose/MarkerArray.h> #include <aruco_pose/MarkerArray.h>
#include <aruco_pose/Marker.h> #include <aruco_pose/Marker.h>
#include <aruco_pose/MapConfig.h>
#include <opencv2/opencv.hpp> #include <opencv2/opencv.hpp>
#include <opencv2/aruco.hpp> #include <opencv2/aruco.hpp>
@@ -77,13 +74,10 @@ private:
tf2_ros::StaticTransformBroadcaster static_br_; tf2_ros::StaticTransformBroadcaster static_br_;
tf2_ros::Buffer tf_buffer_; tf2_ros::Buffer tf_buffer_;
tf2_ros::TransformListener tf_listener_{tf_buffer_}; tf2_ros::TransformListener tf_listener_{tf_buffer_};
std::shared_ptr<dynamic_reconfigure::Server<aruco_pose::MapConfig>> dyn_srv_;
bool enabled_ = true;
std::string type_;
visualization_msgs::MarkerArray vis_array_; visualization_msgs::MarkerArray vis_array_;
std::string known_vertical_, map_, markers_frame_, markers_parent_frame_; std::string known_tilt_, map_, markers_frame_, markers_parent_frame_;
int image_width_, image_height_, image_margin_; int image_width_, image_height_, image_margin_;
bool flip_vertical_, auto_flip_, image_axis_; bool auto_flip_, image_axis_;
public: public:
virtual void onInit() virtual void onInit()
@@ -102,10 +96,10 @@ public:
static_cast<cv::aruco::PREDEFINED_DICTIONARY_NAME>(nh_priv_.param("dictionary", 2))); static_cast<cv::aruco::PREDEFINED_DICTIONARY_NAME>(nh_priv_.param("dictionary", 2)));
camera_matrix_ = cv::Mat::zeros(3, 3, CV_64F); camera_matrix_ = cv::Mat::zeros(3, 3, CV_64F);
type_ = nh_priv_.param<std::string>("type", "map"); std::string type, map;
type = nh_priv_.param<std::string>("type", "map");
transform_.child_frame_id = nh_priv_.param<std::string>("frame_id", "aruco_map"); transform_.child_frame_id = nh_priv_.param<std::string>("frame_id", "aruco_map");
known_vertical_ = nh_priv_.param("known_vertical", nh_priv_.param("known_tilt", std::string(""))); // known_tilt is an old name known_tilt_ = nh_priv_.param<std::string>("known_tilt", "");
flip_vertical_ = nh_priv_.param<bool>("flip_vertical", false);
auto_flip_ = nh_priv_.param("auto_flip", false); auto_flip_ = nh_priv_.param("auto_flip", false);
image_width_ = nh_priv_.param("image_width" , 2000); image_width_ = nh_priv_.param("image_width" , 2000);
image_height_ = nh_priv_.param("image_height", 2000); image_height_ = nh_priv_.param("image_height", 2000);
@@ -116,13 +110,13 @@ public:
// createStripLine(); // createStripLine();
if (type_ == "map") { if (type == "map") {
map_ = nh_priv_.param<std::string>("map" , ""); param(nh_priv_, "map", map);
loadMap(map_); loadMap(map);
} else if (type_ == "gridboard") { } else if (type == "gridboard") {
createGridBoard(nh_priv_); createGridBoard(nh_priv_);
} else { } else {
NODELET_FATAL("unknown type: %s", type_.c_str()); NODELET_FATAL("unknown type: %s", type.c_str());
ros::shutdown(); ros::shutdown();
} }
@@ -130,7 +124,10 @@ public:
vis_markers_pub_ = nh_priv_.advertise<visualization_msgs::MarkerArray>("visualization", 1, true); vis_markers_pub_ = nh_priv_.advertise<visualization_msgs::MarkerArray>("visualization", 1, true);
debug_pub_ = it_priv.advertise("debug", 1); debug_pub_ = it_priv.advertise("debug", 1);
publishMap(); publishMarkersFrames();
publishMarkers();
publishMapImage();
vis_markers_pub_.publish(vis_array_);
image_sub_.subscribe(nh_, "image_raw", 1); image_sub_.subscribe(nh_, "image_raw", 1);
info_sub_.subscribe(nh_, "camera_info", 1); info_sub_.subscribe(nh_, "camera_info", 1);
@@ -139,12 +136,6 @@ public:
sync_.reset(new message_filters::Synchronizer<SyncPolicy>(SyncPolicy(10), image_sub_, info_sub_, markers_sub_)); sync_.reset(new message_filters::Synchronizer<SyncPolicy>(SyncPolicy(10), image_sub_, info_sub_, markers_sub_));
sync_->registerCallback(boost::bind(&ArucoMap::callback, this, _1, _2, _3)); sync_->registerCallback(boost::bind(&ArucoMap::callback, this, _1, _2, _3));
dyn_srv_ = std::make_shared<dynamic_reconfigure::Server<aruco_pose::MapConfig>>(nh_priv_);
dynamic_reconfigure::Server<aruco_pose::MapConfig>::CallbackType cb;
cb = std::bind(&ArucoMap::paramCallback, this, std::placeholders::_1, std::placeholders::_2);
dyn_srv_->setCallback(cb);
NODELET_INFO("ready"); NODELET_INFO("ready");
} }
@@ -152,9 +143,6 @@ public:
const sensor_msgs::CameraInfoConstPtr& cinfo, const sensor_msgs::CameraInfoConstPtr& cinfo,
const aruco_pose::MarkerArrayConstPtr& markers) const aruco_pose::MarkerArrayConstPtr& markers)
{ {
if (!enabled_) return;
if (markers->markers.empty()) return; // map not loaded
int valid = 0; int valid = 0;
int count = markers->markers.size(); int count = markers->markers.size();
std::vector<int> ids; std::vector<int> ids;
@@ -178,7 +166,7 @@ public:
corners.push_back(marker_corners); corners.push_back(marker_corners);
} }
if (known_vertical_.empty()) { if (known_tilt_.empty()) {
// simple estimation // simple estimation
valid = cv::aruco::estimatePoseBoard(corners, ids, board_, camera_matrix_, dist_coeffs_, valid = cv::aruco::estimatePoseBoard(corners, ids, board_, camera_matrix_, dist_coeffs_,
rvec, tvec, false); rvec, tvec, false);
@@ -192,7 +180,7 @@ public:
} else { } else {
Mat obj_points, img_points; Mat obj_points, img_points;
// estimation with known vertical // estimation with "snapping"
cv::aruco::getBoardObjectAndImagePoints(board_, corners, ids, obj_points, img_points); cv::aruco::getBoardObjectAndImagePoints(board_, corners, ids, obj_points, img_points);
if (obj_points.empty()) goto publish_debug; if (obj_points.empty()) goto publish_debug;
@@ -204,11 +192,11 @@ public:
fillTransform(transform_.transform, rvec, tvec); fillTransform(transform_.transform, rvec, tvec);
try { try {
geometry_msgs::TransformStamped vertical = tf_buffer_.lookupTransform(markers->header.frame_id, geometry_msgs::TransformStamped snap_to = tf_buffer_.lookupTransform(markers->header.frame_id,
known_vertical_, markers->header.stamp, ros::Duration(0.02)); known_tilt_, markers->header.stamp, ros::Duration(0.02));
applyVertical(transform_.transform.rotation, vertical.transform.rotation, flip_vertical_, auto_flip_); snapOrientation(transform_.transform.rotation, snap_to.transform.rotation, auto_flip_);
} catch (const tf2::TransformException& e) { } catch (const tf2::TransformException& e) {
NODELET_WARN_THROTTLE(1, "can't retrieve known vertical: %s", e.what()); NODELET_WARN_THROTTLE(1, "can't snap: %s", e.what());
} }
geometry_msgs::TransformStamped shift; geometry_msgs::TransformStamped shift;
@@ -280,17 +268,9 @@ publish_debug:
std::ifstream f(filename); std::ifstream f(filename);
std::string line; std::string line;
clearMarkers();
if (map_ == "") {
NODELET_INFO("No map loaded");
return;
}
if (!f.good()) { if (!f.good()) {
NODELET_ERROR("%s - %s", strerror(errno), filename.c_str()); NODELET_FATAL("%s - %s", strerror(errno), filename.c_str());
map_ = ""; ros::shutdown();
return;
} }
while (std::getline(f, line)) { while (std::getline(f, line)) {
@@ -316,10 +296,9 @@ publish_debug:
s.putback(first); s.putback(first);
} else { } else {
// Probably garbage data; inform user and throw an exception, possibly killing nodelet // Probably garbage data; inform user and throw an exception, possibly killing nodelet
NODELET_ERROR("Malformed input: %s", line.c_str()); NODELET_FATAL("Malformed input: %s", line.c_str());
map_ = ""; ros::shutdown();
clearMarkers(); throw std::runtime_error("Malformed input");
return;
} }
if (!(s >> id >> length >> x >> y)) { if (!(s >> id >> length >> x >> y)) {
@@ -350,14 +329,6 @@ publish_debug:
NODELET_INFO("loading %s complete (%d markers)", filename.c_str(), static_cast<int>(board_->ids.size())); NODELET_INFO("loading %s complete (%d markers)", filename.c_str(), static_cast<int>(board_->ids.size()));
} }
void publishMap()
{
publishMarkersFrames();
publishMarkers();
publishMapImage();
vis_markers_pub_.publish(vis_array_);
}
void createGridBoard(ros::NodeHandle& nh) void createGridBoard(ros::NodeHandle& nh)
{ {
NODELET_INFO("generate gridboard"); NODELET_INFO("generate gridboard");
@@ -399,15 +370,6 @@ publish_debug:
} }
} }
void clearMarkers()
{
board_->ids.clear();
board_->objPoints.clear();
markers_.markers.clear();
vis_array_.markers.clear();
markers_transforms_.clear();
}
// void createStripLine() // void createStripLine()
// { // {
// visualization_msgs::Marker marker; // visualization_msgs::Marker marker;
@@ -504,7 +466,7 @@ publish_debug:
vis_marker.pose.position.x = x; vis_marker.pose.position.x = x;
vis_marker.pose.position.y = y; vis_marker.pose.position.y = y;
vis_marker.pose.position.z = z; vis_marker.pose.position.z = z;
tf::quaternionTFToMsg(q, vis_marker.pose.orientation); tf::quaternionTFToMsg(q, marker.pose.orientation);
vis_marker.frame_locked = true; vis_marker.frame_locked = true;
vis_array_.markers.push_back(vis_marker); vis_array_.markers.push_back(vis_marker);
@@ -547,22 +509,6 @@ publish_debug:
msg.image = image; msg.image = image;
img_pub_.publish(msg.toImageMsg()); img_pub_.publish(msg.toImageMsg());
} }
void paramCallback(aruco_pose::MapConfig &config, uint32_t level)
{
// https://github.com/CopterExpress/clover/commit/2cd334c474e3ed04ef65ca1ba7f08ab535a3dc6d#diff-942723f9452c398ae93f1a91427f9a7b614be5e5871f8a3e590f324d804f0d58R356
enabled_ = config.enabled;
if (type_ == "map" && config.map != map_) {
map_ = config.map;
loadMap(map_);
publishMap();
}
if (config.image_axis != image_axis_) {
image_axis_ = config.image_axis;
publishMapImage();
}
}
}; };
PLUGINLIB_EXPORT_CLASS(ArucoMap, nodelet::Nodelet) PLUGINLIB_EXPORT_CLASS(ArucoMap, nodelet::Nodelet)

View File

@@ -106,25 +106,26 @@ inline bool isFlipped(tf::Quaternion& q)
return (abs(pitch) > M_PI / 2) || (abs(roll) > M_PI / 2); return (abs(pitch) > M_PI / 2) || (abs(roll) > M_PI / 2);
} }
/* Apply a vertical to an orientation */ /* Set roll and pitch from "from" to "to", keeping yaw */
inline void applyVertical(geometry_msgs::Quaternion& orientation, const geometry_msgs::Quaternion& vertical, inline void snapOrientation(geometry_msgs::Quaternion& to, const geometry_msgs::Quaternion& from, bool auto_flip = false)
bool flip_vertical = false, bool auto_flip = false) // editorconfig-checker-disable-line
{ {
tf::Quaternion _vertical, _orientation; tf::Quaternion _from, _to;
tf::quaternionMsgToTF(vertical, _vertical); tf::quaternionMsgToTF(from, _from);
tf::quaternionMsgToTF(orientation, _orientation); tf::quaternionMsgToTF(to, _to);
if (flip_vertical || (auto_flip && !isFlipped(_orientation))) { if (auto_flip) {
static const tf::Quaternion flip = tf::createQuaternionFromRPY(M_PI, 0, 0); if (!isFlipped(_from)) {
_vertical *= flip; // flip vertical static const tf::Quaternion flip = tf::createQuaternionFromRPY(M_PI, 0, 0);
_from *= flip; // flip "from"
}
} }
auto diff = tf::Matrix3x3(_orientation).transposeTimes(tf::Matrix3x3(_vertical)); auto diff = tf::Matrix3x3(_to).transposeTimes(tf::Matrix3x3(_from));
double _, yaw; double _, yaw;
diff.getRPY(_, _, yaw); diff.getRPY(_, _, yaw);
auto q = tf::createQuaternionFromRPY(0, 0, -yaw); auto q = tf::createQuaternionFromRPY(0, 0, -yaw);
_vertical = _vertical * q; // set yaw from orientation to vertical _from = _from * q; // set yaw from "to" to "from"
tf::quaternionTFToMsg(_vertical, orientation); // set vertical to orientation tf::quaternionTFToMsg(_from, to); // set "from" to "to"
} }
inline void transformToPose(const geometry_msgs::Transform& transform, geometry_msgs::Pose& pose) inline void transformToPose(const geometry_msgs::Transform& transform, geometry_msgs::Pose& pose)

View File

@@ -6,7 +6,7 @@ import tf2_geometry_msgs
from geometry_msgs.msg import PoseWithCovarianceStamped from geometry_msgs.msg import PoseWithCovarianceStamped
from sensor_msgs.msg import Image from sensor_msgs.msg import Image
from aruco_pose.msg import MarkerArray from aruco_pose.msg import MarkerArray
from visualization_msgs.msg import MarkerArray as VisMarkerArray, Marker as VisMarker from visualization_msgs.msg import MarkerArray as VisMarkerArray
@pytest.fixture @pytest.fixture
@@ -199,36 +199,6 @@ def test_map_markers(node):
def test_map_visualization(node): def test_map_visualization(node):
vis = rospy.wait_for_message('aruco_map/visualization', VisMarkerArray, timeout=5) vis = rospy.wait_for_message('aruco_map/visualization', VisMarkerArray, timeout=5)
assert len(vis.markers) == 7
assert vis.markers[0].header.frame_id == 'aruco_map'
assert vis.markers[0].type == VisMarker.CUBE
assert vis.markers[0].action == VisMarker.ADD
assert vis.markers[0].pose.position.x == 0
assert vis.markers[0].pose.position.y == 0
assert vis.markers[0].pose.position.z == 0
assert vis.markers[0].pose.orientation.x == 0
assert vis.markers[0].pose.orientation.y == 0
assert vis.markers[0].pose.orientation.z == 0
assert vis.markers[0].pose.orientation.w == 1
assert vis.markers[0].scale.x == approx(0.33)
assert vis.markers[0].scale.y == approx(0.33)
assert vis.markers[0].scale.z == approx(0.001)
assert vis.markers[1].pose.position.x == 1
assert vis.markers[1].pose.position.y == 0
assert vis.markers[1].pose.position.z == 0
assert vis.markers[1].pose.orientation.x == 0
assert vis.markers[1].pose.orientation.y == 0
assert vis.markers[1].pose.orientation.z == 0
assert vis.markers[1].pose.orientation.w == 1
# non-zero yaw marker:
assert vis.markers[4].scale.x == approx(0.5)
assert vis.markers[4].pose.position.x == approx(0.5)
assert vis.markers[4].pose.position.y == 2
assert vis.markers[4].pose.position.z == 0
assert vis.markers[4].pose.orientation.x == 0
assert vis.markers[4].pose.orientation.y == 0
assert vis.markers[4].pose.orientation.z == approx(0.5646424733950354)
assert vis.markers[4].pose.orientation.w == approx(0.8253356149096783)
def test_map_debug(node): def test_map_debug(node):
img = rospy.wait_for_message('aruco_map/debug', Image, timeout=5) img = rospy.wait_for_message('aruco_map/debug', Image, timeout=5)

Binary file not shown.

Before

Width:  |  Height:  |  Size: 62 KiB

View File

@@ -1,8 +0,0 @@
import pytest
import subprocess
def test_no_tf_repeated_data():
# `/rosout` acts weirdly inside rostest, so using a subprocess
cmd = """python -c 'import rospy, tf; rospy.init_node("foo"); listener = tf.TransformListener(); rospy.sleep(2)'"""
output = str(subprocess.check_output(cmd, shell=True, stderr=subprocess.STDOUT))
assert 'TF_REPEATED_DATA' not in output, 'TF_REPEATED_DATA was logged on duplicate markers'

View File

@@ -1,21 +0,0 @@
<launch>
<node pkg="image_publisher" type="image_publisher" name="main_camera" args="$(find aruco_pose)/test/duplicate.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" args="manager" required="true"/>
<node pkg="nodelet" clear_params="true" type="nodelet" name="aruco_detect" args="load aruco_pose/aruco_detect nodelet_manager" required="true">
<remap from="image_raw" to="main_camera/image_raw"/>
<remap from="camera_info" to="main_camera/camera_info"/>
<param name="length" value="0.33"/>
<param name="estimate_poses" value="true"/>
<param name="send_tf" value="true"/>
<param name="cornerRefinementMethod" value="1"/>
</node>
<param name="test_module" value="$(find aruco_pose)/test/duplicate.py"/>
<test test-name="aruco_pose_test" pkg="ros_pytest" type="ros_pytest_runner"/>
</launch>

View File

@@ -2,7 +2,6 @@ import rospy
import pytest import pytest
from visualization_msgs.msg import MarkerArray as VisMarkerArray from visualization_msgs.msg import MarkerArray as VisMarkerArray
from aruco_pose.msg import MarkerArray
@pytest.fixture @pytest.fixture
@@ -10,5 +9,5 @@ def node():
return rospy.init_node('aruco_pose_test', anonymous=True) return rospy.init_node('aruco_pose_test', anonymous=True)
def test_node_failure(node): def test_node_failure(node):
assert rospy.wait_for_message('aruco_map/visualization', VisMarkerArray, timeout=5).markers == [] with pytest.raises(rospy.exceptions.ROSException):
assert rospy.wait_for_message('aruco_map/map', MarkerArray, timeout=5).markers == [] rospy.wait_for_message('aruco_map/visualization', VisMarkerArray, timeout=5)

View File

@@ -151,9 +151,6 @@ catkin_make run_tests #&& catkin_test_results
echo_stamp "Change permissions for catkin_ws" echo_stamp "Change permissions for catkin_ws"
chown -Rf pi:pi /home/pi/catkin_ws chown -Rf pi:pi /home/pi/catkin_ws
echo_stamp "Update www"
sudo -u pi sh -c ". devel/setup.sh && rosrun clover www"
echo_stamp "Make \$HOME/examples symlink" echo_stamp "Make \$HOME/examples symlink"
ln -s "$(catkin_find clover examples --first-only)" /home/pi ln -s "$(catkin_find clover examples --first-only)" /home/pi
chown -Rf pi:pi /home/pi/examples chown -Rf pi:pi /home/pi/examples

View File

@@ -2,7 +2,6 @@
# validate all required modules installed # validate all required modules installed
import os
import rospy import rospy
from geometry_msgs.msg import PoseStamped from geometry_msgs.msg import PoseStamped
from sensor_msgs.msg import Range, BatteryState from sensor_msgs.msg import Range, BatteryState
@@ -23,7 +22,6 @@ from clover.srv import GetTelemetry, Navigate, NavigateGlobal, SetPosition, SetV
from led_msgs.srv import SetLEDs from led_msgs.srv import SetLEDs
from led_msgs.msg import LEDStateArray, LEDState from led_msgs.msg import LEDStateArray, LEDState
from aruco_pose.msg import Marker, MarkerArray, Point2D from aruco_pose.msg import Marker, MarkerArray, Point2D
from clover import long_callback
import dynamic_reconfigure.client import dynamic_reconfigure.client
@@ -33,12 +31,9 @@ import tf2_geometry_msgs
import VL53L1X import VL53L1X
import pymavlink import pymavlink
from pymavlink import mavutil from pymavlink import mavutil
import rpi_ws281x
import pigpio
# from espeak import espeak # from espeak import espeak
from pyzbar import pyzbar from pyzbar import pyzbar
import docopt
print(cv2.getBuildInformation()) print(cv2.getBuildInformation())
if not os.environ.get('VM'):
import rpi_ws281x
import pigpio

View File

@@ -6,10 +6,16 @@ set -ex
# validate required software is installed # validate required software is installed
python --version
python2 --version python2 --version
python3 --version python3 --version
ipython --version
ipython3 --version ipython3 --version
# ptvsd does not have a stand-alone binary
python -m ptvsd --version
python3 -m ptvsd --version
node -v node -v
npm -v npm -v
@@ -19,77 +25,42 @@ lsof -v
git --version git --version
vim --version vim --version
pip --version pip --version
pip2 --version
pip3 --version pip3 --version
tcpdump --version tcpdump --version
monkey --version monkey --version
pigpiod -v
i2cdetect -V
butterfly -h
# espeak --version # espeak --version
mjpg_streamer --version
systemctl --version systemctl --version
if [ -z $VM ]; then
# rpi only software
python --version
ipython --version
pip2 --version
# `python` is python2 for now
[[ $(python -c 'import sys;print(sys.version_info.major)') == "2" ]]
# ptvsd does not have a stand-alone binary
python -m ptvsd --version
python3 -m ptvsd --version
pigpiod -v
i2cdetect -V
butterfly -h
mjpg_streamer --version
fi
# ros stuff # ros stuff
roscore -h roscore -h
rosversion clover rosversion clover
rosversion aruco_pose rosversion aruco_pose
rosversion vl53l1x
rosversion mavros rosversion mavros
rosversion mavros_extras rosversion mavros_extras
rosversion ws281x rosversion ws281x
rosversion led_msgs rosversion led_msgs
rosversion dynamic_reconfigure rosversion dynamic_reconfigure
rosversion tf2_web_republisher rosversion tf2_web_republisher
rosversion rosbridge_server rosversion compressed_image_transport
rosversion rosbridge_suite
rosversion rosserial
rosversion usb_cam rosversion usb_cam
rosversion cv_camera rosversion cv_camera
rosversion web_video_server rosversion web_video_server
rosversion rosshow
rosversion nodelet rosversion nodelet
rosversion image_view rosversion image_view
[[ $(rosversion ws281x) == "0.0.13" ]] # validate some versions
[[ $(rosversion cv_camera) == "0.5.1" ]] # patched version with init fix
if [ -z $VM ]; then [[ $(rosversion ws281x) == "0.0.12" ]]
rosversion compressed_image_transport
rosversion rosshow
rosversion vl53l1x
rosversion rosserial
[[ $(rosversion cv_camera) == "0.5.1" ]] # patched version with init fix
fi
# determine user home directory
[ $VM ] && H="/home/clover" || H="/home/pi"
# test basic ros tool work
source $H/catkin_ws/devel/setup.bash
roscd
rosrun
rosmsg
rossrv
rosnode || [ $? -eq 64 ] # usage output code is 64
rostopic || [ $? -eq 64 ]
rosservice || [ $? -eq 64 ]
rosparam
roslaunch -h
# validate examples are present # validate examples are present
[[ $(ls $H/examples/*) ]] [[ $(ls /home/pi/examples/*) ]]
# validate web tools present
[ -d $H/.ros/www ]
[ "$(readlink $H/.ros/www/clover)" = "$H/catkin_ws/src/clover/clover/www" ]
[ "$(readlink $H/.ros/www/clover_blocks)" = "$H/catkin_ws/src/clover/clover_blocks/www" ]

View File

@@ -4,6 +4,8 @@ project(clover)
## Compile as C++11, supported in ROS Kinetic and newer ## Compile as C++11, supported in ROS Kinetic and newer
add_compile_options(-std=c++11) add_compile_options(-std=c++11)
add_compile_options(-Wall -Wextra -Werror)
## Find catkin macros and libraries ## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages ## is used, also find other catkin packages
@@ -17,7 +19,6 @@ find_package(catkin REQUIRED COMPONENTS
message_generation message_generation
geometry_msgs geometry_msgs
sensor_msgs sensor_msgs
led_msgs
geographic_msgs geographic_msgs
tf tf
tf2 tf2
@@ -53,7 +54,7 @@ find_package(OpenCV ${_opencv_version} REQUIRED
## Uncomment this if the package has a setup.py. This macro ensures ## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed ## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
catkin_python_setup() # catkin_python_setup()
################################################ ################################################
## Declare ROS messages, services and actions ## ## Declare ROS messages, services and actions ##
@@ -80,10 +81,11 @@ catkin_python_setup()
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
## Generate messages in the 'msg' folder ## Generate messages in the 'msg' folder
add_message_files( # add_message_files(
FILES # FILES
State.msg # Message1.msg
) # Message2.msg
# )
## Generate services in the 'srv' folder ## Generate services in the 'srv' folder
add_service_files( add_service_files(
@@ -91,9 +93,6 @@ add_service_files(
GetTelemetry.srv GetTelemetry.srv
Navigate.srv Navigate.srv
NavigateGlobal.srv NavigateGlobal.srv
SetAltitude.srv
SetYaw.srv
SetYawRate.srv
SetPosition.srv SetPosition.srv
SetVelocity.srv SetVelocity.srv
SetAttitude.srv SetAttitude.srv
@@ -308,5 +307,4 @@ endif()
if (CATKIN_ENABLE_TESTING) if (CATKIN_ENABLE_TESTING)
find_package(rostest REQUIRED) find_package(rostest REQUIRED)
add_rostest(test/basic.test) add_rostest(test/basic.test)
add_rostest(test/offboard.test)
endif() endif()

View File

@@ -1,64 +0,0 @@
# Information: https://clover.coex.tech/camera
# Example on basic working with the camera and image processing:
# - cuts out a central square from the camera image;
# - publishes this cropped image to the topic `/cv/center`;
# - computes the average color of it;
# - prints its name to the console.
import rospy
import cv2
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
from clover import long_callback
rospy.init_node('cv')
bridge = CvBridge()
printed_color = None
center_pub = rospy.Publisher('~center', Image, queue_size=1)
def get_color_name(h):
if h < 15: return 'red'
elif h < 30: return 'orange'
elif h < 60: return 'yellow'
elif h < 90: return 'green'
elif h < 120: return 'cyan'
elif h < 150: return 'blue'
elif h < 170: return 'magenta'
else: return 'red'
@long_callback
def image_callback(msg):
img = bridge.imgmsg_to_cv2(msg, 'bgr8')
# convert to HSV to work with color hue
img_hsv = cv2.cvtColor(img, cv2.COLOR_BGR2HSV)
# cut out a central square
w = img.shape[1]
h = img.shape[0]
r = 20
center = img_hsv[h // 2 - r:h // 2 + r, w // 2 - r:w // 2 + r]
# compute and print the average hue
mean_hue = center[:, :, 0].mean()
color = get_color_name(mean_hue)
global printed_color
if color != printed_color:
print(color)
printed_color = color
# publish the cropped image
center = cv2.cvtColor(center, cv2.COLOR_HSV2BGR)
center_pub.publish(bridge.cv2_to_imgmsg(center, 'bgr8'))
# process every frame:
image_sub = rospy.Subscriber('main_camera/image_raw', Image, image_callback, queue_size=1)
# process 5 frames per second:
# image_sub = rospy.Subscriber('main_camera/image_raw_throttled', Image, image_callback, queue_size=1)
rospy.spin()

View File

@@ -16,8 +16,11 @@ set_attitude = rospy.ServiceProxy('set_attitude', srv.SetAttitude)
set_rates = rospy.ServiceProxy('set_rates', srv.SetRates) set_rates = rospy.ServiceProxy('set_rates', srv.SetRates)
land = rospy.ServiceProxy('land', Trigger) land = rospy.ServiceProxy('land', Trigger)
def navigate_wait(x=0, y=0, z=0, yaw=math.nan, speed=0.5, frame_id='body', tolerance=0.2, auto_arm=False): def navigate_wait(x=0, y=0, z=0, yaw=float('nan'), yaw_rate=0, speed=0.5, \
res = navigate(x=x, y=y, z=z, yaw=yaw, speed=speed, frame_id=frame_id, auto_arm=auto_arm) 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: if not res.success:
return res return res

View File

@@ -18,9 +18,8 @@
<remap from="map_markers" to="aruco_map/map"/> <remap from="map_markers" to="aruco_map/map"/>
<param name="estimate_poses" value="true"/> <param name="estimate_poses" value="true"/>
<param name="send_tf" value="true"/> <param name="send_tf" value="true"/>
<param name="use_map_markers" value="true"/> <param name="known_tilt" value="map" if="$(eval placement == 'floor')"/>
<param name="known_vertical" value="map" if="$(eval placement == 'floor' or placement == 'ceiling')"/> <param name="known_tilt" value="map_flipped" if="$(eval placement == 'ceiling')"/>
<param name="flip_vertical" value="true" if="$(eval placement == 'ceiling')"/>
<param name="length" value="$(arg length)"/> <param name="length" value="$(arg length)"/>
<param name="transform_timeout" value="0.1"/> <param name="transform_timeout" value="0.1"/>
<!-- aruco detector parameters --> <!-- aruco detector parameters -->
@@ -36,8 +35,8 @@
<remap from="camera_info" to="main_camera/camera_info"/> <remap from="camera_info" to="main_camera/camera_info"/>
<remap from="markers" to="aruco_detect/markers"/> <remap from="markers" to="aruco_detect/markers"/>
<param name="map" value="$(find aruco_pose)/map/$(arg map)"/> <param name="map" value="$(find aruco_pose)/map/$(arg map)"/>
<param name="known_vertical" value="map" if="$(eval placement == 'floor' or placement == 'ceiling')"/> <param name="known_tilt" value="map" if="$(eval placement == 'floor')"/>
<param name="flip_vertical" value="true" if="$(eval placement == 'ceiling')"/> <param name="known_tilt" value="map_flipped" if="$(eval placement == 'ceiling')"/>
<param name="image_axis" value="true"/> <param name="image_axis" value="true"/>
<param name="frame_id" value="aruco_map_detected" if="$(arg aruco_vpe)"/> <param name="frame_id" value="aruco_map_detected" if="$(arg aruco_vpe)"/>
<param name="frame_id" value="aruco_map" unless="$(arg aruco_vpe)"/> <param name="frame_id" value="aruco_map" unless="$(arg aruco_vpe)"/>

View File

@@ -12,7 +12,7 @@
<arg name="led" default="true"/> <arg name="led" default="true"/>
<arg name="blocks" default="false"/> <arg name="blocks" default="false"/>
<arg name="rc" default="false"/> <arg name="rc" default="false"/>
<arg name="force_init" default="true"/> <!-- force estimator to init by publishing zero pose --> <arg name="force_init" value="true"/> <!-- force estimator to init by publishing zero pose -->
<arg name="simulator" default="false"/> <!-- flag that we are operating on a simulated drone --> <arg name="simulator" default="false"/> <!-- flag that we are operating on a simulated drone -->
@@ -45,9 +45,10 @@
<remap from="camera_info" to="main_camera/camera_info"/> <remap from="camera_info" to="main_camera/camera_info"/>
<param name="calc_flow_gyro" value="true"/> <param name="calc_flow_gyro" value="true"/>
<param name="roi_rad" value="0.8"/> <param name="roi_rad" value="0.8"/>
<param name="disable_on_vpe" value="true"/>
</node> </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 --> <!-- simplified offboard control -->
<node name="simple_offboard" pkg="clover" type="simple_offboard" output="screen" clear_params="true"> <node name="simple_offboard" pkg="clover" type="simple_offboard" output="screen" clear_params="true">
<param name="reference_frames/main_camera_optical" value="map"/> <param name="reference_frames/main_camera_optical" value="map"/>
@@ -85,4 +86,8 @@
<param name="use_fake_gcs" value="false"/> <param name="use_fake_gcs" value="false"/>
</node> </node>
<!-- Update static directory -->
<node pkg="roswww_static" name="roswww_static" type="main.py" clear_params="true">
<param name="default_package" value="clover"/>
</node>
</launch> </launch>

View File

@@ -4,8 +4,6 @@
<arg name="direction_z" default="down"/> <!-- direction the camera points: down, up --> <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 --> <arg name="direction_y" default="backward"/> <!-- direction the camera cable points: backward, forward -->
<arg name="device" default="/dev/video0"/> <!-- v4l2 device --> <arg name="device" default="/dev/video0"/> <!-- v4l2 device -->
<arg name="throttled_topic" default="true"/> <!-- enable throttled image topic -->
<arg name="throttled_topic_rate" default="5.0"/> <!-- throttled image topic rate -->
<arg name="simulator" default="false"/> <arg name="simulator" default="false"/>
<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 == '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"/>
@@ -45,8 +43,4 @@
<node pkg="clover" type="camera_markers" ns="main_camera" name="main_camera_markers"> <node pkg="clover" type="camera_markers" ns="main_camera" name="main_camera_markers">
<param name="scale" value="3.0"/> <param name="scale" value="3.0"/>
</node> </node>
<!-- image topic throttled -->
<node pkg="topic_tools" name="main_camera_throttle" type="throttle" ns="main_camera"
args="messages image_raw $(arg throttled_topic_rate) image_raw_throttled" if="$(arg throttled_topic)"/>
</launch> </launch>

View File

@@ -1,5 +1,5 @@
<launch> <launch>
<arg name="fcu_conn" default="usb"/> <!-- options: usb, uart, tcp, udp, sitl, hitl --> <arg name="fcu_conn" default="usb"/> <!-- options: usb, uart, tcp, udp, sitl -->
<arg name="fcu_ip" default="127.0.0.1"/> <arg name="fcu_ip" default="127.0.0.1"/>
<arg name="fcu_sys_id" default="1"/> <arg name="fcu_sys_id" default="1"/>
<arg name="gcs_bridge" default="tcp"/> <arg name="gcs_bridge" default="tcp"/>
@@ -23,9 +23,6 @@
<!-- sitl since PX4 1.9.0 --> <!-- sitl since PX4 1.9.0 -->
<param name="fcu_url" value="udp://@$(arg fcu_ip):14580" if="$(eval fcu_conn == 'sitl')"/> <param name="fcu_url" value="udp://@$(arg fcu_ip):14580" if="$(eval fcu_conn == 'sitl')"/>
<!-- hitl connection (to gazebo_mavlink_interface plugin) -->
<param name="fcu_url" value="udp://$(arg fcu_ip):14540@" if="$(eval fcu_conn == 'hitl')"/>
<!-- set target_system_id --> <!-- set target_system_id -->
<param name="target_system_id" value="$(arg fcu_sys_id)" /> <param name="target_system_id" value="$(arg fcu_sys_id)" />

View File

@@ -1,4 +0,0 @@
<launch>
<!-- shortcut for running the simulation (`roslaunch clover simulator.launch`) -->
<include file="$(find clover_simulation)/launch/simulator.launch"/>
</launch>

View File

@@ -1,38 +0,0 @@
uint8 MODE_NONE = 0
uint8 MODE_NAVIGATE = 1
uint8 MODE_NAVIGATE_GLOBAL = 2
uint8 MODE_POSITION = 3
uint8 MODE_VELOCITY = 4
uint8 MODE_ATTITUDE = 5
uint8 MODE_RATES = 6
uint8 YAW_MODE_YAW = 0
uint8 YAW_MODE_YAW_RATE = 1
uint8 YAW_MODE_YAW_TOWARDS = 2
# type of offboard control
uint8 mode
uint8 yaw_mode
# targets
float32 x
float32 y
float32 z
float32 speed
float32 lat
float32 lon
float32 vx
float32 vy
float32 vz
float32 roll
float32 pitch
float32 yaw
float32 roll_rate
float32 pitch_rate
float32 yaw_rate
float32 thrust
# frames of reference
string xy_frame_id
string z_frame_id
string yaw_frame_id

View File

@@ -37,13 +37,12 @@
<depend>rosbridge_server</depend> <depend>rosbridge_server</depend>
<depend>web_video_server</depend> <depend>web_video_server</depend>
<depend>tf2_web_republisher</depend> <depend>tf2_web_republisher</depend>
<depend>libxml2</depend>
<depend>libxslt</depend>
<depend condition="$ROS_PYTHON_VERSION == 2">python-lxml</depend> <depend condition="$ROS_PYTHON_VERSION == 2">python-lxml</depend>
<depend condition="$ROS_PYTHON_VERSION == 3">python3-lxml</depend> <depend condition="$ROS_PYTHON_VERSION == 3">python3-lxml</depend>
<depend>dynamic_reconfigure</depend> <depend>dynamic_reconfigure</depend>
<exec_depend>python-pymavlink</exec_depend> <exec_depend>python-pymavlink</exec_depend>
<test_depend>ros_pytest</test_depend> <!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<!-- The export tag contains other, unspecified, tags --> <!-- The export tag contains other, unspecified, tags -->
<export> <export>

View File

@@ -1,4 +1,5 @@
flask==1.1.1 flask==1.1.1
docopt==0.6.2
geopy==1.11.0 geopy==1.11.0
smbus2==0.3.0 smbus2==0.3.0
VL53L1X==0.0.5 VL53L1X==0.0.5

View File

@@ -1,11 +0,0 @@
## ! DO NOT MANUALLY INVOKE THIS setup.py, USE CATKIN INSTEAD
from distutils.core import setup
from catkin_pkg.python_setup import generate_distutils_setup
# fetch values from package.xml
setup_args = generate_distutils_setup(
packages=['clover'],
package_dir={'': 'src'})
setup(**setup_args)

View File

@@ -13,12 +13,7 @@ from util import handle_response
rospy.init_node('autotest_aruco', disable_signals=True) # disable signals to allow interrupting with ctrl+c rospy.init_node('autotest_aruco', disable_signals=True) # disable signals to allow interrupting with ctrl+c
try: flow_client = dynamic_reconfigure.client.Client('optical_flow')
flow_client = dynamic_reconfigure.client.Client('optical_flow', timeout=2)
except rospy.ROSException:
flow_client = None
print('Cannot configure optical flow, skip')
get_telemetry = rospy.ServiceProxy('get_telemetry', srv.GetTelemetry) get_telemetry = rospy.ServiceProxy('get_telemetry', srv.GetTelemetry)
navigate = handle_response(rospy.ServiceProxy('navigate', srv.Navigate)) navigate = handle_response(rospy.ServiceProxy('navigate', srv.Navigate))
land = handle_response(rospy.ServiceProxy('land', Trigger)) land = handle_response(rospy.ServiceProxy('land', Trigger))
@@ -35,8 +30,11 @@ def print_current_map_position():
dist = rospy.wait_for_message('rangefinder/range', Range).range 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)) 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=math.nan, speed=0.5, frame_id='body', tolerance=0.2, auto_arm=False): def navigate_wait(x=0, y=0, z=0, yaw=float('nan'), yaw_rate=0, speed=0.5, \
res = navigate(x=x, y=y, z=z, yaw=yaw, speed=speed, frame_id=frame_id, auto_arm=auto_arm) 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: if not res.success:
return res return res
@@ -69,13 +67,12 @@ 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') navigate_wait(x=center_x, y=center_y, z=1.5, speed=5, frame_id='aruco_map')
print_current_map_position() print_current_map_position()
if flow_client: input('Disable optical flow and keep hovering [enter] ')
input('Disable optical flow and keep hovering [enter] ') flow_client.update_configuration({'enabled': False})
flow_client.update_configuration({'enabled': False}) rospy.sleep(5)
rospy.sleep(5)
input('Enable optical flow back [enter] ') input('Enable optical flow back [enter] ')
flow_client.update_configuration({'enabled': True}) flow_client.update_configuration({'enabled': True})
input('Go to side 1 %g 2 heading top [enter] ' % (center_y)) 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') navigate_wait(x=1, y=center_y, z=2, yaw=1.57, frame_id='aruco_map')

View File

@@ -2,7 +2,7 @@
import rospy import rospy
import math import math
from math import nan, inf from math import nan
import signal import signal
import sys import sys
from clover import srv from clover import srv
@@ -15,8 +15,6 @@ rospy.init_node('autotest_flight', disable_signals=True) # disable signals to al
get_telemetry = rospy.ServiceProxy('get_telemetry', srv.GetTelemetry) get_telemetry = rospy.ServiceProxy('get_telemetry', srv.GetTelemetry)
navigate = handle_response(rospy.ServiceProxy('navigate', srv.Navigate)) navigate = handle_response(rospy.ServiceProxy('navigate', srv.Navigate))
navigate_global = handle_response(rospy.ServiceProxy('navigate_global', srv.NavigateGlobal)) navigate_global = handle_response(rospy.ServiceProxy('navigate_global', srv.NavigateGlobal))
set_yaw = handle_response(rospy.ServiceProxy('set_yaw', srv.SetYaw))
set_yaw_rate = handle_response(rospy.ServiceProxy('set_yaw_rate', srv.SetYawRate))
set_position = handle_response(rospy.ServiceProxy('set_position', srv.SetPosition)) set_position = handle_response(rospy.ServiceProxy('set_position', srv.SetPosition))
set_velocity = handle_response(rospy.ServiceProxy('set_velocity', srv.SetVelocity)) set_velocity = handle_response(rospy.ServiceProxy('set_velocity', srv.SetVelocity))
set_attitude = handle_response(rospy.ServiceProxy('set_attitude', srv.SetAttitude)) set_attitude = handle_response(rospy.ServiceProxy('set_attitude', srv.SetAttitude))
@@ -30,8 +28,11 @@ def interrupt(sig, frame):
signal.signal(signal.SIGINT, interrupt) signal.signal(signal.SIGINT, interrupt)
def navigate_wait(x=0, y=0, z=0, yaw=nan, speed=0.5, frame_id='body', tolerance=0.2, auto_arm=False): def navigate_wait(x=0, y=0, z=0, yaw=nan, yaw_rate=0, speed=0.5, \
res = navigate(x=x, y=y, z=z, yaw=yaw, speed=speed, frame_id=frame_id, auto_arm=auto_arm) 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: if not res.success:
return res return res
@@ -68,17 +69,17 @@ set_velocity(vx=1, vy=0.0, vz=0, frame_id='body')
rospy.sleep(2) rospy.sleep(2)
set_position(frame_id='body') set_position(frame_id='body')
input('Rotate right 90° using set_yaw [enter] ') input('Rotate right 90° [enter] ')
set_yaw(yaw=-math.pi / 2, frame_id='navigate_target') navigate(yaw=-math.pi / 2, frame_id='navigate_target')
rospy.sleep(3) rospy.sleep(3)
input('Use set_attitude to fly backwards [enter]') input('Use set_attitude to fly backwards [enter]')
set_attitude(roll=0, pitch=-0.3, yaw=0, thrust=0.5, frame_id='body') set_attitude(pitch=-0.3, roll=0, yaw=0, thrust=0.5, frame_id='body')
rospy.sleep(0.3) rospy.sleep(0.3)
set_position(frame_id='body') set_position(frame_id='body')
input('Use set_attitude to fly right [enter]') input('Use set_attitude to fly right [enter]')
set_attitude(roll=0.3, pitch=0, yaw=0, thrust=0.5, frame_id='body') set_attitude(pitch=0, roll=0.3, yaw=0, thrust=0.5, frame_id='body')
rospy.sleep(0.5) rospy.sleep(0.5)
set_position(frame_id='body') set_position(frame_id='body')
@@ -87,13 +88,13 @@ set_rates(roll_rate=1.2, thrust=0.5)
rospy.sleep(0.4) rospy.sleep(0.4)
set_position(frame_id='body') set_position(frame_id='body')
input('Rotate 360° to the right using set_yaw_rate [enter]') input('Rotate 360° to the right using yaw_rate [enter]')
set_yaw_rate(yaw_rate=-1) set_position(x=nan, y=nan, z=nan, frame_id='body', yaw=nan, yaw_rate=-1)
rospy.sleep(2 * math.pi) rospy.sleep(2 * math.pi)
set_position(frame_id='body') set_position(frame_id='body')
input('Return to start point heading forward [enter]') input('Return to start point [enter]')
navigate_wait(x=start.x, y=start.y, z=start.z, yaw=inf, speed=1, frame_id='map') navigate_wait(x=start.x, y=start.y, z=start.z, yaw=start.yaw, speed=1, frame_id='map')
input('Land [enter]') input('Land [enter]')
land() land()

View File

@@ -1,35 +0,0 @@
import rospy
from threading import Thread, Event
def long_callback(fn):
"""
Decorator fixing a rospy issue for long-running topic callbacks, primarily
for image processing.
See: https://github.com/ros/ros_comm/issues/1901.
Usage example:
@long_callback
def image_callback(msg):
# perform image processing
# ...
rospy.Subscriber('main_camera/image_raw', Image, image_callback, queue_size=1)
"""
e = Event()
def thread():
while not rospy.is_shutdown():
e.wait()
e.clear()
fn(thread.current_msg)
thread.current_msg = None
Thread(target=thread, daemon=True).start()
def wrapper(msg):
thread.current_msg = msg
e.set()
return wrapper

View File

@@ -31,6 +31,7 @@ ros::Time start_time;
double blink_rate, blink_fast_rate, flash_delay, fade_period, wipe_period, rainbow_period; double blink_rate, blink_fast_rate, flash_delay, fade_period, wipe_period, rainbow_period;
double low_battery_threshold; double low_battery_threshold;
std::vector<std::string> error_ignore; std::vector<std::string> error_ignore;
bool blink_state;
led_msgs::SetLEDs set_leds; led_msgs::SetLEDs set_leds;
led_msgs::LEDStateArray state, start_state; led_msgs::LEDStateArray state, start_state;
ros::ServiceClient set_leds_srv; ros::ServiceClient set_leds_srv;
@@ -86,8 +87,9 @@ void proceed(const ros::TimerEvent& event)
set_leds.request.leds.resize(led_count); set_leds.request.leds.resize(led_count);
if (current_effect.effect == "blink" || current_effect.effect == "blink_fast") { if (current_effect.effect == "blink" || current_effect.effect == "blink_fast") {
// enable on odd counter blink_state = !blink_state;
if (counter % 2 != 0) { // toggle all leds
if (blink_state) {
fill(current_effect.r, current_effect.g, current_effect.b); fill(current_effect.r, current_effect.g, current_effect.b);
} else { } else {
fill(0, 0, 0); fill(0, 0, 0);
@@ -220,7 +222,6 @@ bool setEffect(clover::SetLEDEffect::Request& req, clover::SetLEDEffect::Respons
counter = 0; counter = 0;
start_state = state; start_state = state;
start_time = ros::Time::now(); start_time = ros::Time::now();
proceed({ .current_real = start_time });
return true; return true;
} }
@@ -319,8 +320,8 @@ int main(int argc, char **argv)
auto set_effect = nh.advertiseService("set_effect", &setEffect); auto set_effect = nh.advertiseService("set_effect", &setEffect);
auto mavros_state_sub = nh.subscribe("mavros/state", 1, &handleMavrosState); auto mavros_state_sub = nh.subscribe("/mavros/state", 1, &handleMavrosState);
auto battery_sub = nh.subscribe("mavros/battery", 1, &handleBattery); auto battery_sub = nh.subscribe("/mavros/battery", 1, &handleBattery);
auto rosout_sub = nh.subscribe("/rosout_agg", 1, &handleLog); auto rosout_sub = nh.subscribe("/rosout_agg", 1, &handleLog);
timer = nh.createTimer(ros::Duration(0), &proceed, false, false); timer = nh.createTimer(ros::Duration(0), &proceed, false, false);

View File

@@ -25,7 +25,6 @@
#include <dynamic_reconfigure/server.h> #include <dynamic_reconfigure/server.h>
#include <mavros_msgs/OpticalFlowRad.h> #include <mavros_msgs/OpticalFlowRad.h>
#include <sensor_msgs/Imu.h> #include <sensor_msgs/Imu.h>
#include <geometry_msgs/PoseStamped.h>
#include <geometry_msgs/Vector3Stamped.h> #include <geometry_msgs/Vector3Stamped.h>
#include <geometry_msgs/PointStamped.h> #include <geometry_msgs/PointStamped.h>
#include <geometry_msgs/TwistStamped.h> #include <geometry_msgs/TwistStamped.h>
@@ -58,9 +57,6 @@ private:
std::unique_ptr<tf2_ros::TransformListener> tf_listener_; std::unique_ptr<tf2_ros::TransformListener> tf_listener_;
bool calc_flow_gyro_; bool calc_flow_gyro_;
float flow_gyro_default_; float flow_gyro_default_;
bool disable_on_vpe_;
ros::Subscriber vpe_sub_;
ros::Time last_vpe_time_;
std::shared_ptr<dynamic_reconfigure::Server<clover::FlowConfig>> dyn_srv_; std::shared_ptr<dynamic_reconfigure::Server<clover::FlowConfig>> dyn_srv_;
void onInit() void onInit()
@@ -91,11 +87,6 @@ private:
img_sub_ = it.subscribeCamera("image_raw", 1, &OpticalFlow::flow, this); img_sub_ = it.subscribeCamera("image_raw", 1, &OpticalFlow::flow, this);
disable_on_vpe_ = nh_priv.param("disable_on_vpe", false);
if (disable_on_vpe_) {
vpe_sub_ = nh.subscribe("mavros/vision_pose/pose", 1, &OpticalFlow::vpeCallback, this);
}
dyn_srv_ = std::make_shared<dynamic_reconfigure::Server<clover::FlowConfig>>(nh_priv); dyn_srv_ = std::make_shared<dynamic_reconfigure::Server<clover::FlowConfig>>(nh_priv);
dynamic_reconfigure::Server<clover::FlowConfig>::CallbackType cb; dynamic_reconfigure::Server<clover::FlowConfig>::CallbackType cb;
@@ -130,12 +121,6 @@ private:
{ {
if (!enabled_) return; if (!enabled_) return;
if (disable_on_vpe_ &&
!last_vpe_time_.isZero() &&
(msg->header.stamp - last_vpe_time_).toSec() < 0.1) {
return;
}
parseCameraInfo(cinfo); parseCameraInfo(cinfo);
auto img = cv_bridge::toCvShare(msg, "mono8")->image; auto img = cv_bridge::toCvShare(msg, "mono8")->image;
@@ -169,7 +154,7 @@ private:
img.convertTo(curr_, CV_32F); img.convertTo(curr_, CV_32F);
if (prev_.empty() || (msg->header.stamp - prev_stamp_).toSec() > 0.1) { // outdated previous frame if (prev_.empty()) {
prev_ = curr_.clone(); prev_ = curr_.clone();
prev_stamp_ = msg->header.stamp; prev_stamp_ = msg->header.stamp;
cv::createHanningWindow(hann_, curr_.size(), CV_32F); cv::createHanningWindow(hann_, curr_.size(), CV_32F);
@@ -251,15 +236,6 @@ private:
prev_ = curr_.clone(); prev_ = curr_.clone();
prev_stamp_ = msg->header.stamp; prev_stamp_ = msg->header.stamp;
// Publish estimated angular velocity
geometry_msgs::TwistStamped velo;
velo.header.stamp = msg->header.stamp;
velo.header.frame_id = fcu_frame_id_;
velo.twist.angular.x = flow_fcu.vector.x / integration_time.toSec();
velo.twist.angular.y = flow_fcu.vector.y / integration_time.toSec();
velo_pub_.publish(velo);
publish_debug:
// Publish debug image // Publish debug image
if (img_pub_.getNumSubscribers() > 0) { if (img_pub_.getNumSubscribers() > 0) {
// publish debug image // publish debug image
@@ -271,6 +247,14 @@ publish_debug:
out_msg.image = img; out_msg.image = img;
img_pub_.publish(out_msg.toImageMsg()); img_pub_.publish(out_msg.toImageMsg());
} }
// Publish estimated angular velocity
geometry_msgs::TwistStamped velo;
velo.header.stamp = msg->header.stamp;
velo.header.frame_id = fcu_frame_id_;
velo.twist.angular.x = flow_fcu.vector.x / integration_time.toSec();
velo.twist.angular.y = flow_fcu.vector.y / integration_time.toSec();
velo_pub_.publish(velo);
} }
} }
@@ -292,17 +276,13 @@ publish_debug:
return flow; return flow;
} }
void paramCallback(clover::FlowConfig &config, uint32_t level) void paramCallback(clover::FlowConfig &config, [[maybe_unused]] uint32_t level)
{ {
enabled_ = config.enabled; enabled_ = config.enabled;
if (!enabled_) { if (!enabled_) {
prev_ = Mat(); // clear previous frame prev_ = Mat(); // clear previous frame
} }
} }
void vpeCallback(const geometry_msgs::PoseStamped& vpe) {
last_vpe_time_ = vpe.header.stamp;
}
}; };
PLUGINLIB_EXPORT_CLASS(OpticalFlow, nodelet::Nodelet) PLUGINLIB_EXPORT_CLASS(OpticalFlow, nodelet::Nodelet)

View File

@@ -91,7 +91,7 @@ private:
void fakeGCSThread() void fakeGCSThread()
{ {
// Awful workaround for fixing PX4 not sending STATUSTEXTs // Awful workaround for fixing PX4 not sending STATUSTEXTs
// if there is no GCS heartbeats. // if there is no GCS hearbeats.
// TODO: use timer // TODO: use timer
// TODO: remove, when PX4 get this fixed. // TODO: remove, when PX4 get this fixed.
ros::Publisher mavlink_pub = nh.advertise<mavros_msgs::Mavlink>("mavlink/to", 1); ros::Publisher mavlink_pub = nh.advertise<mavros_msgs::Mavlink>("mavlink/to", 1);

View File

@@ -9,14 +9,13 @@
# The above copyright notice and this permission notice shall be included in all # The above copyright notice and this permission notice shall be included in all
# copies or substantial portions of the Software. # copies or substantial portions of the Software.
import os, sys import os
import math import math
import subprocess import subprocess
import re import re
from collections import OrderedDict from collections import OrderedDict
import traceback import traceback
import threading from threading import Event
from threading import Event, Thread, Lock
import numpy import numpy
import rospy import rospy
import tf2_ros import tf2_ros
@@ -28,16 +27,24 @@ from mavros_msgs.msg import State, OpticalFlowRad, Mavlink
from mavros_msgs.srv import ParamGet from mavros_msgs.srv import ParamGet
from geometry_msgs.msg import PoseStamped, TwistStamped, PoseWithCovarianceStamped, Vector3Stamped from geometry_msgs.msg import PoseStamped, TwistStamped, PoseWithCovarianceStamped, Vector3Stamped
from visualization_msgs.msg import MarkerArray as VisualizationMarkerArray from visualization_msgs.msg import MarkerArray as VisualizationMarkerArray
from diagnostic_msgs.msg import DiagnosticArray
import tf.transformations as t import tf.transformations as t
from aruco_pose.msg import MarkerArray from aruco_pose.msg import MarkerArray
from mavros import mavlink from mavros import mavlink
import locale import locale
# TODO: check attitude is present
# TODO: disk free space
# TODO: map, base_link, body
# TODO: rc service
# TODO: perform commander check, ekf2 status on PX4
# TODO: check if FCU params setter succeed
# TODO: selfcheck ROS service (with blacklists for checks)
rospy.init_node('selfcheck') rospy.init_node('selfcheck')
os.environ['ROSCONSOLE_FORMAT']='${message}' os.environ['ROSCONSOLE_FORMAT']='[${severity}]: ${message}'
# use user's locale to convert numbers, etc # use user's locale to convert numbers, etc
locale.setlocale(locale.LC_ALL, '') locale.setlocale(locale.LC_ALL, '')
@@ -46,68 +53,46 @@ tf_buffer = tf2_ros.Buffer()
tf_listener = tf2_ros.TransformListener(tf_buffer) tf_listener = tf2_ros.TransformListener(tf_buffer)
thread_local = threading.local() failures = []
reports_lock = Lock() infos = []
current_check = None
# formatting colors
if sys.stdout.isatty():
GREY = '\033[90m'
GREEN = '\033[92m'
RED = '\033[31m'
END = '\033[0m'
else:
GREY = GREEN = RED = END = ''
def failure(text, *args): def failure(text, *args):
msg = text % args msg = text % args
thread_local.reports += [{'failure': msg}] rospy.logwarn('%s: %s', current_check, msg)
failures.append(msg)
def info(text, *args): def info(text, *args):
msg = text % args msg = text % args
thread_local.reports += [{'info': msg}] rospy.loginfo('%s: %s', current_check, msg)
infos.append(msg)
def check(name): def check(name):
def inner(fn): def inner(fn):
def wrapper(*args, **kwargs): def wrapper(*args, **kwargs):
start = rospy.get_time() failures[:] = []
thread_local.reports = [] infos[:] = []
global current_check
current_check = name
try: try:
fn(*args, **kwargs) fn(*args, **kwargs)
except Exception as e: except Exception as e:
traceback.print_exc() traceback.print_exc()
rospy.logerr('%s: exception occurred', name) rospy.logerr('%s: exception occurred', name)
with reports_lock: return
for report in thread_local.reports: if not failures and not infos:
if 'failure' in report: rospy.loginfo('%s: OK', name)
rospy.logerr('%s: %s', name, report['failure'])
elif 'info' in report:
rospy.loginfo(GREY + name + END + ': ' + report['info'])
if not thread_local.reports:
rospy.loginfo(GREY + name + END + ': ' + GREEN + 'OK' + END)
if rospy.get_param('~time', False):
rospy.loginfo('%s: %.1f sec', name, rospy.get_time() - start)
return wrapper return wrapper
return inner return inner
def ff(value, precision=2):
# safely format float or int
if value is None:
return RED + '???' + END
if isinstance(value, float):
return ('{:.' + str(precision + 1) + '}').format(value)
elif isinstance(value, int):
return str(value)
param_get = rospy.ServiceProxy('mavros/param/get', ParamGet) param_get = rospy.ServiceProxy('mavros/param/get', ParamGet)
def get_param(name, default=None): def get_param(name):
try: try:
res = param_get(param_id=name) res = param_get(param_id=name)
except rospy.ServiceException as e: except rospy.ServiceException as e:
@@ -116,17 +101,12 @@ def get_param(name, default=None):
if not res.success: if not res.success:
failure('unable to retrieve PX4 parameter %s', name) failure('unable to retrieve PX4 parameter %s', name)
return default
else: else:
if res.value.integer != 0: if res.value.integer != 0:
return res.value.integer return res.value.integer
return res.value.real return res.value.real
def get_paramf(name, precision=2):
return ff(get_param(name), precision)
recv_event = Event() recv_event = Event()
link = mavutil.mavlink.MAVLink('', 255, 1) link = mavutil.mavlink.MAVLink('', 255, 1)
mavlink_pub = rospy.Publisher('mavlink/to', Mavlink, queue_size=1) mavlink_pub = rospy.Publisher('mavlink/to', Mavlink, queue_size=1)
@@ -171,24 +151,6 @@ def mavlink_exec(cmd, timeout=3.0):
return mavlink_recv return mavlink_recv
def read_diagnostics(name, key):
e = Event()
def cb(msg):
for status in msg.status:
if status.name.lower() == name.lower():
for value in status.values:
if value.key.lower() == key.lower():
cb.value = value.value
e.set()
return
cb.value = None
sub = rospy.Subscriber('/diagnostics', DiagnosticArray, cb)
e.wait(1.0) # wait to read all the diagnostics from nodes publishing them
sub.unregister()
return cb.value
BOARD_ROTATIONS = { BOARD_ROTATIONS = {
0: 'no rotation', 0: 'no rotation',
1: 'yaw 45°', 1: 'yaw 45°',
@@ -234,31 +196,29 @@ def check_fcu():
state = rospy.wait_for_message('mavros/state', State, timeout=3) state = rospy.wait_for_message('mavros/state', State, timeout=3)
if not state.connected: if not state.connected:
failure('no connection to the FCU (check wiring)') failure('no connection to the FCU (check wiring)')
info('fcu_url = %s', rospy.get_param('mavros/fcu_url', '?'))
return return
if not is_process_running('px4', exact=True): # can't use px4 console in SITL clover_tag = re.compile(r'-cl[oe]ver\.\d+$')
clover_tag = re.compile(r'-cl[oe]ver\.\d+$') clover_fw = False
clover_fw = False
# Make sure the console is available to us # Make sure the console is available to us
mavlink_exec('\n') mavlink_exec('\n')
version_str = mavlink_exec('ver all') version_str = mavlink_exec('ver all')
if version_str == '': if version_str == '':
info('no version data available from SITL') info('no version data available from SITL')
for line in version_str.split('\n'): for line in version_str.split('\n'):
if line.startswith('FW version: '): if line.startswith('FW version: '):
info(line[len('FW version: '):]) info(line[len('FW version: '):])
elif line.startswith('FW git tag: '): # only Clover's firmware elif line.startswith('FW git tag: '): # only Clover's firmware
tag = line[len('FW git tag: '):] tag = line[len('FW git tag: '):]
clover_fw = clover_tag.search(tag) clover_fw = clover_tag.search(tag)
info(tag) info(tag)
elif line.startswith('HW arch: '): elif line.startswith('HW arch: '):
info(line[len('HW arch: '):]) info(line[len('HW arch: '):])
if not clover_fw: if not clover_fw:
info('not Clover PX4 firmware, check https://clover.coex.tech/firmware') info('not Clover PX4 firmware, check https://clover.coex.tech/firmware')
est = get_param('SYS_MC_EST_GROUP') est = get_param('SYS_MC_EST_GROUP')
if est == 1: if est == 1:
@@ -295,29 +255,21 @@ def check_fcu():
if cbrk_usb_chk != 197848: if cbrk_usb_chk != 197848:
failure('set parameter CBRK_USB_CHK to 197848 for flying with USB connected') failure('set parameter CBRK_USB_CHK to 197848 for flying with USB connected')
if not is_process_running('px4', exact=True): # skip battery check in SITL
try:
battery = rospy.wait_for_message('mavros/battery', BatteryState, timeout=3)
if not battery.cell_voltage:
failure('cell voltage is not available, https://clover.coex.tech/power')
else:
cell = battery.cell_voltage[0]
if cell > 4.3 or cell < 3.0:
failure('incorrect cell voltage: %.2f V, https://clover.coex.tech/power', cell)
elif cell < 3.7:
failure('critically low cell voltage: %.2f V, recharge battery', cell)
except rospy.ROSException:
failure('no battery state')
# time sync check
try: try:
info('time sync offset: %.2f s', float(read_diagnostics('mavros: Time Sync', 'Estimated time offset (s)'))) battery = rospy.wait_for_message('mavros/battery', BatteryState, timeout=3)
except: if not battery.cell_voltage:
failure('cannot read time sync offset') failure('cell voltage is not available, https://clover.coex.tech/power')
else:
cell = battery.cell_voltage[0]
if cell > 4.3 or cell < 3.0:
failure('incorrect cell voltage: %.2f V, https://clover.coex.tech/power', cell)
elif cell < 3.7:
failure('critically low cell voltage: %.2f V, recharge battery', cell)
except rospy.ROSException:
failure('no battery state')
except rospy.ROSException: except rospy.ROSException:
failure('no MAVROS state (check wiring)') failure('no MAVROS state (check wiring)')
info('fcu_url = %s', rospy.get_param('mavros/fcu_url', '?'))
def describe_direction(v): def describe_direction(v):
@@ -384,7 +336,7 @@ def is_process_running(binary, exact=False, full=False):
if exact: if exact:
args.append('-x') # match exactly with the command name args.append('-x') # match exactly with the command name
if full: if full:
args.append('-f') # use full command line (including arguments) to match args.append('-f') # use full process name to match
args.append(binary) args.append(binary)
subprocess.check_output(args) subprocess.check_output(args)
return True return True
@@ -394,24 +346,19 @@ def is_process_running(binary, exact=False, full=False):
@check('ArUco markers') @check('ArUco markers')
def check_aruco(): def check_aruco():
markers = None
if is_process_running('aruco_detect', full=True): if is_process_running('aruco_detect', full=True):
try: try:
info('aruco_detect/length = %g m', rospy.get_param('aruco_detect/length', '?')) info('aruco_detect/length = %g m', rospy.get_param('aruco_detect/length'))
except KeyError: except KeyError:
failure('aruco_detect/length parameter is not set') failure('aruco_detect/length parameter is not set')
known_vertical = rospy.get_param('aruco_detect/known_vertical', '') known_tilt = rospy.get_param('aruco_detect/known_tilt', '')
flip_vertical = rospy.get_param('aruco_detect/flip_vertical', False) if known_tilt == 'map':
description = '' known_tilt += ' (ALL markers are on the floor)'
if known_vertical == 'map' and not flip_vertical: elif known_tilt == 'map_flipped':
description = ' (all markers are on the floor)' known_tilt += ' (ALL markers are on the ceiling)'
elif known_vertical == 'map' and flip_vertical: info('aruco_detector/known_tilt = %s', known_tilt)
description = ' (all markers are on the ceiling)'
info('aruco_detect/known_vertical = %s', known_vertical)
info('aruco_detect/flip_vertical = %s%s', flip_vertical, description)
try: try:
markers = rospy.wait_for_message('aruco_detect/markers', MarkerArray, timeout=0.8) rospy.wait_for_message('aruco_detect/markers', MarkerArray, timeout=1)
except rospy.ROSException: except rospy.ROSException:
failure('no markers detection') failure('no markers detection')
return return
@@ -420,61 +367,42 @@ def check_aruco():
return return
if is_process_running('aruco_map', full=True): if is_process_running('aruco_map', full=True):
known_vertical = rospy.get_param('aruco_map/known_vertical', '') known_tilt = rospy.get_param('aruco_map/known_tilt', '')
flip_vertical = rospy.get_param('aruco_map/flip_vertical', False) if known_tilt == 'map':
description = '' known_tilt += ' (marker\'s map is on the floor)'
if known_vertical == 'map' and not flip_vertical: elif known_tilt == 'map_flipped':
description += ' (markers map is on the floor)' known_tilt += ' (marker\'s map is on the ceiling)'
elif known_vertical == 'map' and flip_vertical: info('aruco_map/known_tilt = %s', known_tilt)
description += ' (markers map is on the ceiling)'
info('aruco_map/known_vertical = %s', known_vertical)
info('aruco_map/flip_vertical = %s%s', flip_vertical, description)
try: try:
visualization = rospy.wait_for_message('aruco_map/visualization', VisualizationMarkerArray, timeout=0.8) visualization = rospy.wait_for_message('aruco_map/visualization', VisualizationMarkerArray, timeout=1)
info('map has %s markers', len(visualization.markers)) info('map has %s markers', len(visualization.markers))
except: except:
failure('cannot read aruco_map/visualization topic') failure('cannot read aruco_map/visualization topic')
try: try:
rospy.wait_for_message('aruco_map/pose', PoseWithCovarianceStamped, timeout=0.8) rospy.wait_for_message('aruco_map/pose', PoseWithCovarianceStamped, timeout=1)
except rospy.ROSException: except rospy.ROSException:
if not markers: failure('no map detection')
info('no map detection as no markers detection')
elif not markers.markers:
info('no map detection as no markers detected')
else:
failure('no map detection')
else: else:
info('aruco_map is not running') info('aruco_map is not running')
def is_on_the_floor():
try:
dist = rospy.wait_for_message('rangefinder/range', Range, timeout=1)
return dist.range < 0.3
except rospy.ROSException:
return False
@check('Vision position estimate') @check('Vision position estimate')
def check_vpe(): def check_vpe():
vis = None vis = None
try: try:
vis = rospy.wait_for_message('mavros/vision_pose/pose', PoseStamped, timeout=0.8) vis = rospy.wait_for_message('mavros/vision_pose/pose', PoseStamped, timeout=1)
except rospy.ROSException: except rospy.ROSException:
try: try:
vis = rospy.wait_for_message('mavros/mocap/pose', PoseStamped, timeout=0.8) vis = rospy.wait_for_message('mavros/mocap/pose', PoseStamped, timeout=1)
except rospy.ROSException: except rospy.ROSException:
if not is_process_running('vpe_publisher', full=True): failure('no VPE or MoCap messages')
info('no vision position estimate, vpe_publisher is not running') # check if vpe_publisher is running
elif rospy.get_param('aruco_map/known_vertical', '') == 'map' \ try:
and rospy.get_param('aruco_map/flip_vertical', False): subprocess.check_output(['pgrep', '-x', 'vpe_publisher'])
failure('no vision position estimate, markers are on the ceiling') except subprocess.CalledProcessError:
elif is_on_the_floor(): return # it's not running, skip following checks
info('no vision position estimate, the drone is on the floor')
else:
failure('no vision position estimate')
# check PX4 settings # check PX4 settings
est = get_param('SYS_MC_EST_GROUP') est = get_param('SYS_MC_EST_GROUP')
@@ -486,14 +414,14 @@ def check_vpe():
if vision_yaw_w == 0: if vision_yaw_w == 0:
failure('vision yaw weight is zero, change ATT_W_EXT_HDG parameter') failure('vision yaw weight is zero, change ATT_W_EXT_HDG parameter')
else: else:
info('vision yaw weight: %s', ff(vision_yaw_w)) info('Vision yaw weight: %.2f', vision_yaw_w)
fuse = get_param('LPE_FUSION') fuse = get_param('LPE_FUSION')
if not fuse & (1 << 2): if not fuse & (1 << 2):
failure('vision position fusion is disabled, change LPE_FUSION parameter') failure('vision position fusion is disabled, change LPE_FUSION parameter')
delay = get_param('LPE_VIS_DELAY') delay = get_param('LPE_VIS_DELAY')
if delay != 0: if delay != 0:
failure('LPE_VIS_DELAY = %s, but it should be zero', delay) failure('LPE_VIS_DELAY parameter is %s, but it should be zero', delay)
info('LPE_VIS_XY = %s m, LPE_VIS_Z = %s m', get_paramf('LPE_VIS_XY'), get_paramf('LPE_VIS_Z')) info('LPE_VIS_XY is %.2f m, LPE_VIS_Z is %.2f m', get_param('LPE_VIS_XY'), get_param('LPE_VIS_Z'))
elif est == 2: elif est == 2:
fuse = get_param('EKF2_AID_MASK') fuse = get_param('EKF2_AID_MASK')
if not fuse & (1 << 3): if not fuse & (1 << 3):
@@ -502,10 +430,10 @@ def check_vpe():
failure('vision yaw fusion is disabled, change EKF2_AID_MASK parameter') failure('vision yaw fusion is disabled, change EKF2_AID_MASK parameter')
delay = get_param('EKF2_EV_DELAY') delay = get_param('EKF2_EV_DELAY')
if delay != 0: if delay != 0:
failure('EKF2_EV_DELAY = %.2f, but it should be zero', delay) failure('EKF2_EV_DELAY is %.2f, but it should be zero', delay)
info('EKF2_EVA_NOISE = %s, EKF2_EVP_NOISE = %s', info('EKF2_EVA_NOISE is %.3f, EKF2_EVP_NOISE is %.3f',
get_paramf('EKF2_EVA_NOISE', 3), get_param('EKF2_EVA_NOISE'),
get_paramf('EKF2_EVP_NOISE', 3)) get_param('EKF2_EVP_NOISE'))
if not vis: if not vis:
return return
@@ -603,19 +531,13 @@ def check_velocity():
@check('Global position (GPS)') @check('Global position (GPS)')
def check_global_position(): def check_global_position():
try: try:
rospy.wait_for_message('mavros/global_position/global', NavSatFix, timeout=0.8) rospy.wait_for_message('mavros/global_position/global', NavSatFix, timeout=1)
except rospy.ROSException: except rospy.ROSException:
info('no global position') info('no global position')
if get_param('SYS_MC_EST_GROUP') == 2 and (get_param('EKF2_AID_MASK', 0) & (1 << 0)):
failure('enabled GPS fusion may suppress vision position aiding')
@check('Optical flow') @check('Optical flow')
def check_optical_flow(): def check_optical_flow():
if not is_process_running('optical_flow', full=True):
info('optical_flow is not running')
return
# TODO:check FPS! # TODO:check FPS!
try: try:
rospy.wait_for_message('mavros/px4flow/raw/send', OpticalFlowRad, timeout=0.5) rospy.wait_for_message('mavros/px4flow/raw/send', OpticalFlowRad, timeout=0.5)
@@ -623,7 +545,7 @@ def check_optical_flow():
# check PX4 settings # check PX4 settings
rot = get_param('SENS_FLOW_ROT') rot = get_param('SENS_FLOW_ROT')
if rot != 0: if rot != 0:
failure('SENS_FLOW_ROT = %s, but it should be zero', rot) failure('SENS_FLOW_ROT parameter is %s, but it should be zero', rot)
est = get_param('SYS_MC_EST_GROUP') est = get_param('SYS_MC_EST_GROUP')
if est == 1: if est == 1:
fuse = get_param('LPE_FUSION') fuse = get_param('LPE_FUSION')
@@ -631,36 +553,32 @@ def check_optical_flow():
failure('optical flow fusion is disabled, change LPE_FUSION parameter') failure('optical flow fusion is disabled, change LPE_FUSION parameter')
if not fuse & (1 << 1): if not fuse & (1 << 1):
failure('flow gyro compensation is disabled, change LPE_FUSION parameter') failure('flow gyro compensation is disabled, change LPE_FUSION parameter')
scale = get_param('LPE_FLW_SCALE', 1) scale = get_param('LPE_FLW_SCALE')
if not numpy.isclose(scale, 1.0): if not numpy.isclose(scale, 1.0):
failure('LPE_FLW_SCALE = %.2f, but it should be 1.0', scale) failure('LPE_FLW_SCALE parameter is %.2f, but it should be 1.0', scale)
info('LPE_FLW_QMIN = %s, LPE_FLW_R = %s, LPE_FLW_RR = %s', info('LPE_FLW_QMIN is %s, LPE_FLW_R is %.4f, LPE_FLW_RR is %.4f, SENS_FLOW_MINHGT is %.3f, SENS_FLOW_MAXHGT is %.3f',
get_paramf('LPE_FLW_QMIN'), get_param('LPE_FLW_QMIN'),
get_paramf('LPE_FLW_R', 4), get_param('LPE_FLW_R'),
get_paramf('LPE_FLW_RR', 4)) get_param('LPE_FLW_RR'),
get_param('SENS_FLOW_MINHGT'),
get_param('SENS_FLOW_MAXHGT'))
elif est == 2: elif est == 2:
fuse = get_param('EKF2_AID_MASK', 0) fuse = get_param('EKF2_AID_MASK')
if not fuse & (1 << 1): if not fuse & (1 << 1):
failure('optical flow fusion is disabled, change EKF2_AID_MASK parameter') failure('optical flow fusion is disabled, change EKF2_AID_MASK parameter')
delay = get_param('EKF2_OF_DELAY', 0) delay = get_param('EKF2_OF_DELAY')
if delay != 0: if delay != 0:
failure('EKF2_OF_DELAY = %.2f, but it should be zero', delay) failure('EKF2_OF_DELAY is %.2f, but it should be zero', delay)
info('EKF2_OF_QMIN = %s, EKF2_OF_N_MIN = %s, EKF2_OF_N_MAX = %s', info('EKF2_OF_QMIN is %s, EKF2_OF_N_MIN is %.4f, EKF2_OF_N_MAX is %.4f, SENS_FLOW_MINHGT is %.3f, SENS_FLOW_MAXHGT is %.3f',
get_paramf('EKF2_OF_QMIN'), get_param('EKF2_OF_QMIN'),
get_paramf('EKF2_OF_N_MIN', 4), get_param('EKF2_OF_N_MIN'),
get_paramf('EKF2_OF_N_MAX', 4)) get_param('EKF2_OF_N_MAX'),
info('SENS_FLOW_MINHGT = %s, SENS_FLOW_MAXHGT = %s', get_paramf('SENS_FLOW_MINHGT', 3), get_paramf('SENS_FLOW_MAXHGT', 3)) get_param('SENS_FLOW_MINHGT'),
get_param('SENS_FLOW_MAXHGT'))
except rospy.ROSException: except rospy.ROSException:
if rospy.get_param('optical_flow/disable_on_vpe', False): failure('no optical flow data (from Raspberry)')
try:
rospy.wait_for_message('mavros/vision_pose/pose', PoseStamped, timeout=1)
info('no optical flow as disable_on_vpe is true')
except:
failure('no optical flow on RPi, disable_on_vpe is true, but no vision pose also')
else:
failure('no optical flow on RPi')
@check('Rangefinder') @check('Rangefinder')
@@ -684,7 +602,7 @@ def check_rangefinder():
est = get_param('SYS_MC_EST_GROUP') est = get_param('SYS_MC_EST_GROUP')
if est == 1: if est == 1:
fuse = get_param('LPE_FUSION', 0) fuse = get_param('LPE_FUSION')
if not fuse & (1 << 5): if not fuse & (1 << 5):
info('"pub agl as lpos down" in LPE_FUSION is disabled, NOT operating over flat surface') info('"pub agl as lpos down" in LPE_FUSION is disabled, NOT operating over flat surface')
else: else:
@@ -705,10 +623,6 @@ def check_rangefinder():
@check('Boot duration') @check('Boot duration')
def check_boot_duration(): def check_boot_duration():
if not os.path.exists('/etc/clover_version'):
info('skip check')
return # Don't check not on Clover's image
output = subprocess.check_output('systemd-analyze').decode() output = subprocess.check_output('systemd-analyze').decode()
r = re.compile(r'([\d\.]+)s\s*$', flags=re.MULTILINE) r = re.compile(r'([\d\.]+)s\s*$', flags=re.MULTILINE)
duration = float(r.search(output).groups()[0]) duration = float(r.search(output).groups()[0])
@@ -718,7 +632,7 @@ def check_boot_duration():
@check('CPU usage') @check('CPU usage')
def check_cpu_usage(): def check_cpu_usage():
WHITELIST = 'nodelet', 'gzclient', 'gzserver', 'selfcheck.py' WHITELIST = 'nodelet', 'gzclient', 'gzserver'
CMD = "top -n 1 -b -i | tail -n +8 | awk '{ printf(\"%-8s\\t%-8s\\t%-8s\\n\", $1, $9, $12); }'" CMD = "top -n 1 -b -i | tail -n +8 | awk '{ printf(\"%-8s\\t%-8s\\t%-8s\\n\", $1, $9, $12); }'"
output = subprocess.check_output(CMD, shell=True).decode() output = subprocess.check_output(CMD, shell=True).decode()
processes = output.split('\n') processes = output.split('\n')
@@ -734,9 +648,6 @@ def check_cpu_usage():
@check('clover.service') @check('clover.service')
def check_clover_service(): def check_clover_service():
if not os.path.exists('/etc/clover_version'):
return # Don't check not on Clover's image
try: try:
output = subprocess.check_output('systemctl show -p ActiveState --value clover.service'.split(), output = subprocess.check_output('systemctl show -p ActiveState --value clover.service'.split(),
stderr=subprocess.STDOUT).decode() stderr=subprocess.STDOUT).decode()
@@ -787,18 +698,11 @@ def check_image():
try: try:
info('version: %s', open('/etc/clover_version').read().strip()) info('version: %s', open('/etc/clover_version').read().strip())
except IOError: except IOError:
try: info('no /etc/clover_version file, not the Clover image?')
info('VM version: %s', open('/etc/clover_vm_version').read().strip())
except IOError:
info('no /etc/clover_version file, not the Clover image?')
@check('Preflight status') @check('Preflight status')
def check_preflight_status(): def check_preflight_status():
if is_process_running('px4', exact=True):
info('can\'t check in SITL')
return
# Make sure the console is available to us # Make sure the console is available to us
mavlink_exec('\n') mavlink_exec('\n')
cmdr_output = mavlink_exec('commander check') cmdr_output = mavlink_exec('commander check')
@@ -820,10 +724,6 @@ def check_preflight_status():
@check('Network') @check('Network')
def check_network(): def check_network():
if not os.path.exists('/etc/clover_version'):
# TODO:
return # Don't check not on Clover's image
ros_hostname = os.environ.get('ROS_HOSTNAME', '').strip() ros_hostname = os.environ.get('ROS_HOSTNAME', '').strip()
if not ros_hostname: if not ros_hostname:
@@ -901,47 +801,26 @@ def check_board():
info('could not open /proc/device-tree/model, not a Raspberry Pi?') info('could not open /proc/device-tree/model, not a Raspberry Pi?')
def parallel_for(fns):
threads = []
for fn in fns:
thread = Thread(target=fn)
thread.start()
threads.append(thread)
for thread in threads:
thread.join()
def consequentially_for(fns):
for fn in fns:
fn()
def selfcheck(): def selfcheck():
checks = [ check_image()
check_image, check_board()
check_board, check_clover_service()
check_clover_service, check_network()
check_network, check_fcu()
check_fcu, check_imu()
check_imu, check_local_position()
check_local_position, check_velocity()
check_velocity, check_global_position()
check_global_position, check_preflight_status()
check_preflight_status, check_main_camera()
check_main_camera, check_aruco()
check_aruco, check_simpleoffboard()
check_simpleoffboard, check_optical_flow()
check_optical_flow, check_vpe()
check_vpe, check_rangefinder()
check_rangefinder, check_rpi_health()
check_rpi_health, check_cpu_usage()
check_cpu_usage, check_boot_duration()
check_boot_duration,
]
if rospy.get_param('~parallel', False):
parallel_for(checks)
else:
consequentially_for(checks)
if __name__ == '__main__': if __name__ == '__main__':

View File

@@ -23,7 +23,6 @@
#include <tf2_ros/static_transform_broadcaster.h> #include <tf2_ros/static_transform_broadcaster.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h> #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <std_srvs/Trigger.h> #include <std_srvs/Trigger.h>
#include <geometry_msgs/PointStamped.h>
#include <geometry_msgs/PoseStamped.h> #include <geometry_msgs/PoseStamped.h>
#include <geometry_msgs/TwistStamped.h> #include <geometry_msgs/TwistStamped.h>
#include <geometry_msgs/Vector3Stamped.h> #include <geometry_msgs/Vector3Stamped.h>
@@ -38,19 +37,14 @@
#include <mavros_msgs/State.h> #include <mavros_msgs/State.h>
#include <mavros_msgs/StatusText.h> #include <mavros_msgs/StatusText.h>
#include <mavros_msgs/ManualControl.h> #include <mavros_msgs/ManualControl.h>
#include <mavros_msgs/Altitude.h>
#include <clover/GetTelemetry.h> #include <clover/GetTelemetry.h>
#include <clover/Navigate.h> #include <clover/Navigate.h>
#include <clover/NavigateGlobal.h> #include <clover/NavigateGlobal.h>
#include <clover/SetAltitude.h>
#include <clover/SetYaw.h>
#include <clover/SetYawRate.h>
#include <clover/SetPosition.h> #include <clover/SetPosition.h>
#include <clover/SetVelocity.h> #include <clover/SetVelocity.h>
#include <clover/SetAttitude.h> #include <clover/SetAttitude.h>
#include <clover/SetRates.h> #include <clover/SetRates.h>
#include <clover/State.h>
using std::string; using std::string;
using std::isnan; using std::isnan;
@@ -60,7 +54,6 @@ using namespace clover;
using mavros_msgs::PositionTarget; using mavros_msgs::PositionTarget;
using mavros_msgs::AttitudeTarget; using mavros_msgs::AttitudeTarget;
using mavros_msgs::Thrust; using mavros_msgs::Thrust;
using mavros_msgs::Altitude;
// tf2 // tf2
tf2_ros::Buffer tf_buffer; tf2_ros::Buffer tf_buffer;
@@ -88,40 +81,33 @@ bool land_only_in_offboard, nav_from_sp, check_kill_switch;
std::map<string, string> reference_frames; std::map<string, string> reference_frames;
// Publishers // Publishers
ros::Publisher attitude_pub, attitude_raw_pub, position_pub, position_raw_pub, rates_pub, thrust_pub, state_pub; ros::Publisher attitude_pub, attitude_raw_pub, position_pub, position_raw_pub, rates_pub, thrust_pub;
// Service clients // Service clients
ros::ServiceClient arming, set_mode; ros::ServiceClient arming, set_mode;
// Containers // Containers
ros::Timer setpoint_timer; ros::Timer setpoint_timer;
tf::Quaternion tq;
PoseStamped position_msg; PoseStamped position_msg;
PositionTarget position_raw_msg; PositionTarget position_raw_msg;
//TwistStamped rates_msg; AttitudeTarget att_raw_msg;
Thrust thrust_msg;
TwistStamped rates_msg;
TransformStamped target, setpoint; TransformStamped target, setpoint;
geometry_msgs::TransformStamped body; geometry_msgs::TransformStamped body;
geometry_msgs::TransformStamped terrain;
// State // State
PoseStamped nav_start; PoseStamped nav_start;
PointStamped setpoint_position; PoseStamped setpoint_position, setpoint_position_transformed;
PointStamped setpoint_altitude; Vector3Stamped setpoint_velocity, setpoint_velocity_transformed;
Vector3Stamped setpoint_velocity; QuaternionStamped setpoint_attitude, setpoint_attitude_transformed;
float setpoint_yaw, setpoint_roll, setpoint_pitch; float setpoint_yaw_rate;
Vector3 setpoint_rates;
string yaw_frame_id;
float setpoint_thrust;
float nav_speed; float nav_speed;
float setpoint_lat = NAN, setpoint_lon = NAN;
bool busy = false; bool busy = false;
bool wait_armed = false; bool wait_armed = false;
bool nav_from_sp_flag = false; bool nav_from_sp_flag = false;
// Last published
PoseStamped setpoint_pose_local;
Vector3Stamped setpoint_velocity_local;
float yaw_local;
enum setpoint_type_t { enum setpoint_type_t {
NONE, NONE,
NAVIGATE, NAVIGATE,
@@ -129,10 +115,7 @@ enum setpoint_type_t {
POSITION, POSITION,
VELOCITY, VELOCITY,
ATTITUDE, ATTITUDE,
RATES, RATES
_ALTITUDE,
_YAW,
_YAW_RATE,
}; };
enum setpoint_type_t setpoint_type = NONE; enum setpoint_type_t setpoint_type = NONE;
@@ -167,9 +150,6 @@ void handleState(const mavros_msgs::State& s)
inline void publishBodyFrame() inline void publishBodyFrame()
{ {
if (body.child_frame_id.empty()) return; if (body.child_frame_id.empty()) return;
if (!body.header.stamp.isZero() && body.header.stamp == local_position.header.stamp) {
return; // avoid TF_REPEATED_DATA warnings
}
tf::Quaternion q; tf::Quaternion q;
q.setRPY(0, 0, tf::getYaw(local_position.pose.orientation)); q.setRPY(0, 0, tf::getYaw(local_position.pose.orientation));
@@ -187,7 +167,7 @@ void handleLocalPosition(const PoseStamped& pose)
{ {
local_position = pose; local_position = pose;
publishBodyFrame(); publishBodyFrame();
// TODO: home? // TODO: terrain?, home?
} }
// wait for transform without interrupting publishing setpoints // wait for transform without interrupting publishing setpoints
@@ -205,20 +185,6 @@ inline bool waitTransform(const string& target, const string& source,
return false; return false;
} }
void handleAltitude(const Altitude& alt)
{
// publish terrain frame
if (!std::isfinite(alt.bottom_clearance)) return;
// terrain.header.stamp = alt.header.stamp;
if (!waitTransform(local_frame, body.child_frame_id, alt.header.stamp, ros::Duration(0.1))) return;
auto t = tf_buffer.lookupTransform(local_frame, body.child_frame_id, alt.header.stamp);
t.child_frame_id = terrain.child_frame_id;
t.transform.translation.z -= alt.bottom_clearance;
static_transform_broadcaster->sendTransform(t);
}
#define TIMEOUT(msg, timeout) (msg.header.stamp.isZero() || (ros::Time::now() - msg.header.stamp > timeout)) #define TIMEOUT(msg, timeout) (msg.header.stamp.isZero() || (ros::Time::now() - msg.header.stamp > timeout))
bool getTelemetry(GetTelemetry::Request& req, GetTelemetry::Response& res) bool getTelemetry(GetTelemetry::Request& req, GetTelemetry::Response& res)
@@ -238,11 +204,11 @@ bool getTelemetry(GetTelemetry::Request& req, GetTelemetry::Response& res)
res.vx = NAN; res.vx = NAN;
res.vy = NAN; res.vy = NAN;
res.vz = NAN; res.vz = NAN;
res.roll = NAN;
res.pitch = NAN; res.pitch = NAN;
res.roll = NAN;
res.yaw = NAN; res.yaw = NAN;
res.roll_rate = NAN;
res.pitch_rate = NAN; res.pitch_rate = NAN;
res.roll_rate = NAN;
res.yaw_rate = NAN; res.yaw_rate = NAN;
res.voltage = NAN; res.voltage = NAN;
res.cell_voltage = NAN; res.cell_voltage = NAN;
@@ -372,20 +338,20 @@ inline float getDistance(const Point& from, const Point& to)
return hypot(from.x - to.x, from.y - to.y, from.z - to.z); return hypot(from.x - to.x, from.y - to.y, from.z - to.z);
} }
void getNavigateSetpoint(const ros::Time& stamp, const float speed, Point& nav_setpoint) void getNavigateSetpoint(const ros::Time& stamp, float speed, Point& nav_setpoint)
{ {
if (wait_armed) { if (wait_armed) {
// don't start navigating if we're waiting arming // don't start navigating if we're waiting arming
nav_start.header.stamp = stamp; nav_start.header.stamp = stamp;
} }
float distance = getDistance(nav_start.pose.position, setpoint_pose_local.pose.position); float distance = getDistance(nav_start.pose.position, setpoint_position_transformed.pose.position);
float time = distance / speed; float time = distance / speed;
float passed = std::min((stamp - nav_start.header.stamp).toSec() / time, 1.0); float passed = std::min((stamp - nav_start.header.stamp).toSec() / time, 1.0);
nav_setpoint.x = nav_start.pose.position.x + (setpoint_pose_local.pose.position.x - nav_start.pose.position.x) * passed; nav_setpoint.x = nav_start.pose.position.x + (setpoint_position_transformed.pose.position.x - nav_start.pose.position.x) * passed;
nav_setpoint.y = nav_start.pose.position.y + (setpoint_pose_local.pose.position.y - nav_start.pose.position.y) * passed; nav_setpoint.y = nav_start.pose.position.y + (setpoint_position_transformed.pose.position.y - nav_start.pose.position.y) * passed;
nav_setpoint.z = nav_start.pose.position.z + (setpoint_pose_local.pose.position.z - nav_start.pose.position.z) * passed; nav_setpoint.z = nav_start.pose.position.z + (setpoint_position_transformed.pose.position.z - nav_start.pose.position.z) * passed;
} }
PoseStamped globalToLocal(double lat, double lon) PoseStamped globalToLocal(double lat, double lon)
@@ -416,101 +382,44 @@ PoseStamped globalToLocal(double lat, double lon)
return pose; return pose;
} }
// publish navigate_target frame
void publishTarget(ros::Time stamp, bool _static = false)
{
bool single_frame = (setpoint_position.header.frame_id == setpoint_altitude.header.frame_id);
// handle yaw for target frame
if (setpoint_yaw_type == YAW || setpoint_yaw_type == YAW_RATE) { // use last set yaw for yaw_rate
if (setpoint_altitude.header.frame_id == yaw_frame_id) {
target.transform.rotation = tf::createQuaternionMsgFromYaw(setpoint_yaw);
} else {
single_frame = false;
target.transform.rotation = tf::createQuaternionMsgFromYaw(yaw_local);
}
} else if (setpoint_yaw_type == TOWARDS) {
single_frame = false;
target.transform.rotation = tf::createQuaternionMsgFromYaw(yaw_local);
}
if (_static && single_frame) {
// publish at user's command, if all frames are the same
target.header.frame_id = setpoint_position.header.frame_id;
target.header.stamp = stamp;
target.transform.translation.x = setpoint_position.point.x;
target.transform.translation.y = setpoint_position.point.y;
target.transform.translation.z = setpoint_position.point.z;
} else if (!_static) {
// publish at each iteration, if frames are different
target.header = setpoint_pose_local.header;
target.transform.translation.x = setpoint_pose_local.pose.position.x;
target.transform.translation.y = setpoint_pose_local.pose.position.y;
target.transform.translation.z = setpoint_pose_local.pose.position.z;
}
static_transform_broadcaster->sendTransform(target);
}
void publish(const ros::Time stamp) void publish(const ros::Time stamp)
{ {
if (setpoint_type == NONE) return; if (setpoint_type == NONE) return;
position_raw_msg.header.stamp = stamp; position_raw_msg.header.stamp = stamp;
thrust_msg.header.stamp = stamp;
rates_msg.header.stamp = stamp;
// transform position try {
if (setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL || setpoint_type == POSITION) { // transform position and/or yaw
setpoint_position.header.stamp = stamp; if (setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL || setpoint_type == POSITION || setpoint_type == VELOCITY || setpoint_type == ATTITUDE) {
setpoint_altitude.header.stamp = stamp; setpoint_position.header.stamp = stamp;
// transform xy tf_buffer.transform(setpoint_position, setpoint_position_transformed, local_frame, ros::Duration(0.05));
try {
auto xy = tf_buffer.transform(setpoint_position, local_frame, ros::Duration(0.05));
setpoint_pose_local.header = xy.header;
setpoint_pose_local.pose.position.x = xy.point.x;
setpoint_pose_local.pose.position.y = xy.point.y;
} catch (tf2::TransformException& ex) {
// can't transform xy, use last known
ROS_WARN_THROTTLE(10, "can't transform: %s", ex.what());
} }
// transform altitude
try { // transform velocity
setpoint_pose_local.pose.position.z = tf_buffer.transform(setpoint_altitude, local_frame, ros::Duration(0.05)).point.z; if (setpoint_type == VELOCITY) {
} catch (tf2::TransformException& ex) { setpoint_velocity.header.stamp = stamp;
// can't transform altitude, use last known tf_buffer.transform(setpoint_velocity, setpoint_velocity_transformed, local_frame, ros::Duration(0.05));
ROS_WARN_THROTTLE(10, "can't transform: %s", ex.what());
} }
} catch (const tf2::TransformException& e) {
ROS_WARN_THROTTLE(10, "can't transform");
} }
// transform yaw
if (setpoint_yaw_type == YAW) {
try {
QuaternionStamped q;
q.header.stamp = stamp;
q.header.frame_id = yaw_frame_id;
q.quaternion = tf::createQuaternionMsgFromYaw(setpoint_yaw);
yaw_local = tf2::getYaw(tf_buffer.transform(q, local_frame, ros::Duration(0.05)).quaternion);
} catch (tf2::TransformException& ex) {
// can't transform yaw, use last known
ROS_WARN_THROTTLE(10, "can't transform: %s", ex.what());
}
}
// compute navigate setpoint
if (setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL) { if (setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL) {
position_msg.pose.orientation = setpoint_position_transformed.pose.orientation; // copy yaw
getNavigateSetpoint(stamp, nav_speed, position_msg.pose.position); getNavigateSetpoint(stamp, nav_speed, position_msg.pose.position);
if (setpoint_yaw_type == TOWARDS) { if (setpoint_yaw_type == TOWARDS) {
yaw_local = atan2(position_msg.pose.position.y - nav_start.pose.position.y, double yaw_towards = atan2(position_msg.pose.position.y - nav_start.pose.position.y,
position_msg.pose.position.x - nav_start.pose.position.x); position_msg.pose.position.x - nav_start.pose.position.x);
position_msg.pose.orientation = tf::createQuaternionMsgFromRollPitchYaw(0, 0, yaw_towards);
} }
position_msg.pose.orientation = tf::createQuaternionMsgFromYaw(yaw_local);
} }
if (setpoint_type == POSITION) { if (setpoint_type == POSITION) {
position_msg = setpoint_pose_local; position_msg = setpoint_position_transformed;
position_msg.pose.orientation = tf::createQuaternionMsgFromYaw(yaw_local);
} }
if (setpoint_type == POSITION || setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL) { if (setpoint_type == POSITION || setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL) {
@@ -527,14 +436,14 @@ void publish(const ros::Time stamp)
PositionTarget::IGNORE_AFY + PositionTarget::IGNORE_AFY +
PositionTarget::IGNORE_AFZ + PositionTarget::IGNORE_AFZ +
PositionTarget::IGNORE_YAW; PositionTarget::IGNORE_YAW;
position_raw_msg.yaw_rate = setpoint_rates.z; position_raw_msg.yaw_rate = setpoint_yaw_rate;
position_raw_msg.position = position_msg.pose.position; position_raw_msg.position = position_msg.pose.position;
position_raw_pub.publish(position_raw_msg); position_raw_pub.publish(position_raw_msg);
} }
// publish setpoint frame // publish setpoint frame
if (!setpoint.child_frame_id.empty()) { if (!setpoint.child_frame_id.empty()) {
if (setpoint.header.stamp >= position_msg.header.stamp) { if (setpoint.header.stamp == position_msg.header.stamp) {
return; // avoid TF_REPEATED_DATA warnings return; // avoid TF_REPEATED_DATA warnings
} }
@@ -546,22 +455,9 @@ void publish(const ros::Time stamp)
setpoint.header.stamp = position_msg.header.stamp; setpoint.header.stamp = position_msg.header.stamp;
transform_broadcaster->sendTransform(setpoint); transform_broadcaster->sendTransform(setpoint);
} }
// publish dynamic target frame
publishTarget(stamp);
} }
if (setpoint_type == VELOCITY) { if (setpoint_type == VELOCITY) {
// transform velocity to local frame
setpoint_velocity.header.stamp = stamp;
try {
setpoint_velocity_local = tf_buffer.transform(setpoint_velocity, local_frame, ros::Duration(0.05));
} catch (tf2::TransformException& ex) {
// can't transform velocity, use last known
ROS_WARN_THROTTLE(10, "can't transform: %s", ex.what());
}
// publish velocity
position_raw_msg.type_mask = PositionTarget::IGNORE_PX + position_raw_msg.type_mask = PositionTarget::IGNORE_PX +
PositionTarget::IGNORE_PY + PositionTarget::IGNORE_PY +
PositionTarget::IGNORE_PZ + PositionTarget::IGNORE_PZ +
@@ -569,22 +465,14 @@ void publish(const ros::Time stamp)
PositionTarget::IGNORE_AFY + PositionTarget::IGNORE_AFY +
PositionTarget::IGNORE_AFZ; PositionTarget::IGNORE_AFZ;
position_raw_msg.type_mask += setpoint_yaw_type == YAW ? PositionTarget::IGNORE_YAW_RATE : PositionTarget::IGNORE_YAW; position_raw_msg.type_mask += setpoint_yaw_type == YAW ? PositionTarget::IGNORE_YAW_RATE : PositionTarget::IGNORE_YAW;
position_raw_msg.velocity = setpoint_velocity_local.vector; position_raw_msg.velocity = setpoint_velocity_transformed.vector;
position_raw_msg.yaw = yaw_local; position_raw_msg.yaw = tf2::getYaw(setpoint_position_transformed.pose.orientation);
position_raw_msg.yaw_rate = setpoint_rates.z; position_raw_msg.yaw_rate = setpoint_yaw_rate;
position_raw_pub.publish(position_raw_msg); position_raw_pub.publish(position_raw_msg);
} }
if (setpoint_type == ATTITUDE) { if (setpoint_type == ATTITUDE) {
PoseStamped msg; attitude_pub.publish(setpoint_position_transformed);
msg.header.stamp = stamp;
msg.header.frame_id = local_frame;
msg.pose.orientation = tf::createQuaternionMsgFromRollPitchYaw(setpoint_roll, setpoint_pitch, yaw_local);
attitude_pub.publish(msg);
Thrust thrust_msg;
thrust_msg.header.stamp = stamp;
thrust_msg.thrust = setpoint_thrust;
thrust_pub.publish(thrust_msg); thrust_pub.publish(thrust_msg);
} }
@@ -593,12 +481,11 @@ void publish(const ros::Time stamp)
// thrust_pub.publish(thrust_msg); // thrust_pub.publish(thrust_msg);
// mavros rates topics waits for rates in local frame // mavros rates topics waits for rates in local frame
// use rates in body frame for simplicity // use rates in body frame for simplicity
AttitudeTarget att_raw_msg;
att_raw_msg.header.stamp = stamp; att_raw_msg.header.stamp = stamp;
att_raw_msg.header.frame_id = fcu_frame; att_raw_msg.header.frame_id = fcu_frame;
att_raw_msg.type_mask = AttitudeTarget::IGNORE_ATTITUDE; att_raw_msg.type_mask = AttitudeTarget::IGNORE_ATTITUDE;
att_raw_msg.body_rate = setpoint_rates; att_raw_msg.body_rate = rates_msg.twist.angular;
att_raw_msg.thrust = setpoint_thrust; att_raw_msg.thrust = thrust_msg.thrust;
attitude_raw_pub.publish(att_raw_msg); attitude_raw_pub.publish(att_raw_msg);
} }
} }
@@ -616,10 +503,10 @@ inline void checkManualControl()
if (check_kill_switch) { if (check_kill_switch) {
// switch values: https://github.com/PX4/PX4-Autopilot/blob/c302514a0809b1765fafd13c014d705446ae1113/msg/manual_control_setpoint.msg#L3 // 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 [[maybe_unused]] const uint8_t SWITCH_POS_NONE = 0; // switch is not mapped
const uint8_t SWITCH_POS_ON = 1; // switch activated [[maybe_unused]] const uint8_t SWITCH_POS_ON = 1; // switch activated
const uint8_t SWITCH_POS_MIDDLE = 2; // middle position [[maybe_unused]] 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_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 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; uint8_t kill_switch = (manual_control.buttons & (0b11 << KILL_SWITCH_BIT)) >> KILL_SWITCH_BIT;
@@ -638,59 +525,10 @@ inline void checkState()
throw std::runtime_error("No connection to FCU, https://clover.coex.tech/connection"); throw std::runtime_error("No connection to FCU, https://clover.coex.tech/connection");
} }
void publishState()
{
clover::State msg;
msg.mode = setpoint_type;
msg.yaw_mode = setpoint_yaw_type;
if (setpoint_position.header.frame_id.empty()) {
msg.x = NAN;
msg.y = NAN;
msg.z = NAN;
} else {
msg.x = setpoint_position.point.x;
msg.y = setpoint_position.point.y;
msg.z = setpoint_altitude.point.z;
}
msg.speed = nav_speed;
msg.lat = setpoint_lat;
msg.lon = setpoint_lon;
msg.vx = setpoint_velocity.vector.x;
msg.vy = setpoint_velocity.vector.y;
msg.vz = setpoint_velocity.vector.z;
msg.roll = setpoint_roll;
msg.pitch = setpoint_pitch;
msg.yaw = !yaw_frame_id.empty() ? setpoint_yaw : NAN;
msg.roll_rate = setpoint_rates.x;
msg.pitch_rate = setpoint_rates.y;
msg.yaw_rate = setpoint_rates.z;
msg.thrust = setpoint_thrust;
if (setpoint_type == VELOCITY) {
msg.xy_frame_id = setpoint_velocity.header.frame_id;
msg.z_frame_id = setpoint_velocity.header.frame_id;
} else {
msg.xy_frame_id = setpoint_position.header.frame_id;
msg.z_frame_id = setpoint_altitude.header.frame_id;
}
msg.yaw_frame_id = yaw_frame_id;
state_pub.publish(msg);
}
inline float safe(float value) {
return std::isfinite(value) ? value : 0;
}
#define ENSURE_FINITE(var) { if (!std::isfinite(var)) throw std::runtime_error(#var " argument cannot be NaN or Inf"); } #define ENSURE_FINITE(var) { if (!std::isfinite(var)) throw std::runtime_error(#var " argument cannot be NaN or Inf"); }
#define ENSURE_NON_INF(var) { if (std::isinf(var)) throw std::runtime_error(#var " argument cannot be Inf"); }
bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, float vy, float vz, bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, float vy, float vz,
float roll, float pitch, float yaw, float roll_rate, float pitch_rate, float yaw_rate, // editorconfig-checker-disable-line float pitch, float roll, float yaw, float pitch_rate, float roll_rate, float yaw_rate, // editorconfig-checker-disable-line
float lat, float lon, float thrust, float speed, string frame_id, bool auto_arm, // editorconfig-checker-disable-line float lat, float lon, float thrust, float speed, string frame_id, bool auto_arm, // editorconfig-checker-disable-line
uint8_t& success, string& message) // editorconfig-checker-disable-line uint8_t& success, string& message) // editorconfig-checker-disable-line
{ {
@@ -717,40 +555,69 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
auto search = reference_frames.find(frame_id); auto search = reference_frames.find(frame_id);
const string& reference_frame = search == reference_frames.end() ? frame_id : search->second; const string& reference_frame = search == reference_frames.end() ? frame_id : search->second;
ENSURE_NON_INF(x); // Serve "partial" commands
ENSURE_NON_INF(y);
ENSURE_NON_INF(z);
ENSURE_NON_INF(speed); // TODO: allow inf
ENSURE_NON_INF(vx);
ENSURE_NON_INF(vy);
ENSURE_NON_INF(vz);
ENSURE_NON_INF(roll);
ENSURE_NON_INF(pitch);
ENSURE_NON_INF(roll_rate);
ENSURE_NON_INF(pitch_rate);
ENSURE_NON_INF(yaw_rate);
ENSURE_NON_INF(thrust);
if (sp_type == NAVIGATE_GLOBAL) { if (!auto_arm && std::isfinite(yaw) &&
isnan(x) && isnan(y) && isnan(z) && isnan(vx) && isnan(vy) && isnan(vz) &&
isnan(pitch) && isnan(roll) && isnan(thrust) &&
isnan(lat) && isnan(lon)) {
// change only the yaw
if (setpoint_type == POSITION || setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL || setpoint_type == VELOCITY) {
if (!waitTransform(setpoint_position.header.frame_id, frame_id, stamp, transform_timeout))
throw std::runtime_error("Can't transform from " + frame_id + " to " + setpoint_position.header.frame_id);
message = "Changing yaw only";
QuaternionStamped q;
q.header.frame_id = frame_id;
q.header.stamp = stamp;
q.quaternion = tf::createQuaternionMsgFromYaw(yaw); // TODO: pitch=0, roll=0 is not totally correct
setpoint_position.pose.orientation = tf_buffer.transform(q, setpoint_position.header.frame_id).quaternion;
setpoint_yaw_type = YAW;
goto publish_setpoint;
} else {
throw std::runtime_error("Setting yaw is possible only when position or velocity setpoints active");
}
}
if (!auto_arm && std::isfinite(yaw_rate) &&
isnan(x) && isnan(y) && isnan(z) && isnan(vx) && isnan(vy) && isnan(vz) &&
isnan(pitch) && isnan(roll) && isnan(yaw) && isnan(thrust) &&
isnan(lat) && isnan(lon)) {
// change only the yaw rate
if (setpoint_type == POSITION || setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL || setpoint_type == VELOCITY) {
message = "Changing yaw rate only";
setpoint_yaw_type = YAW_RATE;
setpoint_yaw_rate = yaw_rate;
goto publish_setpoint;
} else {
throw std::runtime_error("Setting yaw rate is possible only when position or velocity setpoints active");
}
}
// Serve normal commands
if (sp_type == NAVIGATE || sp_type == POSITION) {
ENSURE_FINITE(x);
ENSURE_FINITE(y);
ENSURE_FINITE(z);
} else if (sp_type == NAVIGATE_GLOBAL) {
ENSURE_FINITE(lat); ENSURE_FINITE(lat);
ENSURE_FINITE(lon); ENSURE_FINITE(lon);
} ENSURE_FINITE(z);
} else if (sp_type == VELOCITY) {
if (isfinite(x) != isfinite(y)) { ENSURE_FINITE(vx);
throw std::runtime_error("x and y can be set only together"); ENSURE_FINITE(vy);
} ENSURE_FINITE(vz);
} else if (sp_type == ATTITUDE) {
if (isfinite(yaw_rate)) { ENSURE_FINITE(pitch);
if (sp_type > RATES && setpoint_type == ATTITUDE) { ENSURE_FINITE(roll);
throw std::runtime_error("Yaw rate cannot be set in attitude mode."); ENSURE_FINITE(thrust);
} } else if (sp_type == RATES) {
} ENSURE_FINITE(pitch_rate);
ENSURE_FINITE(roll_rate);
// set_altitude ENSURE_FINITE(thrust);
if (sp_type == _ALTITUDE) {
if (setpoint_type == VELOCITY || setpoint_type == ATTITUDE || setpoint_type == RATES) {
throw std::runtime_error("Altitude cannot be set in velocity, attitude or rates mode.");
}
} }
if (sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL) { if (sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL) {
@@ -764,13 +631,20 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
speed = default_speed; speed = default_speed;
} }
if (sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL || sp_type == POSITION || sp_type == VELOCITY) {
if (yaw_rate != 0 && !std::isnan(yaw))
throw std::runtime_error("Yaw value should be NaN for setting yaw rate");
if (std::isnan(yaw_rate) && std::isnan(yaw))
throw std::runtime_error("Both yaw and yaw_rate cannot be NaN");
}
if (sp_type == NAVIGATE_GLOBAL) { if (sp_type == NAVIGATE_GLOBAL) {
if (TIMEOUT(global_position, global_position_timeout)) if (TIMEOUT(global_position, global_position_timeout))
throw std::runtime_error("No global position"); throw std::runtime_error("No global position");
} }
// if any value need to be transformed to reference frame if (sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL || sp_type == POSITION || sp_type == VELOCITY || sp_type == ATTITUDE) {
if (isfinite(x) || isfinite(y) || isfinite(z) || isfinite(vx) || isfinite(vy) || isfinite(vz) || isfinite(yaw)) {
// make sure transform from frame_id to reference frame available // make sure transform from frame_id to reference frame available
if (!waitTransform(reference_frame, frame_id, stamp, transform_timeout)) if (!waitTransform(reference_frame, frame_id, stamp, transform_timeout))
throw std::runtime_error("Can't transform from " + frame_id + " to " + reference_frame); throw std::runtime_error("Can't transform from " + frame_id + " to " + reference_frame);
@@ -787,26 +661,15 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
auto xy_in_req_frame = tf_buffer.transform(pose_local, frame_id); auto xy_in_req_frame = tf_buffer.transform(pose_local, frame_id);
x = xy_in_req_frame.pose.position.x; x = xy_in_req_frame.pose.position.x;
y = xy_in_req_frame.pose.position.y; y = xy_in_req_frame.pose.position.y;
setpoint_lat = lat;
setpoint_lon = lon;
} }
// Everything fine - switch setpoint type // Everything fine - switch setpoint type
if (sp_type <= RATES) { setpoint_type = sp_type;
setpoint_type = sp_type;
}
if (setpoint_type != NAVIGATE && setpoint_type != NAVIGATE_GLOBAL) { if (sp_type != NAVIGATE && sp_type != NAVIGATE_GLOBAL) {
nav_from_sp_flag = false; nav_from_sp_flag = false;
} }
if (auto_arm || setpoint_type == VELOCITY || setpoint_type == ATTITUDE || setpoint_type == RATES) {
// invalidate position setpoint
setpoint_position.header.frame_id = "";
setpoint_altitude.header.frame_id = "";
yaw_frame_id = "";
}
if (sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL) { if (sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL) {
// starting point // starting point
if (nav_from_sp && nav_from_sp_flag) { if (nav_from_sp && nav_from_sp_flag) {
@@ -815,139 +678,89 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
} else { } else {
nav_start = local_position; nav_start = local_position;
} }
nav_speed = speed;
if (!isnan(speed)) {
nav_speed = speed;
}
nav_from_sp_flag = true; nav_from_sp_flag = true;
} }
// handle position // if (sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL || sp_type == POSITION || sp_type == VELOCITY) {
if (setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL || setpoint_type == POSITION) { // if (std::isnan(yaw) && yaw_rate == 0) {
// // keep yaw unchanged
// // TODO: this is incorrect, because we need yaw in desired frame
// yaw = tf2::getYaw(local_position.pose.orientation);
// }
// }
PointStamped desired; if (sp_type == POSITION || sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL || sp_type == VELOCITY || sp_type == ATTITUDE) {
desired.header.frame_id = frame_id; // destination point and/or attitude
desired.header.stamp = stamp; PoseStamped ps;
desired.point.x = safe(x); ps.header.frame_id = frame_id;
desired.point.y = safe(y); ps.header.stamp = stamp;
desired.point.z = safe(z); ps.pose.position.x = x;
ps.pose.position.y = y;
ps.pose.position.z = z;
ps.pose.orientation.w = 1.0; // Ensure quaternion is always valid
// transform to reference frame if (sp_type == ATTITUDE) {
desired = tf_buffer.transform(desired, reference_frame); ps.pose.position.x = 0;
ps.pose.position.y = 0;
// set horizontal position ps.pose.position.z = 0;
if (isfinite(x) && isfinite(y)) { ps.pose.orientation = tf::createQuaternionMsgFromRollPitchYaw(roll, pitch, yaw);
setpoint_position = desired; } else if (std::isnan(yaw)) {
} else if (setpoint_position.header.frame_id.empty()) { setpoint_yaw_type = YAW_RATE;
// TODO: use transform for current stamp setpoint_yaw_rate = yaw_rate;
setpoint_position.header = local_position.header; } else if (std::isinf(yaw) && yaw > 0) {
setpoint_position.point = local_position.pose.position;
}
// set altitude
if (isfinite(z)) {
setpoint_altitude = desired;
} else if (setpoint_altitude.header.frame_id.empty()) {
setpoint_altitude.header = local_position.header;
setpoint_altitude.point = local_position.pose.position;
}
}
// handle velocity
if (sp_type == VELOCITY) {
// TODO: allow setting different modes by altitude and xy
Vector3Stamped desired;
desired.header.frame_id = frame_id;
desired.header.stamp = stamp;
desired.vector.x = safe(vx);
desired.vector.y = safe(vy);
desired.vector.z = safe(vz);
// transform to reference frame
desired = tf_buffer.transform(desired, reference_frame);
setpoint_velocity.header = desired.header;
// set horizontal velocity
if (isfinite(vx) && isfinite(vy)) {
setpoint_velocity.vector.x = desired.vector.x;
setpoint_velocity.vector.y = desired.vector.y;
}
// set vertical velocity
if (isfinite(vz)) {
setpoint_velocity.vector.z = desired.vector.z;
}
}
// handle yaw
if (sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL || sp_type == POSITION || sp_type == VELOCITY || sp_type == ATTITUDE || sp_type == _YAW) {
if (isfinite(yaw)) {
setpoint_yaw_type = YAW;
QuaternionStamped desired;
desired.header.frame_id = frame_id;
desired.header.stamp = stamp;
desired.quaternion = tf::createQuaternionMsgFromYaw(yaw);
// transform to reference frame
desired = tf_buffer.transform(desired, reference_frame);
setpoint_yaw = tf2::getYaw(desired.quaternion);
yaw_frame_id = reference_frame;
} else if (isinf(yaw) && yaw > 0) {
// yaw towards // yaw towards
setpoint_yaw_type = TOWARDS; setpoint_yaw_type = TOWARDS;
yaw = 0;
} else if (yaw_frame_id.empty() || sp_type == _YAW) { setpoint_yaw_rate = 0;
// yaw is nan and not set previously OR set_yaw(yaw=nan) was called } else {
setpoint_yaw_type = YAW; setpoint_yaw_type = YAW;
setpoint_yaw = tf2::getYaw(local_position.pose.orientation); // set yaw to current yaw setpoint_yaw_rate = 0;
yaw_frame_id = local_position.header.frame_id; ps.pose.orientation = tf::createQuaternionMsgFromYaw(yaw);
} }
tf_buffer.transform(ps, setpoint_position, reference_frame);
} }
// handle roll if (sp_type == VELOCITY) {
if (isfinite(roll)) { Vector3Stamped vel;
setpoint_roll = roll; vel.header.frame_id = frame_id;
vel.header.stamp = stamp;
vel.vector.x = vx;
vel.vector.y = vy;
vel.vector.z = vz;
tf_buffer.transform(vel, setpoint_velocity, reference_frame);
} }
// handle pitch if (sp_type == ATTITUDE || sp_type == RATES) {
if (isfinite(pitch)) { thrust_msg.thrust = thrust;
setpoint_pitch = pitch;
} }
// handle yaw rate if (sp_type == RATES) {
if (isfinite(yaw_rate)) { rates_msg.twist.angular.x = roll_rate;
setpoint_yaw_type = YAW_RATE; rates_msg.twist.angular.y = pitch_rate;
setpoint_rates.z = yaw_rate; rates_msg.twist.angular.z = yaw_rate;
}
// handle pitch rate
if (isfinite(roll_rate)) {
setpoint_rates.x = roll_rate;
}
// handle roll rate
if (isfinite(pitch_rate)) {
setpoint_rates.y = pitch_rate;
}
// handle thrust
if (isfinite(thrust)) {
setpoint_thrust = thrust;
} }
wait_armed = auto_arm; wait_armed = auto_arm;
publish_setpoint:
publish(stamp); // calculate initial transformed messages first publish(stamp); // calculate initial transformed messages first
setpoint_timer.start(); setpoint_timer.start();
if (setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL || setpoint_type == POSITION) { // publish target frame
publishTarget(stamp, true); if (!target.child_frame_id.empty()) {
if (setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL || setpoint_type == POSITION) {
target.header.frame_id = setpoint_position.header.frame_id;
target.header.stamp = stamp;
target.transform.translation.x = setpoint_position.pose.position.x;
target.transform.translation.y = setpoint_position.pose.position.y;
target.transform.translation.z = setpoint_position.pose.position.z;
target.transform.rotation = setpoint_position.pose.orientation;
static_transform_broadcaster->sendTransform(target);
}
} }
publishState();
if (auto_arm) { if (auto_arm) {
offboardAndArm(); offboardAndArm();
wait_armed = false; wait_armed = false;
@@ -972,42 +785,30 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
} }
bool navigate(Navigate::Request& req, Navigate::Response& res) { bool navigate(Navigate::Request& req, Navigate::Response& res) {
return serve(NAVIGATE, req.x, req.y, req.z, NAN, NAN, NAN, NAN, NAN, req.yaw, NAN, NAN, NAN, NAN, NAN, NAN, req.speed, req.frame_id, req.auto_arm, res.success, res.message); return serve(NAVIGATE, req.x, req.y, req.z, NAN, NAN, NAN, NAN, NAN, req.yaw, NAN, NAN, req.yaw_rate, NAN, NAN, NAN, req.speed, req.frame_id, req.auto_arm, res.success, res.message);
} }
bool navigateGlobal(NavigateGlobal::Request& req, NavigateGlobal::Response& res) { bool navigateGlobal(NavigateGlobal::Request& req, NavigateGlobal::Response& res) {
return serve(NAVIGATE_GLOBAL, NAN, NAN, req.z, NAN, NAN, NAN, NAN, NAN, req.yaw, NAN, NAN, NAN, req.lat, req.lon, NAN, req.speed, req.frame_id, req.auto_arm, res.success, res.message); return serve(NAVIGATE_GLOBAL, NAN, NAN, req.z, NAN, NAN, NAN, NAN, NAN, req.yaw, NAN, NAN, req.yaw_rate, req.lat, req.lon, NAN, req.speed, req.frame_id, req.auto_arm, res.success, res.message);
}
bool setAltitude(SetAltitude::Request& req, SetAltitude::Response& res) {
return serve(_ALTITUDE, NAN, NAN, req.z, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, req.frame_id, false, res.success, res.message);
}
bool setYaw(SetYaw::Request& req, SetYaw::Response& res) {
return serve(_YAW, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, req.yaw, NAN, NAN, NAN, NAN, NAN, NAN, NAN, req.frame_id, false, res.success, res.message);
}
bool setYawRate(SetYawRate::Request& req, SetYawRate::Response& res) {
return serve(_YAW_RATE, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, req.yaw_rate, NAN, NAN, NAN, NAN, "", false, res.success, res.message);
} }
bool setPosition(SetPosition::Request& req, SetPosition::Response& res) { bool setPosition(SetPosition::Request& req, SetPosition::Response& res) {
return serve(POSITION, req.x, req.y, req.z, NAN, NAN, NAN, NAN, NAN, req.yaw, NAN, NAN, NAN, NAN, NAN, NAN, NAN, req.frame_id, req.auto_arm, res.success, res.message); return serve(POSITION, req.x, req.y, req.z, NAN, NAN, NAN, NAN, NAN, req.yaw, NAN, NAN, req.yaw_rate, NAN, NAN, NAN, NAN, req.frame_id, req.auto_arm, res.success, res.message);
} }
bool setVelocity(SetVelocity::Request& req, SetVelocity::Response& res) { bool setVelocity(SetVelocity::Request& req, SetVelocity::Response& res) {
return serve(VELOCITY, NAN, NAN, NAN, req.vx, req.vy, req.vz, NAN, NAN, req.yaw, NAN, NAN, NAN, NAN, NAN, NAN, NAN, req.frame_id, req.auto_arm, res.success, res.message); return serve(VELOCITY, NAN, NAN, NAN, req.vx, req.vy, req.vz, NAN, NAN, req.yaw, NAN, NAN, req.yaw_rate, NAN, NAN, NAN, NAN, req.frame_id, req.auto_arm, res.success, res.message);
} }
bool setAttitude(SetAttitude::Request& req, SetAttitude::Response& res) { bool setAttitude(SetAttitude::Request& req, SetAttitude::Response& res) {
return serve(ATTITUDE, NAN, NAN, NAN, NAN, NAN, NAN, req.roll, req.pitch, req.yaw, NAN, NAN, NAN, NAN, NAN, req.thrust, NAN, req.frame_id, req.auto_arm, res.success, res.message); return serve(ATTITUDE, NAN, NAN, NAN, NAN, NAN, NAN, req.pitch, req.roll, req.yaw, NAN, NAN, NAN, NAN, NAN, req.thrust, NAN, req.frame_id, req.auto_arm, res.success, res.message);
} }
bool setRates(SetRates::Request& req, SetRates::Response& res) { bool setRates(SetRates::Request& req, SetRates::Response& res) {
return serve(RATES, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, req.roll_rate, req.pitch_rate, req.yaw_rate, NAN, NAN, req.thrust, NAN, "", req.auto_arm, res.success, res.message); 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 { try {
if (busy) if (busy)
@@ -1036,7 +837,9 @@ bool land(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
auto start = ros::Time::now(); auto start = ros::Time::now();
while (ros::ok()) { while (ros::ok()) {
if (state.mode == "AUTO.LAND") { if (state.mode == "AUTO.LAND") {
break; res.success = true;
busy = false;
return true;
} }
if (ros::Time::now() - start > land_timeout) if (ros::Time::now() - start > land_timeout)
throw std::runtime_error("Land request timed out"); throw std::runtime_error("Land request timed out");
@@ -1045,18 +848,6 @@ bool land(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
r.sleep(); r.sleep();
} }
// stop setpoints and invalidate position setpoint
setpoint_timer.stop();
setpoint_type = NONE;
setpoint_position.header.frame_id = "";
setpoint_altitude.header.frame_id = "";
yaw_frame_id = "";
publishState();
res.success = true;
busy = false;
return true;
} catch (const std::exception& e) { } catch (const std::exception& e) {
res.message = e.what(); res.message = e.what();
ROS_INFO("%s", e.what()); ROS_INFO("%s", e.what());
@@ -1066,18 +857,6 @@ bool land(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
return false; return false;
} }
bool release(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
{
setpoint_timer.stop();
setpoint_type = NONE;
setpoint_position.header.frame_id = "";
setpoint_altitude.header.frame_id = "";
yaw_frame_id = "";
publishState();
res.success = true;
return true;
}
int main(int argc, char **argv) int main(int argc, char **argv)
{ {
ros::init(argc, argv, "simple_offboard"); ros::init(argc, argv, "simple_offboard");
@@ -1099,7 +878,6 @@ int main(int argc, char **argv)
nh_priv.param("check_kill_switch", check_kill_switch, true); nh_priv.param("check_kill_switch", check_kill_switch, true);
nh_priv.param("default_speed", default_speed, 0.5f); nh_priv.param("default_speed", default_speed, 0.5f);
nh_priv.param<string>("body_frame", body.child_frame_id, "body"); nh_priv.param<string>("body_frame", body.child_frame_id, "body");
nh_priv.param<string>("terrain_frame", terrain.child_frame_id, "terrain");
nh_priv.getParam("reference_frames", reference_frames); nh_priv.getParam("reference_frames", reference_frames);
// Default reference frames // Default reference frames
@@ -1135,12 +913,6 @@ int main(int argc, char **argv)
auto manual_control_sub = nh.subscribe(mavros + "/manual_control/control", 1, &handleMessage<mavros_msgs::ManualControl, manual_control>); auto manual_control_sub = nh.subscribe(mavros + "/manual_control/control", 1, &handleMessage<mavros_msgs::ManualControl, manual_control>);
auto local_position_sub = nh.subscribe(mavros + "/local_position/pose", 1, &handleLocalPosition); auto local_position_sub = nh.subscribe(mavros + "/local_position/pose", 1, &handleLocalPosition);
ros::Subscriber altitude_sub;
if (!body.child_frame_id.empty() && !terrain.child_frame_id.empty()) {
terrain.header.frame_id = local_frame;
altitude_sub = nh.subscribe(mavros + "/altitude", 1, &handleAltitude);
}
// Setpoint publishers // Setpoint publishers
position_pub = nh.advertise<PoseStamped>(mavros + "/setpoint_position/local", 1); position_pub = nh.advertise<PoseStamped>(mavros + "/setpoint_position/local", 1);
position_raw_pub = nh.advertise<PositionTarget>(mavros + "/setpoint_raw/local", 1); position_raw_pub = nh.advertise<PositionTarget>(mavros + "/setpoint_raw/local", 1);
@@ -1149,22 +921,15 @@ int main(int argc, char **argv)
rates_pub = nh.advertise<TwistStamped>(mavros + "/setpoint_attitude/cmd_vel", 1); rates_pub = nh.advertise<TwistStamped>(mavros + "/setpoint_attitude/cmd_vel", 1);
thrust_pub = nh.advertise<Thrust>(mavros + "/setpoint_attitude/thrust", 1); thrust_pub = nh.advertise<Thrust>(mavros + "/setpoint_attitude/thrust", 1);
// State publisher
state_pub = nh_priv.advertise<clover::State>("state", 1, true);
// Service servers // Service servers
auto gt_serv = nh.advertiseService("get_telemetry", &getTelemetry); auto gt_serv = nh.advertiseService("get_telemetry", &getTelemetry);
auto na_serv = nh.advertiseService("navigate", &navigate); auto na_serv = nh.advertiseService("navigate", &navigate);
auto ng_serv = nh.advertiseService("navigate_global", &navigateGlobal); auto ng_serv = nh.advertiseService("navigate_global", &navigateGlobal);
auto sl_serv = nh.advertiseService("set_altitude", &setAltitude);
auto ya_serv = nh.advertiseService("set_yaw", &setYaw);
auto yr_serv = nh.advertiseService("set_yaw_rate", &setYawRate);
auto sp_serv = nh.advertiseService("set_position", &setPosition); auto sp_serv = nh.advertiseService("set_position", &setPosition);
auto sv_serv = nh.advertiseService("set_velocity", &setVelocity); auto sv_serv = nh.advertiseService("set_velocity", &setVelocity);
auto sa_serv = nh.advertiseService("set_attitude", &setAttitude); auto sa_serv = nh.advertiseService("set_attitude", &setAttitude);
auto sr_serv = nh.advertiseService("set_rates", &setRates); auto sr_serv = nh.advertiseService("set_rates", &setRates);
auto ld_serv = nh.advertiseService("land", &land); auto ld_serv = nh.advertiseService("land", &land);
auto rl_serv = nh_priv.advertiseService("release", &release);
// Setpoint timer // Setpoint timer
setpoint_timer = nh.createTimer(ros::Duration(1 / nh_priv.param("setpoint_rate", 30.0)), &publishSetpoint, false, false); setpoint_timer = nh.createTimer(ros::Duration(1 / nh_priv.param("setpoint_rate", 30.0)), &publishSetpoint, false, false);
@@ -1172,7 +937,7 @@ int main(int argc, char **argv)
position_msg.header.frame_id = local_frame; position_msg.header.frame_id = local_frame;
position_raw_msg.header.frame_id = local_frame; position_raw_msg.header.frame_id = local_frame;
position_raw_msg.coordinate_frame = PositionTarget::FRAME_LOCAL_NED; position_raw_msg.coordinate_frame = PositionTarget::FRAME_LOCAL_NED;
//rates_msg.header.frame_id = fcu_frame; rates_msg.header.frame_id = fcu_frame;
ROS_INFO("ready"); ROS_INFO("ready");
ros::spin(); ros::spin();

View File

@@ -25,7 +25,7 @@
using std::string; using std::string;
using namespace geometry_msgs; using namespace geometry_msgs;
bool reset_flag = true; // offset should be reset on the start bool reset_flag = false;
string local_frame_id, frame_id, child_frame_id, offset_frame_id; string local_frame_id, frame_id, child_frame_id, offset_frame_id;
tf2_ros::Buffer tf_buffer; tf2_ros::Buffer tf_buffer;
ros::Publisher vpe_pub; ros::Publisher vpe_pub;
@@ -33,14 +33,14 @@ ros::Subscriber local_position_sub;
ros::Timer zero_timer; ros::Timer zero_timer;
PoseStamped vpe, pose; PoseStamped vpe, pose;
ros::Time got_local_pos(0); ros::Time got_local_pos(0);
ros::Duration publish_zero_timeout, publish_zero_duration, offset_timeout; ros::Duration publish_zero_timout, publish_zero_duration, offset_timeout;
TransformStamped offset; TransformStamped offset;
void publishZero(const ros::TimerEvent& e) void publishZero(const ros::TimerEvent& e)
{ {
if (!vpe.header.stamp.isZero() && e.current_real - vpe.header.stamp < publish_zero_timeout) return; // have vpe if (!vpe.header.stamp.isZero() && e.current_real - vpe.header.stamp < publish_zero_timout) return; // have vpe
if (!pose.header.stamp.isZero() && e.current_real - pose.header.stamp < publish_zero_timeout) { // 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()) { if (got_local_pos.isZero()) {
ROS_INFO("got local position"); ROS_INFO("got local position");
got_local_pos = e.current_real; 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; reset_flag = true;
res.success = true; res.success = true;
@@ -124,8 +124,8 @@ int main(int argc, char **argv) {
nh_priv.param<string>("frame_id", frame_id, ""); nh_priv.param<string>("frame_id", frame_id, "");
nh_priv.param<string>("offset_frame_id", offset_frame_id, ""); nh_priv.param<string>("offset_frame_id", offset_frame_id, "");
nh.param<string>("mavros/local_position/frame_id", local_frame_id, "map"); nh_priv.param<string>("mavros/local_position/frame_id", local_frame_id, "map");
nh.param<string>("mavros/local_position/tf/child_frame_id", child_frame_id, "base_link"); nh_priv.param<string>("mavros/local_position/tf/child_frame_id", child_frame_id, "base_link");
offset_timeout = ros::Duration(nh_priv.param("offset_timeout", 3.0)); offset_timeout = ros::Duration(nh_priv.param("offset_timeout", 3.0));
if (!frame_id.empty()) { if (!frame_id.empty()) {
@@ -144,7 +144,7 @@ int main(int argc, char **argv) {
if (nh_priv.param("force_init", false) || nh_priv.param("publish_zero", false)) { // publish_zero is old name if (nh_priv.param("force_init", false) || nh_priv.param("publish_zero", false)) { // publish_zero is old name
// publish zero to initialize the local position // publish zero to initialize the local position
zero_timer = nh.createTimer(ros::Duration(0.1), &publishZero); zero_timer = nh.createTimer(ros::Duration(0.1), &publishZero);
publish_zero_timeout = ros::Duration(nh_priv.param("force_init_timeout", 5.0)); publish_zero_timout = ros::Duration(nh_priv.param("force_init_timeout", 5.0));
publish_zero_duration = ros::Duration(nh_priv.param("force_init_duration", 5.0)); publish_zero_duration = ros::Duration(nh_priv.param("force_init_duration", 5.0));
local_position_sub = nh.subscribe("mavros/local_position/pose", 1, &localPositionCallback); local_position_sub = nh.subscribe("mavros/local_position/pose", 1, &localPositionCallback);
} }

View File

@@ -1,4 +0,0 @@
#!/usr/bin/env bash
export ROSWWW_DEFAULT=clover
rosrun roswww_static update

View File

@@ -13,11 +13,11 @@ float32 alt
float32 vx float32 vx
float32 vy float32 vy
float32 vz float32 vz
float32 roll
float32 pitch float32 pitch
float32 roll
float32 yaw float32 yaw
float32 roll_rate
float32 pitch_rate float32 pitch_rate
float32 roll_rate
float32 yaw_rate float32 yaw_rate
float32 voltage float32 voltage
float32 cell_voltage float32 cell_voltage

View File

@@ -2,6 +2,7 @@ float32 x
float32 y float32 y
float32 z float32 z
float32 yaw float32 yaw
float32 yaw_rate
float32 speed float32 speed
string frame_id string frame_id
bool auto_arm bool auto_arm

View File

@@ -2,6 +2,7 @@ float64 lat
float64 lon float64 lon
float32 z float32 z
float32 yaw float32 yaw
float32 yaw_rate
float32 speed float32 speed
string frame_id string frame_id
bool auto_arm bool auto_arm

View File

@@ -1,5 +0,0 @@
float32 z
string frame_id
---
bool success
string message

View File

@@ -1,5 +1,5 @@
float32 roll
float32 pitch float32 pitch
float32 roll
float32 yaw float32 yaw
float32 thrust float32 thrust
string frame_id string frame_id

View File

@@ -2,6 +2,7 @@ float32 x
float32 y float32 y
float32 z float32 z
float32 yaw float32 yaw
float32 yaw_rate
string frame_id string frame_id
bool auto_arm bool auto_arm
--- ---

View File

@@ -1,5 +1,5 @@
float32 roll_rate
float32 pitch_rate float32 pitch_rate
float32 roll_rate
float32 yaw_rate float32 yaw_rate
float32 thrust float32 thrust
bool auto_arm bool auto_arm

View File

@@ -2,6 +2,7 @@ float32 vx
float32 vy float32 vy
float32 vz float32 vz
float32 yaw float32 yaw
float32 yaw_rate
string frame_id string frame_id
bool auto_arm bool auto_arm
--- ---

View File

@@ -1,5 +0,0 @@
float32 yaw
string frame_id
---
bool success
string message

View File

@@ -1,4 +0,0 @@
float32 yaw_rate
---
bool success
string message

View File

@@ -3,7 +3,6 @@ import rospy
import pytest import pytest
from mavros_msgs.msg import State from mavros_msgs.msg import State
from clover import srv from clover import srv
import time
@pytest.fixture() @pytest.fixture()
def node(): def node():
@@ -25,7 +24,6 @@ def test_simple_offboard_services_available():
rospy.wait_for_service('set_attitude', timeout=5) rospy.wait_for_service('set_attitude', timeout=5)
rospy.wait_for_service('set_rates', timeout=5) rospy.wait_for_service('set_rates', timeout=5)
rospy.wait_for_service('land', timeout=5) rospy.wait_for_service('land', timeout=5)
rospy.wait_for_service('simple_offboard/release', timeout=5)
def test_web_video_server(node): def test_web_video_server(node):
try: try:
@@ -61,18 +59,3 @@ def test_blocks(node):
t.join() t.join()
assert wait_print.result == 'test' assert wait_print.result == 'test'
def test_long_callback():
from clover import long_callback
from time import sleep
# very basic test for long_callback
@long_callback
def cb(i):
cb.counter += i
cb.counter = 0
cb(2)
sleep(0.1)
cb(3)
sleep(1)
assert cb.counter == 5

View File

@@ -37,9 +37,6 @@
<node name="clover_blocks" pkg="clover_blocks" type="clover_blocks" output="screen" required="true"/> <node name="clover_blocks" pkg="clover_blocks" type="clover_blocks" output="screen" required="true"/>
<node pkg="topic_tools" name="main_camera_throttle" type="throttle" ns="main_camera"
args="messages image_raw 5.0 image_raw_throttled" required="true"/>
<param name="test_module" value="$(find clover)/test/basic.py"/> <param name="test_module" value="$(find clover)/test/basic.py"/>
<test test-name="basic_test" pkg="ros_pytest" type="ros_pytest_runner"/> <test test-name="basic_test" pkg="ros_pytest" type="ros_pytest_runner"/>
</launch> </launch>

View File

@@ -1,402 +0,0 @@
import rospy
import pytest
from pytest import approx
import threading
import mavros_msgs.msg
from geometry_msgs.msg import PoseStamped
from clover import srv
from clover.msg import State
from math import nan, inf
import tf2_ros
import tf2_geometry_msgs
@pytest.fixture()
def node():
return rospy.init_node('offboard_test', anonymous=True)
@pytest.fixture
def tf_buffer():
buf = tf2_ros.Buffer()
tf2_ros.TransformListener(buf)
return buf
def get_state():
return rospy.wait_for_message('/simple_offboard/state', State, timeout=1)
def get_navigate_target(tf_buffer):
target = tf_buffer.lookup_transform('map', 'navigate_target', rospy.get_rostime(), rospy.Duration(1))
assert target.child_frame_id == 'navigate_target'
return target
def test_offboard(node, tf_buffer):
navigate = rospy.ServiceProxy('navigate', srv.Navigate)
set_position = rospy.ServiceProxy('set_position', srv.SetPosition)
set_altitude = rospy.ServiceProxy('set_altitude', srv.SetAltitude)
set_yaw = rospy.ServiceProxy('set_yaw', srv.SetYaw)
set_yaw_rate = rospy.ServiceProxy('set_yaw_rate', srv.SetYawRate)
set_velocity = rospy.ServiceProxy('set_velocity', srv.SetVelocity)
set_attitude = rospy.ServiceProxy('set_attitude', srv.SetAttitude)
set_rates = rospy.ServiceProxy('set_rates', srv.SetRates)
get_telemetry = rospy.ServiceProxy('get_telemetry', srv.GetTelemetry)
res = navigate()
assert res.success == False
assert res.message.startswith('State timeout')
telem = get_telemetry()
assert telem.connected == False
state_pub = rospy.Publisher('/mavros/state', mavros_msgs.msg.State, latch=True, queue_size=1)
state_msg = mavros_msgs.msg.State(mode='OFFBOARD', armed=True)
def publish_state():
r = rospy.Rate(2)
while not rospy.is_shutdown():
state_msg.header.stamp = rospy.Time.now()
state_pub.publish(state_msg)
r.sleep()
# start publishing state
threading.Thread(target=publish_state, daemon=True).start()
rospy.sleep(0.5)
telem = get_telemetry()
assert telem.connected == False
res = navigate()
assert res.success == False
assert res.message.startswith('No connection to FCU')
state_msg.connected = True
rospy.sleep(1)
telem = get_telemetry()
assert telem.connected == True
res = navigate()
assert res.success == False
assert res.message.startswith('No local position')
local_position_pub = rospy.Publisher('/mavros/local_position/pose', PoseStamped, latch=True, queue_size=1)
local_position_msg = PoseStamped()
local_position_msg.header.frame_id = 'map'
local_position_msg.pose.position.x = 1
local_position_msg.pose.position.y = 2
local_position_msg.pose.position.z = 3
local_position_msg.pose.orientation.w = 1
def publish_local_position():
r = rospy.Rate(30)
while not rospy.is_shutdown():
local_position_msg.header.stamp = rospy.Time.now()
local_position_pub.publish(local_position_msg)
r.sleep()
# start publishing local position
threading.Thread(target=publish_local_position, daemon=True).start()
rospy.sleep(0.5)
# check body frame
body = tf_buffer.lookup_transform('map', 'body', rospy.get_rostime(), rospy.Duration(1))
assert body.child_frame_id == 'body'
assert body.transform.translation.x == approx(1)
assert body.transform.translation.y == approx(2)
assert body.transform.translation.z == approx(3)
res = navigate(x=3, y=2, z=1, frame_id='map')
assert res.success == True
state = get_state()
assert state.mode == State.MODE_NAVIGATE
assert state.yaw_mode == State.YAW_MODE_YAW
assert state.x == 3
assert state.y == 2
assert state.z == 1
assert state.yaw == 0
assert state.xy_frame_id == 'map'
assert state.z_frame_id == 'map'
assert state.yaw_frame_id == 'map'
target = get_navigate_target(tf_buffer)
assert target.header.frame_id == 'map'
assert target.transform.translation.x == approx(3)
assert target.transform.translation.y == approx(2)
assert target.transform.translation.z == approx(1)
assert target.transform.rotation.x == 0
assert target.transform.rotation.y == 0
assert target.transform.rotation.z == 0
assert target.transform.rotation.w == 1
# try to set only the y
res = navigate(x=nan, y=1, z=nan)
assert res.success == False
assert res.message.startswith('x and y can be set only together')
# set z in body frame
res = navigate(x=nan, y=nan, z=1, frame_id='body')
assert res.success == True
state = get_state()
assert state.mode == State.MODE_NAVIGATE
assert state.yaw_mode == State.YAW_MODE_YAW
assert state.x == 3
assert state.y == 2
assert state.z == 4
assert state.yaw == 0
assert state.xy_frame_id == 'map'
assert state.z_frame_id == 'map'
assert state.yaw_frame_id == 'map'
# set xy in test frame
res = navigate(x=1, y=2, z=nan, frame_id='test')
assert res.success == True
state = get_state()
assert state.mode == State.MODE_NAVIGATE
assert state.yaw_mode == State.YAW_MODE_YAW
assert state.x == 1
assert state.y == 2
assert state.z == 4
assert state.yaw == 0
assert state.xy_frame_id == 'test'
assert state.z_frame_id == 'map'
assert state.yaw_frame_id == 'test'
# auto_arm should invalidate the setpoint
res = navigate(x=nan, y=nan, z=1, frame_id='map', auto_arm=True)
assert res.success == True
state = get_state()
assert state.mode == State.MODE_NAVIGATE
assert state.yaw_mode == State.YAW_MODE_YAW
assert state.x == 1
assert state.y == 2
assert state.z == 1
assert state.yaw == 0
assert state.xy_frame_id == 'map'
assert state.z_frame_id == 'map'
assert state.yaw_frame_id == 'map'
# set_attitude should invalidate the setpoint
res = set_attitude()
assert res.success == True
res = navigate(x=5, y=6, z=nan, yaw=nan, frame_id='map')
assert res.success == True
state = get_state()
assert state.mode == State.MODE_NAVIGATE
assert state.yaw_mode == State.YAW_MODE_YAW
assert state.x == 5
assert state.y == 6
assert state.z == 3
assert state.yaw == 0
assert state.xy_frame_id == 'map'
assert state.z_frame_id == 'map'
assert state.yaw_frame_id == 'map'
# test set_altitude
res = set_altitude(z=7, frame_id='test')
assert res.success == True
state = get_state()
assert state.mode == State.MODE_NAVIGATE
assert state.yaw_mode == State.YAW_MODE_YAW
assert state.x == 5
assert state.y == 6
assert state.z == 7
assert state.yaw == 0
assert state.xy_frame_id == 'map'
assert state.z_frame_id == 'test'
assert state.yaw_frame_id == 'map'
# test set_yaw
res = set_yaw(yaw=0.5, frame_id='test2')
assert res.success == True
state = get_state()
assert state.mode == State.MODE_NAVIGATE
assert state.yaw_mode == State.YAW_MODE_YAW
assert state.x == 5
assert state.y == 6
assert state.z == 7
assert state.yaw == 0.5
assert state.xy_frame_id == 'map'
assert state.z_frame_id == 'test'
assert state.yaw_frame_id == 'test2'
# test set_yaw_rate
res = set_yaw_rate(yaw_rate=2)
assert res.success == True
state = get_state()
assert state.mode == State.MODE_NAVIGATE
assert state.yaw_mode == State.YAW_MODE_YAW_RATE
assert state.x == 5
assert state.y == 6
assert state.z == 7
assert state.yaw_rate == 2
assert state.xy_frame_id == 'map'
assert state.z_frame_id == 'test'
# navigate(yaw=nan) should keep yaw rate mode
res = navigate(x=nan, y=nan, z=nan, yaw=nan)
assert res.success == True
state = get_state()
assert state.mode == State.MODE_NAVIGATE
assert state.yaw_mode == State.YAW_MODE_YAW_RATE
assert state.x == 5
assert state.y == 6
assert state.z == 7
assert state.yaw_rate == 2
assert state.xy_frame_id == 'map'
assert state.z_frame_id == 'test'
# set_yaw(nan) should change back to yaw mode
res = set_yaw(yaw=nan)
assert res.success == True
state = get_state()
assert state.mode == State.MODE_NAVIGATE
assert state.yaw_mode == State.YAW_MODE_YAW
assert state.yaw == 0
assert state.yaw_frame_id == 'map'
# test set_position
res = set_position(x=nan, y=nan, z=13, yaw=nan, frame_id='test2')
assert res.success == True
state = get_state()
assert state.mode == State.MODE_POSITION
assert state.yaw_mode == State.YAW_MODE_YAW
assert state.x == 5
assert state.y == 6
assert state.z == 13
assert state.yaw == 0
assert state.xy_frame_id == 'map'
assert state.z_frame_id == 'test2'
assert state.yaw_frame_id == 'map'
# set_altitude should not change the mode
res = set_altitude(z=3, frame_id='test')
assert res.success == True
state = get_state()
assert state.mode == State.MODE_POSITION
assert state.yaw_mode == State.YAW_MODE_YAW
assert state.x == 5
assert state.y == 6
assert state.z == 3
assert state.yaw == 0
assert state.xy_frame_id == 'map'
assert state.z_frame_id == 'test'
assert state.yaw_frame_id == 'map'
# set_yaw should not change the main mode
res = set_yaw(yaw=1, frame_id='test2')
assert res.success == True
state = get_state()
assert state.mode == State.MODE_POSITION
assert state.yaw_mode == State.YAW_MODE_YAW
assert state.x == 5
assert state.y == 6
assert state.z == 3
assert state.yaw == 1
assert state.xy_frame_id == 'map'
assert state.z_frame_id == 'test'
assert state.yaw_frame_id == 'test2'
# test set_velocity
res = set_velocity(vx=1, frame_id='body')
state = get_state()
assert state.mode == State.MODE_VELOCITY
assert state.yaw_mode == State.YAW_MODE_YAW
assert state.vx == 1
assert state.vy == 0
assert state.vz == 0
assert state.yaw == 0
assert state.xy_frame_id == 'map'
assert state.z_frame_id == 'map'
assert state.yaw_frame_id == 'map'
# set_altitude should not work in velocity mode
res = set_altitude(z=3, frame_id='test')
assert res.success == False
assert res.message.startswith('Altitude cannot be set in')
# test set_attitude
res = set_attitude(roll=0.1, pitch=0.2, yaw=0.3, thrust=0.5)
assert res.success == True
state = get_state()
assert state.mode == State.MODE_ATTITUDE
assert state.yaw_mode == State.YAW_MODE_YAW
assert state.roll == approx(0.1)
assert state.pitch == approx(0.2)
assert state.yaw == approx(0.3)
assert state.thrust == approx(0.5)
assert state.yaw_frame_id == 'map'
msg = rospy.wait_for_message('/mavros/setpoint_attitude/attitude', PoseStamped, timeout=3)
# Tait-Bryan ZYX angle (rzyx) converted to quaternion
assert msg.pose.orientation.x == approx(0.0342708)
assert msg.pose.orientation.y == approx(0.10602051)
assert msg.pose.orientation.z == approx(0.14357218)
assert msg.pose.orientation.w == approx(0.98334744)
msg = rospy.wait_for_message('/mavros/setpoint_attitude/thrust', mavros_msgs.msg.Thrust, timeout=3)
assert msg.thrust == approx(0.5)
# set_yaw should work in attitude mode
res = set_yaw(yaw=0.7, frame_id='test2')
assert res.success == True
state = get_state()
assert state.mode == State.MODE_ATTITUDE
assert state.yaw_mode == State.YAW_MODE_YAW
assert state.roll == approx(0.1)
assert state.pitch == approx(0.2)
assert state.yaw == approx(0.7)
assert state.thrust == approx(0.5)
assert state.yaw_frame_id == 'test2'
# set_yaw_rate should not work in attitude mode
res = set_yaw_rate(yaw_rate=0.3)
assert res.success == False
assert res.message.startswith('Yaw rate cannot be set in')
# test set_rates
res = set_rates(roll_rate=nan, pitch_rate=nan, yaw_rate=0.3, thrust=0.6)
assert res.success == True
state = get_state()
assert state.mode == State.MODE_RATES
assert state.yaw_mode == State.YAW_MODE_YAW_RATE
assert state.roll_rate == approx(0)
assert state.pitch_rate == approx(0)
assert state.yaw_rate == approx(0.3)
assert state.thrust == approx(0.6)
msg = rospy.wait_for_message('/mavros/setpoint_raw/attitude', mavros_msgs.msg.AttitudeTarget, timeout=3)
assert msg.thrust == approx(0.6)
res = set_rates(roll_rate=0.3, pitch_rate=0.2, yaw_rate=0.1, thrust=0.4)
assert res.success == True
state = get_state()
assert state.mode == State.MODE_RATES
assert state.yaw_mode == State.YAW_MODE_YAW_RATE
assert state.roll_rate == approx(0.3)
assert state.pitch_rate == approx(0.2)
assert state.yaw_rate == approx(0.1)
assert state.thrust == approx(0.4)
res = set_rates(roll_rate=nan, pitch_rate=nan, yaw_rate=nan, thrust=0.3)
assert res.success == True
state = get_state()
assert state.mode == State.MODE_RATES
assert state.yaw_mode == State.YAW_MODE_YAW_RATE
assert state.roll_rate == approx(0.3)
assert state.pitch_rate == approx(0.2)
assert state.yaw_rate == approx(0.1)
assert state.thrust == approx(0.3)
msg = rospy.wait_for_message('/mavros/setpoint_raw/attitude', mavros_msgs.msg.AttitudeTarget, timeout=3)
assert msg.type_mask == mavros_msgs.msg.AttitudeTarget.IGNORE_ATTITUDE
assert msg.body_rate.x == approx(0.3)
assert msg.body_rate.y == approx(0.2)
assert msg.body_rate.z == approx(0.1)
# set_yaw_rate should work in rates mode
res = set_yaw_rate(yaw_rate=0.4)
assert res.success == True
state = get_state()
assert state.mode == State.MODE_RATES
assert state.yaw_mode == State.YAW_MODE_YAW_RATE
assert state.roll_rate == approx(0.3)
assert state.pitch_rate == approx(0.2)
assert state.yaw_rate == approx(0.4)
assert state.thrust == approx(0.3)
res = set_rates(roll_rate=inf)
assert res.success == False
assert res.message == 'roll_rate argument cannot be Inf'

View File

@@ -1,10 +0,0 @@
<launch>
<node name="simple_offboard" pkg="clover" type="simple_offboard" required="true" output="screen"/>
<node pkg="tf2_ros" type="static_transform_publisher" name="test_frame" args="10 20 30 0 0 0 map test"/>
<node pkg="tf2_ros" type="static_transform_publisher" name="test2_frame" args="100 200 300 0 0 0 map test2"/>
<param name="test_module" value="$(find clover)/test/offboard.py"/>
<test test-name="offboard_test" pkg="ros_pytest" type="ros_pytest_runner"/>
</launch>

View File

@@ -40,7 +40,6 @@ function viewTopicsList() {
let rosdistro; let rosdistro;
function viewTopic(topic) { function viewTopic(topic) {
let counter = 0;
let index = '<a href=topics.html>Topics</a>'; let index = '<a href=topics.html>Topics</a>';
title.innerHTML = `${index}: ${topic}`; title.innerHTML = `${index}: ${topic}`;
topicMessage.style.display = 'block'; topicMessage.style.display = 'block';
@@ -52,11 +51,10 @@ function viewTopic(topic) {
}); });
new ROSLIB.Topic({ ros: ros, name: topic }).subscribe(function(msg) { new ROSLIB.Topic({ ros: ros, name: topic }).subscribe(function(msg) {
counter++;
document.title = topic; document.title = topic;
if (mouseDown) return; if (mouseDown) return;
if (msg.header && msg.header.stamp) { if (msg.header.stamp) {
if (params.date || params.offset) { if (params.date || params.offset) {
let date = new Date(msg.header.stamp.secs * 1e3 + msg.header.stamp.nsecs * 1e-6); let date = new Date(msg.header.stamp.secs * 1e3 + msg.header.stamp.nsecs * 1e-6);
if (params.date) msg.header.date = date.toISOString(); if (params.date) msg.header.date = date.toISOString();
@@ -64,8 +62,7 @@ function viewTopic(topic) {
} }
} }
let txt = `<div class=counter>${counter} received</div>${yamlStringify(msg)}`; // JSON.stringify(msg, null, 4); topicMessage.innerHTML = yamlStringify(msg); // JSON.stringify(msg, null, 4);
topicMessage.innerHTML = txt;
}); });
} }

View File

@@ -15,7 +15,6 @@
white-space: pre; white-space: pre;
font-family: monospace; font-family: monospace;
} }
.counter { color: #b9b9b9; margin-bottom: 1em; }
#topic-type { font-family: monospace; font-size: 0.5em; vertical-align: super; font-weight: normal; } #topic-type { font-family: monospace; font-size: 0.5em; vertical-align: super; font-weight: normal; }
.topic { font-family: monospace; } .topic { font-family: monospace; }
body.closed { background-color: rgb(207, 207, 207); } body.closed { background-color: rgb(207, 207, 207); }

View File

@@ -19,7 +19,7 @@ The frontend files are located in [`www`](./www/) subdirectory. The frontend app
### Services ### Services
* `~run` ([*clover_blocks/Run*](srv/Run.srv)) run Blockly-generated program (in Python). * `~run` ([*clover_blocks/Run*](srv/Run.srv)) run Blockly-generated program (in Python).
* `~stop` ([*std_srvs/Trigger*](http://docs.ros.org/noetic/api/std_srvs/html/srv/Trigger.html)) terminate the running program. * `~stop` ([*std_srvs/Trigger*](http://docs.ros.org/melodic/api/std_srvs/html/srv/Trigger.html)) terminate the running program.
* `~store` ([*clover_blocks/load*](srv/Store.srv)) store a user program (to `<package_path>/programs` by default). * `~store` ([*clover_blocks/load*](srv/Store.srv)) store a user program (to `<package_path>/programs` by default).
* `~load` ([*clover_blocks/load*](srv/Load.srv)) load all the stored programs. * `~load` ([*clover_blocks/load*](srv/Load.srv)) load all the stored programs.
@@ -45,11 +45,11 @@ http://<hostname>/clover_blocks/?navigate_tolerance=0.5&sleep_time=0.1
#### Published #### Published
* `~running` ([*std_msgs/Bool*](http://docs.ros.org/noetic/api/std_msgs/html/msg/Bool.html)) indicates if the program is currently running. * `~running` ([*std_msgs/Bool*](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html)) indicates if the program is currently running.
* `~block` ([*std_msgs/String*](http://docs.ros.org/noetic/api/std_msgs/html/msg/String.html)) current executing block (maximum topic rate is limited). * `~block` ([*std_msgs/String*](http://docs.ros.org/melodic/api/std_msgs/html/msg/String.html)) current executing block (maximum topic rate is limited).
* `~error` ([*std_msgs/String*](http://docs.ros.org/noetic/api/std_msgs/html/msg/String.html))  user program errors and exceptions. * `~error` ([*std_msgs/String*](http://docs.ros.org/melodic/api/std_msgs/html/msg/String.html))  user program errors and exceptions.
* `~prompt` ([*clover_blocks/Prompt*](msg/Prompt.msg)) user input request (includes random request ID string). * `~prompt` ([*clover_blocks/Prompt*](msg/Prompt.msg)) user input request (includes random request ID string).
This topic is published from the frontend side: This topic is published from the frontend side:
* `~prompt/<request_id>` ([*std_msgs/String*](http://docs.ros.org/noetic/api/std_msgs/html/msg/String.html))  user input response. * `~prompt/<request_id>` ([*std_msgs/String*](http://docs.ros.org/melodic/api/std_msgs/html/msg/String.html))  user input response.

View File

@@ -15,7 +15,6 @@ const COLOR_GPIO = 200;
const DOCS_URL = 'https://clover.coex.tech/en/blocks.html'; const DOCS_URL = 'https://clover.coex.tech/en/blocks.html';
var frameIds = [["body", "BODY"], ["markers map", "ARUCO_MAP"], ["marker", "ARUCO"], ["last navigate target", "NAVIGATE_TARGET"], ["map", "MAP"]]; var frameIds = [["body", "BODY"], ["markers map", "ARUCO_MAP"], ["marker", "ARUCO"], ["last navigate target", "NAVIGATE_TARGET"], ["map", "MAP"]];
var frameIdsWithTerrain = frameIds.concat([["terrain", "TERRAIN"]]);
function considerFrameId(e) { function considerFrameId(e) {
if (!(e instanceof Blockly.Events.Change || e instanceof Blockly.Events.Create)) return; if (!(e instanceof Blockly.Events.Change || e instanceof Blockly.Events.Create)) return;
@@ -23,7 +22,7 @@ function considerFrameId(e) {
var frameId = this.getFieldValue('FRAME_ID'); var frameId = this.getFieldValue('FRAME_ID');
// set appropriate coordinates labels // set appropriate coordinates labels
if (this.getInput('X')) { // block has x-y-z fields if (this.getInput('X')) { // block has x-y-z fields
if (frameId == 'BODY' || frameId == 'NAVIGATE_TARGET' || frameId == 'BASE_LINK' || frameId == 'TERRAIN') { if (frameId == 'BODY' || frameId == 'NAVIGATE_TARGET' || frameId == 'BASE_LINK') {
this.getInput('X').fieldRow[0].setValue('forward'); this.getInput('X').fieldRow[0].setValue('forward');
this.getInput('Y').fieldRow[0].setValue('left'); this.getInput('Y').fieldRow[0].setValue('left');
this.getInput('Z').fieldRow[0].setValue('up'); this.getInput('Z').fieldRow[0].setValue('up');
@@ -60,8 +59,8 @@ function updateSetpointBlock(e) {
this.getInput('VY').setVisible(velocity); this.getInput('VY').setVisible(velocity);
this.getInput('VZ').setVisible(velocity); this.getInput('VZ').setVisible(velocity);
this.getInput('YAW').setVisible(attitude); this.getInput('YAW').setVisible(attitude);
this.getInput('ROLL').setVisible(attitude);
this.getInput('PITCH').setVisible(attitude); this.getInput('PITCH').setVisible(attitude);
this.getInput('ROLL').setVisible(attitude);
this.getInput('THRUST').setVisible(attitude); this.getInput('THRUST').setVisible(attitude);
this.getInput('RELATIVE_TO').setVisible(type != 'RATES'); this.getInput('RELATIVE_TO').setVisible(type != 'RATES');
@@ -74,7 +73,7 @@ function updateSetpointBlock(e) {
Blockly.Blocks['navigate'] = { Blockly.Blocks['navigate'] = {
init: function () { init: function () {
let navFrameId = frameIdsWithTerrain.slice(); let navFrameId = frameIds.slice();
navFrameId.push(['global', 'GLOBAL_LOCAL']) navFrameId.push(['global', 'GLOBAL_LOCAL'])
navFrameId.push(['global, WGS 84 alt.', 'GLOBAL']) navFrameId.push(['global, WGS 84 alt.', 'GLOBAL'])
this.appendDummyInput() this.appendDummyInput()
@@ -164,14 +163,14 @@ Blockly.Blocks['setpoint'] = {
this.appendValueInput("VZ") this.appendValueInput("VZ")
.setCheck("Number") .setCheck("Number")
.appendField("vz"); .appendField("vz");
this.appendValueInput("ROLL")
.setCheck("Number")
.appendField("roll")
.setVisible(false);
this.appendValueInput("PITCH") this.appendValueInput("PITCH")
.setCheck("Number") .setCheck("Number")
.appendField("pitch") .appendField("pitch")
.setVisible(false); .setVisible(false);
this.appendValueInput("ROLL")
.setCheck("Number")
.appendField("roll")
.setVisible(false);
this.appendValueInput("YAW") this.appendValueInput("YAW")
.setCheck("Number") .setCheck("Number")
.appendField("yaw") .appendField("yaw")
@@ -214,7 +213,7 @@ Blockly.Blocks['get_position'] = {
.appendField("current") .appendField("current")
.appendField(new Blockly.FieldDropdown([["x", "X"], ["y", "Y"], ["z", "Z"], ["vx", "VX"], ["vy", "VY"], ["vz", "VZ"]]), "FIELD") .appendField(new Blockly.FieldDropdown([["x", "X"], ["y", "Y"], ["z", "Z"], ["vx", "VX"], ["vy", "VY"], ["vz", "VZ"]]), "FIELD")
.appendField("relative to") .appendField("relative to")
.appendField(new Blockly.FieldDropdown(frameIdsWithTerrain), "FRAME_ID"); .appendField(new Blockly.FieldDropdown(frameIds), "FRAME_ID");
this.appendValueInput("ID") this.appendValueInput("ID")
.setCheck("Number") .setCheck("Number")
.appendField("with ID") .appendField("with ID")
@@ -248,7 +247,7 @@ Blockly.Blocks['get_attitude'] = {
init: function () { init: function () {
this.appendDummyInput() this.appendDummyInput()
.appendField("current") .appendField("current")
.appendField(new Blockly.FieldDropdown([["roll", "ROLL"], ["pitch", "PITCH"], ["roll rate", "ROLL_RATE"], ["pitch rate", "PITCH_RATE"], ["yaw rate", "YAW_RATE"]]), "FIELD"); .appendField(new Blockly.FieldDropdown([["pitch", "PITCH"], ["roll", "ROLL"], ["pitch rate", "PITCH_RATE"], ["roll rate", "ROLL_RATE"], ["yaw rate", "YAW_RATE"]]), "FIELD");
this.setOutput(true, "Number"); this.setOutput(true, "Number");
this.setColour(COLOR_STATE); this.setColour(COLOR_STATE);
this.setTooltip("Returns current orientation or angle rates in degree or degree per second (not radian)."); this.setTooltip("Returns current orientation or angle rates in degree or degree per second (not radian).");
@@ -510,7 +509,7 @@ Blockly.Blocks['distance'] = {
.appendField("z"); .appendField("z");
this.appendDummyInput() this.appendDummyInput()
.appendField("relative to") .appendField("relative to")
.appendField(new Blockly.FieldDropdown([["markers map", "ARUCO_MAP"], ["marker", "ARUCO"], ["last navigate target", "NAVIGATE_TARGET"], ["terrain", "TERRAIN"]]), "FRAME_ID"); .appendField(new Blockly.FieldDropdown([["markers map", "ARUCO_MAP"], ["marker", "ARUCO"], ["last navigate target", "NAVIGATE_TARGET"]]), "FRAME_ID");
this.appendValueInput("ID") this.appendValueInput("ID")
.setCheck("Number") .setCheck("Number")
.appendField("with ID") .appendField("with ID")

View File

@@ -69,8 +69,8 @@
<value name="VX"><shadow type="math_number"><field name="NUM">0</field></shadow></value> <value name="VX"><shadow type="math_number"><field name="NUM">0</field></shadow></value>
<value name="VY"><shadow type="math_number"><field name="NUM">0</field></shadow></value> <value name="VY"><shadow type="math_number"><field name="NUM">0</field></shadow></value>
<value name="VZ"><shadow type="math_number"><field name="NUM">0</field></shadow></value> <value name="VZ"><shadow type="math_number"><field name="NUM">0</field></shadow></value>
<value name="ROLL"><shadow type="math_number"><field name="NUM">0</field></shadow></value>
<value name="PITCH"><shadow type="math_number"><field name="NUM">0</field></shadow></value> <value name="PITCH"><shadow type="math_number"><field name="NUM">0</field></shadow></value>
<value name="ROLL"><shadow type="math_number"><field name="NUM">0</field></shadow></value>
<value name="YAW"><shadow type="math_number"><field name="NUM">0</field></shadow></value> <value name="YAW"><shadow type="math_number"><field name="NUM">0</field></shadow></value>
<value name="THRUST"><shadow type="math_number"><field name="NUM">0.5</field></shadow></value> <value name="THRUST"><shadow type="math_number"><field name="NUM">0.5</field></shadow></value>
<value name="ID"><shadow type="math_number"><field name="NUM">0</field></shadow></value> <value name="ID"><shadow type="math_number"><field name="NUM">0</field></shadow></value>

View File

@@ -81,7 +81,7 @@ function generateROSDefinitions() {
code += `get_telemetry = rospy.ServiceProxy('get_telemetry', srv.GetTelemetry)\n`; code += `get_telemetry = rospy.ServiceProxy('get_telemetry', srv.GetTelemetry)\n`;
code += `navigate = rospy.ServiceProxy('navigate', srv.Navigate)\n`; code += `navigate = rospy.ServiceProxy('navigate', srv.Navigate)\n`;
if (rosDefinitions.navigateGlobal) { if (rosDefinitions.navigateGlobal) {
code += `navigate_global = rospy.ServiceProxy('navigate_global', srv.NavigateGlobal)\n`; code += `navigate_global = rospy.ServiceProxy('navigate_global', srv.NavigateGlobal)\n`;
} }
if (rosDefinitions.setVelocity) { if (rosDefinitions.setVelocity) {
code += `set_velocity = rospy.ServiceProxy('set_velocity', srv.SetVelocity)\n`; code += `set_velocity = rospy.ServiceProxy('set_velocity', srv.SetVelocity)\n`;
@@ -276,11 +276,10 @@ Blockly.Python.angle = function(block) {
} }
Blockly.Python.set_yaw = function(block) { Blockly.Python.set_yaw = function(block) {
rosDefinitions.setYaw = true;
simpleOffboard(); simpleOffboard();
let yaw = Blockly.Python.valueToCode(block, 'YAW', Blockly.Python.ORDER_NONE); let yaw = Blockly.Python.valueToCode(block, 'YAW', Blockly.Python.ORDER_NONE);
let frameId = buildFrameId(block); let frameId = buildFrameId(block);
let code = `set_yaw(yaw=${yaw}, frame_id=${frameId})\n`; let code = `navigate(x=float('nan'), y=float('nan'), z=float('nan'), yaw=${yaw}, frame_id=${frameId})\n`;
if (block.getFieldValue('WAIT') == 'TRUE') { if (block.getFieldValue('WAIT') == 'TRUE') {
rosDefinitions.waitYaw = true; rosDefinitions.waitYaw = true;
simpleOffboard(); simpleOffboard();
@@ -329,11 +328,11 @@ Blockly.Python.setpoint = function(block) {
} else if (type == 'ATTITUDE') { } else if (type == 'ATTITUDE') {
rosDefinitions.setAttitude = true; rosDefinitions.setAttitude = true;
simpleOffboard(); simpleOffboard();
return `set_attitude(roll=${roll}, pitch=${pitch}, yaw=${yaw}, thrust=${thrust}, frame_id=${frameId})\n`; return `set_attitude(pitch=${pitch}, roll=${roll}, yaw=${yaw}, thrust=${thrust}, frame_id=${frameId})\n`;
} else if (type == 'RATES') { } else if (type == 'RATES') {
rosDefinitions.setRates = true; rosDefinitions.setRates = true;
simpleOffboard(); simpleOffboard();
return `set_rates(roll_rate=${roll}, pitch_rate=${pitch}, yaw_rate=${yaw}, thrust=${thrust})\n`; return `set_rates(pitch_rate=${pitch}, roll_rate=${roll}, yaw_rate=${yaw}, thrust=${thrust})\n`;
} }
} }

View File

@@ -2,7 +2,7 @@
<robot name="rpi_camera" xmlns:xacro="http://ros.org/wiki/xacro"> <robot name="rpi_camera" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="../camera_sensor.urdf.xacro"/> <xacro:include filename="../camera_sensor.urdf.xacro"/>
<xacro:macro name="distance_sensor" params="name:=lidar_vl53l1x parent x:=0 y:=0 z:=0 roll:=0 pitch:=0 yaw:=0 range_min:=0.01 range_max:=4.0 resolution:=0.01 rate:=10 fov:=0.471239"> <xacro:macro name="distance_sensor" params="name:=lidar_vl53l1x parent x:=0 y:=0 z:=0 roll:=0 pitch:=0 yaw:=0 range_min:=0.01 range_max:=4.0 resolution:=0.01 rate:=10">
<joint name="${name}_joint" type="fixed"> <joint name="${name}_joint" type="fixed">
<origin xyz="${x} ${y} ${z}" <origin xyz="${x} ${y} ${z}"
rpy="${roll} ${pitch} ${yaw}"/> rpy="${roll} ${pitch} ${yaw}"/>
@@ -58,7 +58,7 @@
<topicName>/rangefinder/range</topicName> <topicName>/rangefinder/range</topicName>
<frameName>rangefinder</frameName> <frameName>rangefinder</frameName>
<radiation>infrared</radiation> <radiation>infrared</radiation>
<fov>${fov}</fov> <fov>0.01</fov>
<gaussianNoise>0.001</gaussianNoise> <gaussianNoise>0.001</gaussianNoise>
<updateRate>${rate}</updateRate> <updateRate>${rate}</updateRate>
<min_distance>${range_min}</min_distance> <min_distance>${range_min}</min_distance>

View File

@@ -10,7 +10,7 @@ The simulation may be configured by a set of arguments:
* `mav_id` (*integer*, default: *0*) - MAVLink identifier of the vehicle. **Note**: Multi-vehicle simulation is possible, but requires extensive changes to launch files; * `mav_id` (*integer*, default: *0*) - MAVLink identifier of the vehicle. **Note**: Multi-vehicle simulation is possible, but requires extensive changes to launch files;
* `est` (*string*, default: *lpe*, possible values: *lpe*, *ekf2*) - PX4 estimator selection. Note that this may be overriden in the startup scripts for your craft; * `est` (*string*, default: *lpe*, possible values: *lpe*, *ekf2*) - PX4 estimator selection. Note that this may be overriden in the startup scripts for your craft;
* `vehicle` (*string*, default: *clover*) - PX4 vehicle name. Depending on this parameter, different PX4 presets will be loaded. * `vehicle` (*string*, default: *clover*) - PX4 vehicle name. Depending on this parameter, different PX4 presets will be loaded. **Note**: The default value, *clover*, requires you to use [Clover-specific PX4 branch](https://github.com/CopterExpress/Firmware/tree/v1.10.1-clever);
* `main_camera` (*boolean*, default: *true*) - controls whether the drone will have a vision position estimation camera; * `main_camera` (*boolean*, default: *true*) - controls whether the drone will have a vision position estimation camera;
* `rangefinder` (*boolean*, default: *true*) - controls whether the drone will have a laser rangefinder; * `rangefinder` (*boolean*, default: *true*) - controls whether the drone will have a laser rangefinder;
* `led` (*boolean*, default: *true*) - controls whether the drone will have a programmable LED strip; * `led` (*boolean*, default: *true*) - controls whether the drone will have a programmable LED strip;

View File

@@ -7,31 +7,30 @@
. ${R}etc/init.d-posix/airframes/10016_iris # base on iris . ${R}etc/init.d-posix/airframes/10016_iris # base on iris
param set-default ATT_W_EXT_HDG 0.5 param set ATT_W_EXT_HDG 0.5
param set-default ATT_EXT_HDG_M 1 # 0 = none, 1 = vision, 2 = mocap param set ATT_EXT_HDG_M 1
param set-default COM_DISARM_LAND 1.0 param set COM_DISARM_LAND 1.0
param set-default COM_RCL_EXCEPT 4 # enable offboard flights without rc
param set-default LPE_FLW_SCALE 1.0 param set LPE_FLW_SCALE 1.0
param set-default LPE_FLW_R 0.2 param set LPE_FLW_R 0.2
param set-default LPE_FLW_RR 0.0 param set LPE_FLW_RR 0.0
param set-default LPE_FLW_QMIN 10 param set LPE_FLW_QMIN 10
param set-default LPE_VIS_DELAY 0.0 param set LPE_VIS_DELAY 0.0
param set-default LPE_VIS_Z 0.1 param set LPE_VIS_Z 0.1
param set-default LPE_FUSION 86 # flow + vis + land detector + gyro comp param set LPE_FUSION 86
param set-default SENS_FLOW_ROT 0 param set SENS_FLOW_ROT 0
param set-default SENS_FLOW_MINHGT 0.0 param set SENS_FLOW_MINHGT 0.0
param set-default SENS_FLOW_MAXHGT 4.0 param set SENS_FLOW_MAXHGT 4.0
param set-default SENS_FLOW_MAXR 10.0 param set SENS_FLOW_MAXR 10.0
param set-default EKF2_AID_MASK 26 # flow + vis pos + vis yaw param set EKF2_AID_MASK 26 # flow + vis pos + vis yaw
param set-default EKF2_OF_DELAY 0 param set EKF2_OF_DELAY 0
param set-default EKF2_OF_QMIN 10 param set EKF2_OF_QMIN 10
param set-default EKF2_OF_N_MIN 0.05 param set EKF2_OF_N_MIN 0.05
param set-default EKF2_OF_N_MAX 0.2 param set EKF2_OF_N_MAX 0.2
param set-default EKF2_HGT_MODE 2 # 0 = baro, 1 = gps, 2 = range, 3 = vision param set EKF2_HGT_MODE 2
param set-default EKF2_EVA_NOISE 0.1 param set EKF2_EVA_NOISE 0.1
param set-default EKF2_EVP_NOISE 0.1 param set EKF2_EVP_NOISE 0.1
param set-default EKF2_EV_DELAY 0 param set EKF2_EV_DELAY 0

View File

@@ -21,7 +21,7 @@
</include> </include>
<!-- PX4 instance --> <!-- PX4 instance -->
<node name="sitl_$(arg mav_id)" pkg="px4" type="px4" output="screen" required="true" args="$(find px4)/ROMFS/px4fmu_common -s etc/init.d-posix/rcS -i $(arg mav_id)" unless="$(eval type == 'none')"> <node name="sitl_$(arg mav_id)" pkg="px4" type="px4" output="screen" args="$(find px4)/ROMFS/px4fmu_common -s etc/init.d-posix/rcS -i $(arg mav_id)" unless="$(eval type == 'none')">
<env name="PX4_SIM_MODEL" value="$(arg vehicle)"/> <env name="PX4_SIM_MODEL" value="$(arg vehicle)"/>
<env name="PX4_ESTIMATOR" value="$(arg est)"/> <env name="PX4_ESTIMATOR" value="$(arg est)"/>
</node> </node>
@@ -36,7 +36,7 @@
<arg name="use_clover_physics" value="$(arg use_clover_physics)"/> <arg name="use_clover_physics" value="$(arg use_clover_physics)"/>
</include> </include>
<node name="jmavsim" pkg="px4" required="true" type="jmavsim_run.sh" output="screen" if="$(eval type == 'jmavsim')"> <node name="jmavsim" pkg="px4" type="jmavsim_run.sh" output="screen" if="$(eval type == 'jmavsim')">
<env name="HEADLESS" value="1" if="$(eval not gui)"/> <env name="HEADLESS" value="1" if="$(eval not gui)"/>
</node> </node>

View File

@@ -1,4 +1,4 @@
<package format="3"> <package format="2">
<name>clover_simulation</name> <name>clover_simulation</name>
<version>0.23.0</version> <version>0.23.0</version>
<description>The clover_simulation package provides worlds and launch files for Gazebo.</description> <description>The clover_simulation package provides worlds and launch files for Gazebo.</description>
@@ -22,8 +22,6 @@
<depend>gazebo_ros</depend> <depend>gazebo_ros</depend>
<depend>gazebo_plugins</depend> <depend>gazebo_plugins</depend>
<depend>rospy</depend> <depend>rospy</depend>
<depend condition="$ROS_PYTHON_VERSION == 2">python-docopt</depend>
<depend condition="$ROS_PYTHON_VERSION == 3">python3-docopt</depend>
<export> <export>
<gazebo_ros gazebo_media_path="${prefix}"/> <gazebo_ros gazebo_media_path="${prefix}"/>

View File

@@ -65,8 +65,7 @@ public:
} }
role = (ros::this_node::getName() == "/gazebo") ? Role::Server : Role::Client; role = (ros::this_node::getName() == "/gazebo") ? Role::Server : Role::Client;
ROS_INFO_NAMED(("LedController_" + robotNamespace).c_str(), "LedController has started (as %s) in namespace '%s'", ROS_INFO_NAMED(("LedController_" + robotNamespace).c_str(), "LedController has started (as %s)", role == Role::Client ? "client" : "server");
role == Role::Client ? "client" : "server", robotNamespace.c_str());
nh.reset(new ros::NodeHandle(robotNamespace)); nh.reset(new ros::NodeHandle(robotNamespace));
@@ -110,6 +109,7 @@ LedController& get(std::string robotNamespace)
std::lock_guard<std::mutex> lock(controllerMutex); std::lock_guard<std::mutex> lock(controllerMutex);
auto it = controllers.find(robotNamespace); auto it = controllers.find(robotNamespace);
if (it == controllers.end()) { if (it == controllers.end()) {
gzwarn << "Creating new LED controller for namespace " << robotNamespace << "\n";
controllers[robotNamespace].reset(new LedController(robotNamespace)); controllers[robotNamespace].reset(new LedController(robotNamespace));
return *controllers[robotNamespace]; return *controllers[robotNamespace];
} }

View File

@@ -1,61 +0,0 @@
<?xml version="1.0" encoding="utf-8"?>
<!-- Generator: Adobe Illustrator 23.0.1, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg version="1.1" id="Слой_1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
viewBox="0 0 850.39 283.46" style="enable-background:new 0 0 850.39 283.46;" xml:space="preserve">
<style type="text/css">
.st0{fill:#333333;}
.st1{fill:#FFFFFF;}
.st2{fill:#CCCCCC;}
.st3{fill:#1E1183;}
.st4{fill:#F71523;}
.st5{fill:url(#SVGID_1_);}
.st6{fill:url(#SVGID_2_);}
.st7{fill:url(#SVGID_3_);}
.st8{opacity:0.05;fill:#FFFFFF;}
.st9{opacity:0.05;fill:#CCCCCC;}
.st10{opacity:0.05;fill:url(#SVGID_4_);}
.st11{opacity:0.05;fill:url(#SVGID_5_);}
.st12{opacity:0.05;fill:url(#SVGID_6_);}
.st13{opacity:0.05;fill:url(#SVGID_7_);}
.st14{opacity:0.05;fill:url(#SVGID_8_);}
.st15{opacity:0.05;fill:url(#SVGID_9_);}
.st16{opacity:0.05;fill:url(#SVGID_10_);}
.st17{opacity:0.05;fill:url(#SVGID_11_);}
.st18{opacity:0.05;fill:url(#SVGID_12_);}
</style>
<g>
<polygon class="st3" points="559.36,2.05 433.46,2.05 433.46,36.37 479.25,36.37 479.25,128.02 513.57,128.02 513.57,36.37
559.36,36.37 "/>
<polygon class="st3" points="702.71,36.37 702.71,2.05 576.81,2.05 576.81,2.12 576.75,2.12 576.75,128.02 576.81,128.02
611.07,128.02 702.71,128.02 702.71,93.7 611.07,93.7 611.07,82.23 668.45,82.23 668.45,47.91 611.07,47.91 611.07,36.37 "/>
<polygon class="st3" points="559.45,179.72 559.38,155.4 535.19,155.45 489.34,201.3 467.68,201.3 467.68,155.45 433.37,155.45
433.37,281.35 467.68,281.35 467.68,235.62 489.46,235.62 535.19,281.35 559.38,281.41 559.45,257.09 520.77,218.4 "/>
<path class="st3" d="M67.26,36.87h63.01V2.05H67.26c-34.8,0-63.01,28.21-63.01,63.01s28.21,63.01,63.01,63.01h63.01V93.25H67.26
c-15.57,0-28.19-12.62-28.19-28.19C39.07,49.49,51.69,36.87,67.26,36.87z"/>
<path class="st3" d="M238.36,218.4v63.01h34.82V218.4c0-34.8-28.21-63.01-63.01-63.01s-63.01,28.21-63.01,63.01v63.01h34.82V218.4
c0-15.57,12.62-28.19,28.19-28.19C225.74,190.21,238.36,202.83,238.36,218.4z"/>
<path class="st3" d="M353.08,190.21h63.01V155.4h-63.01c-34.8,0-63.01,28.21-63.01,63.01s28.21,63.01,63.01,63.01h63.01v-34.82
h-63.01c-15.57,0-28.19-12.62-28.19-28.19C324.88,202.83,337.51,190.21,353.08,190.21z"/>
<polygon class="st3" points="95.79,155.4 95.79,200.82 39.41,200.82 39.41,155.4 4.25,155.4 4.25,281.41 39.41,281.41
39.41,235.98 95.79,235.98 95.79,281.41 130.27,281.41 130.27,155.4 "/>
<path class="st4" d="M737.06,200.43c-0.42-25.12-21.44-45.04-46.57-45.04h-45.07v34.32l45.49,0c6.19,0,11.52,4.76,11.81,10.95
c0.31,6.61-4.95,12.06-11.49,12.06h-11.5c-18.95,0-34.32,15.36-34.32,34.32v0v34.26h91.64v-34.26h-45.82
C716.81,247.03,737.49,226.1,737.06,200.43z"/>
<path class="st3" d="M272.4,55.19c-5.46-34.37-37.74-57.8-72.11-52.35c-34.37,5.46-57.8,37.74-52.35,72.11
c5.46,34.37,37.74,57.8,72.11,52.35C254.42,121.84,277.85,89.56,272.4,55.19z M210.17,93.26c-15.57,0-28.19-12.62-28.19-28.19
c0-15.57,12.62-28.19,28.19-28.19c15.57,0,28.19,12.62,28.19,28.19C238.36,80.64,225.74,93.26,210.17,93.26z"/>
<rect x="593.74" y="155.4" transform="matrix(-1 -1.224647e-16 1.224647e-16 -1 1221.7888 356.6999)" class="st4" width="34.32" height="45.91"/>
<path class="st3" d="M370.51,2.12V2.05h-60.96v0.07h-19.48v125.9h34.32V93.26h46.13c25.17,0,45.57-20.4,45.57-45.57
C416.08,22.52,395.68,2.12,370.51,2.12z M364.98,64.71h-40.6V31.12h40.6v0.02c9.27,0,16.78,7.51,16.78,16.78
C381.77,57.19,374.25,64.71,364.98,64.71z"/>
<path class="st3" d="M846.12,47.69c0-25.17-20.4-45.57-45.57-45.57V2.05h-60.96v0.01h-19.48v126.02h34.32V93.26h32.67l34.76,34.76
l24.19,0.06l0.07-24.32l-19.03-19.03C838.61,76.45,846.12,62.95,846.12,47.69z M795.02,64.71
C795.02,64.71,795.02,64.71,795.02,64.71h-40.6V31.12h40.6v0.03c0,0,0,0,0,0c9.27,0,16.78,7.51,16.78,16.78
C811.8,57.19,804.29,64.71,795.02,64.71z"/>
<path class="st4" d="M846.1,195.54c0.31-22.05-18.25-40.09-40.3-40.09h-51.34v34.32h51.59v0.01c2.71,0,5.17,1.93,5.66,4.78
c0.33,1.96-0.48,3.98-1.98,5.29c-1.19,1.04-2.46,1.39-3.68,1.39v0.01h-27.06v34.32h27.06v0.01c2.71,0,5.17,1.93,5.66,4.78
c0.33,1.96-0.48,3.98-1.98,5.29c-1.19,1.04-2.46,1.39-3.68,1.39v0.01h-51.59v34.32h51.34c22.05,0,40.61-18.04,40.3-40.09
c-0.12-8.55-2.96-16.44-7.68-22.86C843.14,211.99,845.98,204.1,846.1,195.54z"/>
</g>
</svg>

Before

Width:  |  Height:  |  Size: 4.2 KiB

View File

@@ -36,7 +36,7 @@
* [Optical Flow](optical_flow.md) * [Optical Flow](optical_flow.md)
* [Autonomous flight (OFFBOARD)](simple_offboard.md) * [Autonomous flight (OFFBOARD)](simple_offboard.md)
* [Coordinate systems (frames)](frames.md) * [Coordinate systems (frames)](frames.md)
* [Code examples](snippets.md) * [Code snippets](snippets.md)
* [Interfacing with a laser rangefinder](laser.md) * [Interfacing with a laser rangefinder](laser.md)
* [LED strip](leds.md) * [LED strip](leds.md)
* [Working with GPIO](gpio.md) * [Working with GPIO](gpio.md)
@@ -96,7 +96,6 @@
* [Migration to v0.20](migrate20.md) * [Migration to v0.20](migrate20.md)
* [Migration to v0.22](migrate22.md) * [Migration to v0.22](migrate22.md)
* [Events](events.md) * [Events](events.md)
* [CopterHack-2023](copterhack2023.md)
* [CopterHack-2022](copterhack2022.md) * [CopterHack-2022](copterhack2022.md)
* [CopterHack-2021](copterhack2021.md) * [CopterHack-2021](copterhack2021.md)
* [CopterHack-2019](copterhack2019.md) * [CopterHack-2019](copterhack2019.md)

View File

@@ -1,5 +1,7 @@
# Working with the camera # Working with the camera
> **Note** In the image version **0.20** `clever` package was renamed to `clover`. See [previous version of the article](https://github.com/CopterExpress/clover/blob/v0.19/docs/en/camera.md) for older images.
Make sure the camera is enabled in the `~/catkin_ws/src/clover/clover/launch/clover.launch` file: Make sure the camera is enabled in the `~/catkin_ws/src/clover/clover/launch/clover.launch` file:
```xml ```xml
@@ -14,7 +16,7 @@ The `clover` service must be restarted after the launch-file has been edited:
sudo systemctl restart clover sudo systemctl restart clover
``` ```
You may use [rqt](rviz.md) or [web_video_server](web_video_server.md) to view the camera stream. You may use rqt or [web_video_server](web_video_server.md) to view the camera stream.
## Troubleshooting ## Troubleshooting
@@ -52,6 +54,8 @@ The [SD card image](image.md) comes with a preinstalled [OpenCV](https://opencv.
### Python ### Python
Main article: http://wiki.ros.org/cv_bridge/Tutorials/ConvertingBetweenROSImagesAndOpenCVImagesPython.
An example of creating a subscriber for a topic with an image from the main camera for processing with OpenCV: An example of creating a subscriber for a topic with an image from the main camera for processing with OpenCV:
```python ```python
@@ -59,14 +63,12 @@ import rospy
import cv2 import cv2
from sensor_msgs.msg import Image from sensor_msgs.msg import Image
from cv_bridge import CvBridge from cv_bridge import CvBridge
from clover import long_callback
rospy.init_node('cv') rospy.init_node('computer_vision_sample')
bridge = CvBridge() bridge = CvBridge()
@long_callback
def image_callback(data): def image_callback(data):
img = bridge.imgmsg_to_cv2(data, 'bgr8') # OpenCV image cv_image = bridge.imgmsg_to_cv2(data, 'bgr8') # OpenCV image
# Do any image processing with cv2... # Do any image processing with cv2...
image_sub = rospy.Subscriber('main_camera/image_raw', Image, image_callback) image_sub = rospy.Subscriber('main_camera/image_raw', Image, image_callback)
@@ -74,31 +76,19 @@ image_sub = rospy.Subscriber('main_camera/image_raw', Image, image_callback)
rospy.spin() rospy.spin()
``` ```
> **Note** Image processing may take significant time to finish. This can cause an [issue](https://github.com/ros/ros_comm/issues/1901) in rospy library, which would lead to processing stale camera frames. To solve this problem you need to use `long_callback` decorator from `clover` library, as in the example above.
#### Limiting CPU usage
When using the `main_camera/image_raw` topic, the script will process the maximum number of frames from the camera, actively utilizing the CPU (up to 100%). In tasks, where processing each camera frame is not critical, you can use the topic, where the frames are published at rate 5 Hz: `main_camera/image_raw_throttled`:
```python
image_sub = rospy.Subscriber('main_camera/image_raw_throttled', Image, image_callback, queue_size=1)
```
#### Publishing images
To debug image processing, you can publish a separate topic with the processed image: To debug image processing, you can publish a separate topic with the processed image:
```python ```python
image_pub = rospy.Publisher('~debug', Image) image_pub = rospy.Publisher('~debug', Image)
``` ```
Publishing the processed image: Publishing the processed image (at the end of the image_callback function):
```python ```python
image_pub.publish(bridge.cv2_to_imgmsg(img, 'bgr8')) image_pub.publish(bridge.cv2_to_imgmsg(cv_image, 'bgr8'))
``` ```
The published images can be viewed using [web_video_server](web_video_server.md) or [rqt](rviz.md). The obtained images can be viewed using [web_video_server](web_video_server.md).
#### Retrieving one frame #### Retrieving one frame
@@ -109,7 +99,7 @@ import rospy
from sensor_msgs.msg import Image from sensor_msgs.msg import Image
from cv_bridge import CvBridge from cv_bridge import CvBridge
rospy.init_node('cv') rospy.init_node('computer_vision_sample')
bridge = CvBridge() bridge = CvBridge()
# ... # ...
@@ -131,32 +121,38 @@ QR codes recognition in Python:
```python ```python
import rospy import rospy
from pyzbar import pyzbar from pyzbar import pyzbar
import cv2
from cv_bridge import CvBridge from cv_bridge import CvBridge
from sensor_msgs.msg import Image from sensor_msgs.msg import Image
from clover import long_callback
rospy.init_node('cv')
bridge = CvBridge() bridge = CvBridge()
@long_callback rospy.init_node('barcode_test')
def image_callback(msg):
img = bridge.imgmsg_to_cv2(msg, 'bgr8') # Image subscriber callback function
barcodes = pyzbar.decode(img) def image_callback(data):
cv_image = bridge.imgmsg_to_cv2(data, 'bgr8') # OpenCV image
barcodes = pyzbar.decode(cv_image)
for barcode in barcodes: for barcode in barcodes:
b_data = barcode.data.decode('utf-8') b_data = barcode.data.decode("utf-8")
b_type = barcode.type b_type = barcode.type
(x, y, w, h) = barcode.rect (x, y, w, h) = barcode.rect
xc = x + w/2 xc = x + w/2
yc = y + h/2 yc = y + h/2
print('Found {} with data {} with center at x={}, y={}'.format(b_type, b_data, xc, yc)) print("Found {} with data {} with center at x={}, y={}".format(b_type, b_data, xc, yc))
image_sub = rospy.Subscriber('main_camera/image_raw_throttled', Image, image_callback, queue_size=1) image_sub = rospy.Subscriber('main_camera/image_raw', Image, image_callback, queue_size=1)
rospy.spin() rospy.spin()
``` ```
> **Hint** See other computer vision examples in the `~/examples` directory of the [RPi image](image.md). The script will take up to 100% CPU capacity. To slow down the script artificially, you can use [throttling](http://wiki.ros.org/topic_tools/throttle) of frames from the camera, for example, at 5 Hz (`main_camera.launch`):
```xml
<node pkg="topic_tools" name="cam_throttle" type="throttle"
args="messages main_camera/image_raw 5.0 main_camera/image_raw_throttled"/>
```
The topic for the subscriber in this case should be changed for `main_camera/image_raw_throttled`.
## Video recording ## Video recording

View File

@@ -10,14 +10,14 @@ There are several tools allowing to calibrate the camera and store calculated pa
Main tutorial: http://wiki.ros.org/camera_calibration/Tutorials/MonocularCalibration. Main tutorial: http://wiki.ros.org/camera_calibration/Tutorials/MonocularCalibration.
In order to calibrate the camera with the `camera_calibration` ROS-package you need a computer with OS GNU/Linux and [ROS Noetic](http://wiki.ros.org/noetic/Installation/Ubuntu) installed. In order to calibrate the camera with the `camera_calibration` ROS-package you need a computer with OS GNU/Linux and [ROS Melodic](ros-install.md) installed.
<img src="../assets/camera_calibration.png" alt="ROS Camera Calibrator" class="zoom center" width=600> <img src="../assets/camera_calibration.png" alt="ROS Camera Calibrator" class="zoom center" width=600>
1. Using the Terminal, install `camera_calibration` package to your computer: 1. Using the Terminal, install `camera_calibration` package to your computer:
```bash ```bash
sudo apt-get install ros-noetic-camera-calibration sudo apt-get install ros-melodic-camera-calibration
``` ```
2. Download the chessboard [chessboard.pdf](../assets/chessboard.pdf). Print the chessboard on paper or open it on the computer screen. 2. Download the chessboard [chessboard.pdf](../assets/chessboard.pdf). Print the chessboard on paper or open it on the computer screen.

View File

@@ -20,14 +20,15 @@ USB connection is the preferred way to connect to the flight controller.
## UART connection ## UART connection
> **Note** In the image version **0.20** `clever` package and service was renamed to `clover`. See [previous version of the article](https://github.com/CopterExpress/clover/blob/v0.19/docs/en/connection.md) for older images.
<!-- TODO: Connection scheme --> <!-- TODO: Connection scheme -->
UART connection is another way for the Raspberry Pi and FCU to communicate. UART connection is another way for the Raspberry Pi and FCU to communicate.
1. Connect the TELEM 2 port on the flight controller using a UART cable to the Raspberry Pi pins following this instruction: the black cable (*GND*) to Ground, the green cable (*UART_RX*) to *GPIO14*, the yellow cable (*UART_TX*) to *GPIO15*. Do not connect the red cable (*5V*). 1. Connect Raspberry Pi to your FCU using a UART cable.
2. Set the PX4 parameters: `MAV_1_CONFIG` to TELEM 2, `SER_TEL2_BAUND` to 921600 8N1. In PX4 of version prior to v1.10.0 the parameter `SYS_COMPANION` should be set to 921600. 2. [Connect to the Raspberry Pi over SSH](ssh.md).
3. [Connect to the Raspberry Pi over SSH](ssh.md). 3. Change the connection type in `~/catkin_ws/src/clover/clover/launch/clover.launch` to UART:
4. Change the connection type in `~/catkin_ws/src/clover/clover/launch/clover.launch` to UART:
```xml ```xml
<arg name="fcu_conn" default="uart"/> <arg name="fcu_conn" default="uart"/>
@@ -39,4 +40,15 @@ UART connection is another way for the Raspberry Pi and FCU to communicate.
sudo systemctl restart clover sudo systemctl restart clover
``` ```
> **Hint** Set the `SYS_COMPANION` PX4 parameter to 921600 to enable UART on the FCU.
## SITL connection
In order to connect to a local or a remote [SITL](sitl.md) instance set the `fcu_conn` parameter to `udp` and `fcu_ip` to the IP address of the SITL instance (`127.0.0.1` if you are running the instance locally):
```xml
<arg name="fcu_conn" default="udp"/>
<arg name="fcu_ip" default="127.0.0.1"/>
```
**Next**: [Using QGroundControl over Wi-Fi](gcs_bridge.md) **Next**: [Using QGroundControl over Wi-Fi](gcs_bridge.md)

View File

@@ -1,169 +0,0 @@
# CopterHack 2023
<img src="../assets/copterhack2023.svg" width=300 align=right>
CopterHack 2023 is an international open-source projects competition on aerial robotics. The main direction of the CopterHack is team competition with a free choice of the project topic. The competitions official language is English.
To learn more about the articles of the CopterHack finalist teams follow the links [CopterHack 2021](copterhack2021.md), [CopterHack 2022](copterhack2022.md).
The proposed projects are supposed to be open-source and be compatible with the Clover quadcopter platform. Teams-participants are supposed to work on their projects throughout the competition, bringing them closer to the state of the finished product while being assisted by industry experts through lectures and regular feedback.
## Projects of the contest's participants {#participants}
|Place|Team|Project|Points|
|:-:|-|-|-|
||🇷🇺 Clover Cloud Team|[Clover Cloud Platform](https://github.com/DevMBS/clover/blob/clover-cloud-platform/docs/en/clover-cloud-platform.md)||
||🇰🇬 Zavarka|[Система обмена грузами с помощью конвейера](https://github.com/aiurobotics/clover/blob/conveyance/docs/ru/conveyance.md)||
||🇮🇳 DJS PHOENIX|[Autonomous Racing Drone](https://github.com/DJSPhoenix/clover/blob/DJSPhoenix_chetak/docs/ru/djs_phoenix_chetak.md)||
||🇷🇺 FSOTM|[Drone Interceptor](https://github.com/deadln/clover/blob/interceptor/docs/ru/interceptor.md)||
||🇰🇬 Homelesses|[Trash Collector](https://github.com/Isa-jesus/clover/blob/trash-collector/docs/ru/trash-collector.md)||
||🇷🇺 Digital otters|[Digital otters](https://github.com/Mentalsupernova/clover_cool/blob/new-article.md/docs/ru/new-article.md)||
||🇷🇺 Light Flight|[Сопровождение БПЛА при посадке](https://github.com/SirSerow/clover_inertial_ns/blob/inertial-1/Description.md)||
||🇰🇬 LiveSavers|[LiveSavers](https://github.com/Sarvar00/clover/blob/livesavers/docs/ru/livesaver.md)||
||🇷🇺 C305|[Система радио-навигации](https://github.com/Lukerrr/clover-c305/blob/nav_beacon/docs/ru/nav-beacon.md)||
||🇷🇺 XenCOM|[Bound by fate](https://github.com/xenkek/clover/blob/xenkek-patch-1/docs/ru/bound_by_fate.md)||
||🇨🇦 Clover with Motion Capture System|[Clover with Motion Capture System](https://github.com/ssmith-81/clover/blob/MoCap_Clover/docs/en/mocap_clover.md)||
||🇧🇷 Atena|[Swarm in Blocks 2](https://github.com/Grupo-SEMEAR-USP/clover/blob/swarm_in_blocks_2/docs/en/swarm_in_blocks_2.md)||
||🇧🇾 FTL|[Advanced Clover 2](https://github.com/FTL-team/clover/blob/FTL-advancedClover3/docs/ru/advanced_clover_simulator_platform.md)||
||🇷🇺 Лицей №128|[Платформа для зарядки квадрокоптера](https://github.com/Juli-Shvetsova/clover/blob/liceu128-1/docs/ru/liceu128.md)||
||🇷🇺 Ava_Clover|[DoubleClover](https://github.com/bessiaka/clover/blob/Ava_Clover/docs/ru/soosocta.md)||
||🇷🇺 TPU_1|[Совместная транспортировка груза](https://github.com/shamoleg/clover/blob/tpu_1/docs/ru/tpu_1.md)||
||🇷🇺 TPU_2|[Алгоритм полета сквозь лесную местность](https://github.com/shamoleg/clover/blob/tpu_2/docs/ru/tpu_2.md)|&nbsp;|
## CopterHack 2023 stages
The qualifying and project development stages will be held in an online format, however, the final round will be in a hybrid mode (offline + online). The competition involves monthly updates from the teams with regular feedback from the jury. All teams are required to prepare a final video and presentation on the project's results to participate in the final stage.
1. Qualifying stage. Applications are accepted on the deadline date until October 31, 2022.
2. Projects development stage. This stage includes monthly updates and mentorship of participants. Starting date - November 1, 2022. Deadline date - February 28, 2023.
3. All teams-participants are required to make the final video to proceed to the final round. Final videos are required to be uploaded until March 31, 2023.
4. The final round. Projects presentation takes place April 23, 2023.
## Conditions and criteria for evaluation the final result
General project requirements:
1. Open-source.
2. Compatibility with the Clover platform.
Judging criteria for the jury at the final:
1. Readiness and the article (max. 10 points): the degree of readiness of the project; an accessible and understandable description of the project in the article; a link to the code with comments, diagrams, drawings. It should be possible to reproduce the project and get the result according to the article.
2. Amount of work done (max. 6 points): the amount of work done by the team in the framework within of CopterHack, its complexity, and the technical level.
3. Usefulness for Clover (max. 6 points): the relevance to the Clover and PX4 platform application in practice, the potential level of demand from other Clover users.
4. Presentation at the final (max. 3 points): quality and entertainment points of the final presentation; completeness of the project coverage; demonstration; answers to the jury's questions.
## Prize fund
Basing on the results of the evaluation of projects at the final round, the jury will select the winners with the following prizes.
* 1st place: $3000 (USD).
* 2nd place: $2000 (USD).
* 3rd place: $1000 (USD).
* 4th place: $500 (USD).
* 5th place: $500 (USD).
The competition partners can reward the teams according to additional criteria identified during the evaluation of projects during the final round.
## How to apply?
> **Note** In order to be able to apply, you must have an account on [GitHub](https://github.com).
Prepare your application and send it as a Draft Pull Request to [Clover repository](https://github.com/CopterExpress/clover)
1. Fork the Clover repository:
<img src="../assets/github_application/github-fork.png" alt="GitHub Fork">
2. On the web page of your fork, go to the `docs/en` section and create a new file in the [Markdown](http://en.wikipedia.org/wiki/Markdown) format:
<img src="../assets/github_application/create_new_file.png" alt="GitHub Create New File">
3. Enter the title of your article. For example, `new-article.md`
<img src="../assets/github_application/new_article.png" alt="GitHub New Article">
4. Fill in your application by the recommended template:
```markdown
# Project name
[CopterHack-2023](copterhack2023.md), team **Team name**.
## Team information
The list of team members:
(Describe the team: full name, contacts (Telegram username), role in the team).
* Alexander Sokolov, @aleksandrsokolov111, engineer.
* Elena Smirnova, @elenasmirnova111, programmer.
## Project description
### Project idea
Briefly describe the idea and stage of the project.
### The potential outcomes
Describe how you see the project result.
### Using Clover platform
Describe how the Clover platform will be used in your project.
### Additional information at the request of participants
For example, information about the team's experience while working on projects, attach a link to articles, videos.
```
5. Go to the bottom of the page and create a new branch with the title of your article:
<img src="../assets/github_application/propose_new_file.png" alt="GitHub Propose New File">
> **Note** Don't commit changes directly to the `master` branch, create a new branch.
6. If necessary, place additional visual assets in the `docs/assets` folder and add them to your article.
7. Send a Draft Pull Request from your branch to Clover:
<img src="../assets/github_application/github-pull-request-create.png" alt="GitHub Create Pull">
8. In the Pull Request comments, you will be given feedback on the application.
9. Please note, in the *Checks* block the *Documentation* field should contain a tick, id cross appeared, click *Details* link to see the list of issues in you article found by markdownlint. If you need to change added files, edit them in you branch changes will appear in the Pull Request automatically. **Do not open a new Pull Request for the same application**.
10. During the contest, you will work on this document, bringing it closer to the finished state. By the end of the contest you are expected to publish your article which is supposed to be the result of your work in CopterHack.
Teams-participants are supposed to be added to the special Telegram group, where one can send the project's updates and get feedback from the Jury. For all participating teams, COEX will provide a 40% discount on the Clover drone kit.
> **Info** There are no restrictions on the age, education, and number of people in a team.
## CopterHack 2023 projects papers contest
Our participants have been engaged in advanced projects in the field of aerial robotics for already two years. This year we are planning to launch a new type of contest stimulating participants to present the research results running within the whole contest, at high -level international conferences as well as to publish them in Russian and international magazines in thematic areas.
Original articles are accepted in following nominations:
* $2000 (USD) for an article in a magazine of first quartile (Q1), indexed in Scopus, Web of Science.
* $1000 (USD) for an article in a magazine, indexed in Scopus, Web of Science.
* $500 (USD) for an article, published in Compendium (Conference Proceedings), indexed in Scopus, Web of Science.
> **Note** [Easy way to find quartiles for journals in Web of Science and Scopus](https://www.texpedi.com/2021/07/how-to-find-journal-quartile.html).
Requirements:
1. The article is required to reflect the results of the project, developed within CopterHack 2023.
2. The article is required to be accepted for publication by the moment of application for the Contest.
3. It is required to indicate in the acknowledgement area that work is accomplished within the Contest.
**Applications deadline**: December 10, 2023. The application for the contest should be submitted through the [Google Form](https://docs.google.com/forms/d/e/1FAIpQLSf52x0CTur-wUCG2URwY-p85gEUBUvgC0mPVNot0RHVjqcLZA/viewform).
**Results announcement**: December 24, 2023.
---
For all questions: [CopterHack in Telegram](https://t.me/CopterHack).
> **Info** Please contact [Oleg Ponfilenok in Telegram](https://t.me/ponfilenok) if you are interested in becoming the contest's partner or jury member.

View File

@@ -20,7 +20,7 @@ The main goal of the contest is aerial robotics popularization and community de
* Third parties can provide technical support for recording a lecture. * Third parties can provide technical support for recording a lecture.
* The status of the participant is unlimited (student, representative of a general education institution, representative of the industry, amateur). * The status of the participant is unlimited (student, representative of a general education institution, representative of the industry, amateur).
Applications deadline: November 30, 2022. Applications deadline: September 1, 2022.
### How to apply? ### How to apply?
@@ -64,7 +64,7 @@ The main goal of the contest is aerial robotics popularization and community de
The application to the contest is performed via the [Google Form](https://docs.google.com/forms/d/e/1FAIpQLSdelVy6yQ1iN6u88KeiEIKGj7gGaM0xccSt2tiYKB46ICmjkQ/viewform). The application to the contest is performed via the [Google Form](https://docs.google.com/forms/d/e/1FAIpQLSdelVy6yQ1iN6u88KeiEIKGj7gGaM0xccSt2tiYKB46ICmjkQ/viewform).
Applications deadline: November 30, 2022. Applications deadline: September 1, 2022.
### Prizes ### Prizes
@@ -105,7 +105,7 @@ The course is evaluated according to a separate, publicly available lesson submi
The application to the contest is performed via the [Google Form](https://docs.google.com/forms/d/e/1FAIpQLSdf2Q68X4hPnFE9f3EP95AxPNnzHKqIsFHtTRT6EBKiH93wzg/viewform) where the link to the video course should be attached. The application to the contest is performed via the [Google Form](https://docs.google.com/forms/d/e/1FAIpQLSdf2Q68X4hPnFE9f3EP95AxPNnzHKqIsFHtTRT6EBKiH93wzg/viewform) where the link to the video course should be attached.
Applications deadline: November 30, 2022. Applications deadline: September 1, 2022.
### Prizes ### Prizes

View File

@@ -40,8 +40,6 @@ Messages published in the topics may be viewed with the `rostopic` utility, e.g.
`/mavros/setpoint_position/local` — set target position and yaw of the drone \(in the ENU coordinate system\). `/mavros/setpoint_position/local` — set target position and yaw of the drone \(in the ENU coordinate system\).
`/mavros/setpoint_position/global` set target position in global coordinates (latitude, longitude, altitude) and yaw of the drone.
`/mavros/setpoint_position/cmd_vel` — set target linear velocity of the drone. `/mavros/setpoint_position/cmd_vel` — set target linear velocity of the drone.
`/mavros/setpoint_attitude/attitude` and `/mavros/setpoint_attitude/att_throttle` — set target attitude and throttle level. `/mavros/setpoint_attitude/attitude` and `/mavros/setpoint_attitude/att_throttle` — set target attitude and throttle level.
@@ -54,4 +52,4 @@ Messages published in the topics may be viewed with the `rostopic` utility, e.g.
`/mavros/setpoint_raw/attitude` — sends [SET\_ATTITUDE\_TARGET](https://mavlink.io/en/messages/common.html#SET_ATTITUDE_TARGET) message. Allows setting the target attitude /angular velocity and throttle level. The values to be set are selected using the `type_mask` field `/mavros/setpoint_raw/attitude` — sends [SET\_ATTITUDE\_TARGET](https://mavlink.io/en/messages/common.html#SET_ATTITUDE_TARGET) message. Allows setting the target attitude /angular velocity and throttle level. The values to be set are selected using the `type_mask` field
`/mavros/setpoint_raw/global` — sends [SET\_POSITION\_TARGET\_GLOBAL\_INT](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_GLOBAL_INT). Allows setting the target attitude in global coordinates \(latitude, longitude, altitude\) and flight speed. `/mavros/setpoint_raw/global` — sends [SET\_POSITION\_TARGET\_GLOBAL\_INT](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_GLOBAL_INT). Allows setting the target attitude in global coordinates \(latitude, longitude, altitude\) and flight speed. **Not supported in PX4** \([issue](https://github.com/PX4/Firmware/issues/7552)\).

View File

@@ -22,7 +22,7 @@ In case of using LPE ([COEX patched firmware](firmware.md)):
|Parameter|Value|Comment| |Parameter|Value|Comment|
|-|-|-| |-|-|-|
|`LPE_FUSION`|86|Checkboxes: *flow* + *vis* + *land detector* + *gyro comp*. If flying over horizontal floor *pub agl as lpos down* checkbox is allowed.<br>Details: [Optical Flow](optical_flow.md), [ArUco markers](aruco_map.md), [GPS](gps.md).| |`LPE_FUSION`|86|Checkboxes: *flow* + *vis* + *land Detector* + *gyro comp*. If flying over horizontal floor *pub agl as lpos down* checkbox is allowed.<br>Details: [Optical Flow](optical_flow.md), [ArUco markers](aruco_map.md), [GPS](gps.md).|
|`LPE_VIS_DELAY`|0.0|| |`LPE_VIS_DELAY`|0.0||
|`LPE_VIS_Z`|0.1|| |`LPE_VIS_Z`|0.1||
|`LPE_FLW_SCALE`|1.0|| |`LPE_FLW_SCALE`|1.0||
@@ -60,8 +60,8 @@ The `SYS_MC_EST_GROUP` parameter defines the estimator subsystem to use.
Estimator subsystem is a group of modules that calculates the current state of the copter using readings from the sensors. The copter state includes: Estimator subsystem is a group of modules that calculates the current state of the copter using readings from the sensors. The copter state includes:
* Angle rate of the copter roll_rate, pitch_rate, yaw_rate; * Angle rate of the copter pitch_rate, roll_rate, yaw_rate;
* Copter orientation (in the local coordinate system) roll, pitch, yaw (one of presentations); * Copter orientation (in the local coordinate system) pitch, roll, yaw (one of presentations);
* Copter position (in the local coordinate system) x, y, z; * Copter position (in the local coordinate system) x, y, z;
* Copter speed (in the local coordinate system) vx, vy, vz; * Copter speed (in the local coordinate system) vx, vy, vz;
* Global coordinates of the copter latitude, longitude, altitude; * Global coordinates of the copter latitude, longitude, altitude;

View File

@@ -11,7 +11,7 @@ To use rviz and rqt, a PC running Ubuntu Linux (or a virtual machine such as [Pa
> **Hint** You can use the [preconfigured virtual machine image](simulation_vm.md) with ROS and Clover toolkit. > **Hint** You can use the [preconfigured virtual machine image](simulation_vm.md) with ROS and Clover toolkit.
Install package `ros-noetic-desktop-full` or `ros-noetic-desktop` using the [installation documentation](http://wiki.ros.org/noetic/Installation/Ubuntu). Install package `ros-melodic-desktop-full` or `ros-melodic-desktop` using the [installation documentation](http://wiki.ros.org/melodic/Installation/Ubuntu).
Start rviz Start rviz
--- ---

View File

@@ -51,11 +51,11 @@ Response format:
* `lat, lon` drone latitude and longitude *(degrees)*, requires [GPS](gps.md) module; * `lat, lon` drone latitude and longitude *(degrees)*, requires [GPS](gps.md) module;
* `alt` altitude in the global coordinate system (according to [WGS-84](https://ru.wikipedia.org/wiki/WGS_84) standard, not <abbr title="Above Mean Sea Level">AMSL</abbr>!), requires [GPS](gps.md) module; * `alt` altitude in the global coordinate system (according to [WGS-84](https://ru.wikipedia.org/wiki/WGS_84) standard, not <abbr title="Above Mean Sea Level">AMSL</abbr>!), requires [GPS](gps.md) module;
* `vx, vy, vz` drone velocity *(m/s)*; * `vx, vy, vz` drone velocity *(m/s)*;
* `roll` roll angle *(radians)*;
* `pitch` pitch angle *(radians)*; * `pitch` pitch angle *(radians)*;
* `roll` roll angle *(radians)*;
* `yaw` — yaw angle *(radians)*; * `yaw` — yaw angle *(radians)*;
* `roll_rate` angular roll velocity *(rad/s)*;
* `pitch_rate` — angular pitch velocity *(rad/s)*; * `pitch_rate` — angular pitch velocity *(rad/s)*;
* `roll_rate` angular roll velocity *(rad/s)*;
* `yaw_rate` angular yaw velocity *(rad/s)*; * `yaw_rate` angular yaw velocity *(rad/s)*;
* `voltage` total battery voltage *(V)*; * `voltage` total battery voltage *(V)*;
* `cell_voltage` battery cell voltage *(V)*. * `cell_voltage` battery cell voltage *(V)*.
@@ -103,7 +103,7 @@ Parameters:
* `yaw_rate` angular yaw velocity (will be used if yaw is set to `NaN`) *(rad/s)*; * `yaw_rate` angular yaw velocity (will be used if yaw is set to `NaN`) *(rad/s)*;
* `speed` flight speed (setpoint speed) *(m/s)*; * `speed` flight speed (setpoint speed) *(m/s)*;
* `auto_arm` switch the drone to `OFFBOARD` mode and arm automatically (**the drone will take off**); * `auto_arm` switch the drone to `OFFBOARD` mode and arm automatically (**the drone will take off**);
* `frame_id` [coordinate system](frames.md) for values `x`, `y`, `z` and `yaw`. Example: `map`, `body`, `aruco_map`. Default value: `map`. * `frame_id` [coordinate system](frames.md) for values `x`, `y`, `z`, `vx`, `vy`, `vz`. Example: `map`, `body`, `aruco_map`. Default value: `map`.
> **Note** If you don't want to change your current yaw set the `yaw` parameter to `NaN` (angular velocity by default is 0). > **Note** If you don't want to change your current yaw set the `yaw` parameter to `NaN` (angular velocity by default is 0).
@@ -261,22 +261,22 @@ set_velocity(vx=1, vy=0.0, vz=0, frame_id='body')
### set_attitude ### set_attitude
Set roll, pitch, yaw and throttle level (similar to [the `STABILIZED` mode](modes.md)). This service may be used for lower level control of the drone behavior, or controlling the drone when no reliable data on its position is available. Set pitch, roll, yaw and throttle level (similar to [the `STABILIZED` mode](modes.md)). This service may be used for lower level control of the drone behavior, or controlling the drone when no reliable data on its position is available.
Parameters: Parameters:
* `roll`, `pitch`, `yaw` requested roll, pitch, and yaw angle *(radians)*; * `pitch`, `roll`, `yaw` requested pitch, roll, and yaw angle *(radians)*;
* `thrust` — throttle level, ranges from 0 (no throttle, propellers are stopped) to 1 (full throttle). * `thrust` — throttle level, ranges from 0 (no throttle, propellers are stopped) to 1 (full throttle).
* `auto_arm` switch the drone to `OFFBOARD` mode and arm automatically (**the drone will take off**); * `auto_arm` switch the drone to `OFFBOARD` mode and arm automatically (**the drone will take off**);
* `frame_id` [coordinate system](frames.md) for `yaw` (Default value: `map`). * `frame_id` [coordinate system](frames.md) for `yaw` (Default value: `map`).
### set_rates ### set_rates
Set roll, pitch, and yaw rates and the throttle level (similar to [the `ACRO` mode](modes.md)). This is the lowest drone control level (excluding direct control of motor rotation speed). This service may be used to automatically perform aerobatic tricks (e.g., flips). Set pitch, roll, and yaw rates and the throttle level (similar to [the `ACRO` mode](modes.md)). This is the lowest drone control level (excluding direct control of motor rotation speed). This service may be used to automatically perform aerobatic tricks (e.g., flips).
Parameters: Parameters:
* `roll_rate`, `pitch_rate`, `yaw_rate` pitch, roll, and yaw rates *(rad/s)*; * `pitch_rate`, `roll_rate`, `yaw_rate` pitch, roll, and yaw rates *(rad/s)*;
* `thrust` — throttle level, ranges from 0 (no throttle, propellers are stopped) to 1 (full throttle). * `thrust` — throttle level, ranges from 0 (no throttle, propellers are stopped) to 1 (full throttle).
* `auto_arm` switch the drone to `OFFBOARD` and arm automatically (**the drone will take off**); * `auto_arm` switch the drone to `OFFBOARD` and arm automatically (**the drone will take off**);
@@ -305,16 +305,6 @@ rosservice call /land "{}"
> **Caution** In recent PX4 versions, the vehicle will be switched out of LAND mode to manual mode, if the remote control sticks are moved significantly. > **Caution** In recent PX4 versions, the vehicle will be switched out of LAND mode to manual mode, if the remote control sticks are moved significantly.
### release
If it's necessary to pause sending setpoint messages, use the `simple_offboard/release` service:
```python
release = rospy.ServiceProxy('simple_offboard/release', Trigger)
release()
```
## Additional materials ## Additional materials
* [ArUco-based position estimation and navigation](aruco.md). * [ArUco-based position estimation and navigation](aruco.md).

View File

@@ -2,7 +2,7 @@
Setting up the simulation environment from scratch requires some effort, but results in the most performant setup, with less chance of driver issues. Setting up the simulation environment from scratch requires some effort, but results in the most performant setup, with less chance of driver issues.
<!-- > **Hint** See up-to-date commands set for installation Clover simulation software in the script, that builds the virtual machine image with the simulator: [`install_software.sh`](https://github.com/CopterExpress/clover_vm/blob/master/scripts/install_software.sh). --> > **Hint** See up-to-date commands set for installation Clover simulation software in the script, that builds the virtual machine image with the simulator: [`install_software.sh`](https://github.com/CopterExpress/clover_vm/blob/master/scripts/install_software.sh).
Prerequisites: **Ubuntu 20.04**. Prerequisites: **Ubuntu 20.04**.
@@ -66,7 +66,7 @@ PX4 will be built along with the other packages in our workspace. You may clone
Clone PX4 sources and make the required symlinks: Clone PX4 sources and make the required symlinks:
```bash ```bash
git clone --recursive --depth 1 --branch v1.12.3 https://github.com/PX4/PX4-Autopilot.git ~/PX4-Autopilot git clone --recursive --depth 1 --branch v1.12.0 https://github.com/PX4/PX4-Autopilot.git ~/PX4-Autopilot
ln -s ~/PX4-Autopilot ~/catkin_ws/src/ ln -s ~/PX4-Autopilot ~/catkin_ws/src/
ln -s ~/PX4-Autopilot/Tools/sitl_gazebo ~/catkin_ws/src/ ln -s ~/PX4-Autopilot/Tools/sitl_gazebo ~/catkin_ws/src/
ln -s ~/PX4-Autopilot/mavlink ~/catkin_ws/src/ ln -s ~/PX4-Autopilot/mavlink ~/catkin_ws/src/
@@ -132,12 +132,6 @@ You can test autonomous flight using example scripts in `~/catkin_ws/src/clover/
## Additional steps ## Additional steps
To make it possible to run Gazebo simulation environment without Clover (`gazebo` command), add into your `.bashrc` sourcing Gazebo's initialization script:
```bash
echo "source /usr/share/gazebo/setup.sh" >> ~/.bashrc
```
Optionally, install roscore systemd service to have roscore running in background: Optionally, install roscore systemd service to have roscore running in background:
```bash ```bash
@@ -147,8 +141,6 @@ sudo systemctl enable roscore
sudo systemctl start roscore sudo systemctl start roscore
``` ```
### Web tools setup
Install any web server to serve Clover's web tools (`~/.ros/www` directory), e. g. Monkey: Install any web server to serve Clover's web tools (`~/.ros/www` directory), e. g. Monkey:
```bash ```bash
@@ -160,11 +152,3 @@ sudo cp ~/catkin_ws/src/clover/builder/assets/monkey.service /etc/systemd/system
sudo systemctl enable monkey sudo systemctl enable monkey
sudo systemctl start monkey sudo systemctl start monkey
``` ```
Create `~/.ros/www` using the following command:
```bash
rosrun clover www
```
If the set of packages containing a web part (through `www` directory) is changed, the above command also must be run.

View File

@@ -97,13 +97,3 @@ PX4_SIM_SPEED_FACTOR=0.42 roslaunch clover_simulation simulator.launch
The virtual machine may benefit from several CPU cores, especially if the cores are not very performant. In our tests, a four-core machine with only a single core allocated to the VM was unable to run the simulation, with constant interface freezes and dropped ROS messages. The same machine with all four cores available to the VM was able to run the simulation at 0.25 real-time speed. The virtual machine may benefit from several CPU cores, especially if the cores are not very performant. In our tests, a four-core machine with only a single core allocated to the VM was unable to run the simulation, with constant interface freezes and dropped ROS messages. The same machine with all four cores available to the VM was able to run the simulation at 0.25 real-time speed.
Do note that you should not allocate more resources than you have on your host hardware. Do note that you should not allocate more resources than you have on your host hardware.
### Changing the map of ArUco-markers in the simulator
In order to change the map of ArUco-markers in the simulator, you can use the following command:
```bash
rosrun clover_simulation aruco_gen --single-model --source-world=$(catkin_find clover_simulation resources/worlds/clover.world) $(catkin_find aruco_pose map/map.txt) > $(catkin_find clover_simulation resources/worlds/clover_aruco.world)
```
In this example, `map.txt` is the name of markers name.

View File

@@ -2,7 +2,7 @@
In addition to [native installation instructions](simulation_native.md), we provide a [preconfigured developer virtual machine image](https://github.com/CopterExpress/clover_vm/releases/latest). The image contains: In addition to [native installation instructions](simulation_native.md), we provide a [preconfigured developer virtual machine image](https://github.com/CopterExpress/clover_vm/releases/latest). The image contains:
* Ubuntu 20.04 with XFCE lightweight desktop environment; * Ubuntu 18.04 with XFCE lightweight desktop environment;
* ROS packages required to develop for the Clover platform; * ROS packages required to develop for the Clover platform;
* QGroundControl; * QGroundControl;
* preconfigured Gazebo simulation environment; * preconfigured Gazebo simulation environment;
@@ -16,6 +16,8 @@ The VM is an easy way to set up a simulation environment, but can be used as a d
You can download the latest VM image [in the VM releases repository](https://github.com/CopterExpress/clover_vm/releases). You can download the latest VM image [in the VM releases repository](https://github.com/CopterExpress/clover_vm/releases).
> **Note** The virtual machine should be used when native installation is not feasible or possible. You may experience reduced performance in programs that use 3D rendering, like rviz and Gazebo.
## Setting up the VM ## Setting up the VM
You need to use a VM manager that supports OVF format, like [VirtualBox](https://www.virtualbox.org/wiki/Downloads), [VMware Player](https://www.vmware.com/products/workstation-player.html) or [VMware Workstation](https://www.vmware.com/products/workstation-pro.html). You need to use a VM manager that supports OVF format, like [VirtualBox](https://www.virtualbox.org/wiki/Downloads), [VMware Player](https://www.vmware.com/products/workstation-player.html) or [VMware Workstation](https://www.vmware.com/products/workstation-pro.html).

View File

@@ -144,7 +144,7 @@ Determine whether the copter is turned upside-down:
PI_2 = math.pi / 2 PI_2 = math.pi / 2
telem = get_telemetry() telem = get_telemetry()
flipped = abs(telem.roll) > PI_2 or abs(telem.pitch) > PI_2 flipped = abs(telem.pitch) > PI_2 or abs(telem.roll) > PI_2
``` ```
### # {#angle-hor} ### # {#angle-hor}
@@ -155,8 +155,8 @@ Calculate the copter horizontal angle:
PI_2 = math.pi / 2 PI_2 = math.pi / 2
telem = get_telemetry() telem = get_telemetry()
flipped = not -PI_2 <= telem.roll <= PI_2 or not -PI_2 <= telem.pitch <= PI_2 flipped = not -PI_2 <= telem.pitch <= PI_2 or not -PI_2 <= telem.roll <= PI_2
angle_to_horizon = math.atan(math.hypot(math.tan(telem.roll), math.tan(telem.pitch))) angle_to_horizon = math.atan(math.hypot(math.tan(telem.pitch), math.tan(telem.roll)))
if flipped: if flipped:
angle_to_horizon = math.pi - angle_to_horizon angle_to_horizon = math.pi - angle_to_horizon
``` ```
@@ -207,9 +207,9 @@ def pose_update(pose):
# Processing new data of copter's position # Processing new data of copter's position
pass pass
rospy.Subscriber('mavros/local_position/pose', PoseStamped, pose_update) rospy.Subscriber('/mavros/local_position/pose', PoseStamped, pose_update)
rospy.Subscriber('mavros/local_position/velocity', TwistStamped, velocity_update) rospy.Subscriber('/mavros/local_position/velocity', TwistStamped, velocity_update)
rospy.Subscriber('mavros/battery', BatteryState, battery_update) rospy.Subscriber('/mavros/battery', BatteryState, battery_update)
rospy.Subscriber('mavros/rc/in', RCIn, rc_callback) rospy.Subscriber('mavros/rc/in', RCIn, rc_callback)
rospy.spin() rospy.spin()
@@ -240,30 +240,6 @@ ros_msg = mavlink.convert_to_rosmsg(msg)
mavlink_pub.publish(ros_msg) mavlink_pub.publish(ros_msg)
``` ```
<!-- markdownlint-disable MD044 -->
### # {#mavlink-receive}
<!-- markdownlint-enable MD044 -->
Subscribe to all MAVLink messages from the flight controller and decode them:
```python
from mavros_msgs.msg import Mavlink
from mavros import mavlink
from pymavlink import mavutil
link = mavutil.mavlink.MAVLink('', 255, 1)
def mavlink_cb(msg):
mav_msg = link.decode(mavlink.convert_to_bytes(msg))
print('msgid =', msg.msgid, mav_msg) # print message id and parsed message
mavlink_sub = rospy.Subscriber('mavlink/from', Mavlink, mavlink_cb)
rospy.spin()
```
### # {#rc-sub} ### # {#rc-sub}
React to the drone's mode switching (may be used for starting an autonomous flight, see [example](https://gist.github.com/okalachev/b709f04522d2f9af97e835baedeb806b)): React to the drone's mode switching (may be used for starting an autonomous flight, see [example](https://gist.github.com/okalachev/b709f04522d2f9af97e835baedeb806b)):
@@ -324,7 +300,7 @@ def flip():
while True: while True:
telem = get_telemetry() telem = get_telemetry()
flipped = abs(telem.roll) > PI_2 or abs(telem.pitch) > PI_2 flipped = abs(telem.pitch) > PI_2 or abs(telem.roll) > PI_2
if flipped: if flipped:
break break
@@ -349,7 +325,7 @@ from pymavlink import mavutil
from mavros_msgs.srv import CommandLong from mavros_msgs.srv import CommandLong
from mavros_msgs.msg import State from mavros_msgs.msg import State
send_command = rospy.ServiceProxy('mavros/cmd/command', CommandLong) send_command = rospy.ServiceProxy('/mavros/cmd/command', CommandLong)
def calibrate_gyro(): def calibrate_gyro():
rospy.loginfo('Calibrate gyro') rospy.loginfo('Calibrate gyro')
@@ -414,26 +390,6 @@ rospy.sleep(5)
flow_client.update_configuration({'enabled': True}) flow_client.update_configuration({'enabled': True})
``` ```
<!-- markdownlint-disable MD044 -->
### # {#aruco-map-dynamic}
> **Info** For [RPi image](image.md) version > 0.23.
Change the used [ArUco markers map file](aruco_map.md) dynamically:
<!-- markdownlint-enable MD044 -->
```python
import rospy
import dynamic_reconfigure.client
rospy.init_node('flight')
map_client = dynamic_reconfigure.client.Client('aruco_map')
map_client.update_configuration({'map': '/home/pi/catkin_ws/src/clover/aruco_pose/map/office.txt'})
```
### # {#wait-global-position} ### # {#wait-global-position}
Wait for global position to appear (finishing [GPS receiver](gps.md) initialization): Wait for global position to appear (finishing [GPS receiver](gps.md) initialization):
@@ -480,11 +436,3 @@ param_set(param_id='COM_FLTMODE1', value=ParamValue(integer=8))
# Set parameter of type FLOAT: # Set parameter of type FLOAT:
param_set(param_id='MPC_Z_P', value=ParamValue(real=1.5)) param_set(param_id='MPC_Z_P', value=ParamValue(real=1.5))
``` ```
### # {#is-simulation}
Check, if the code is running inside a [Gazebo simulation](simulation.md):
```python
is_simulation = rospy.get_param('/use_sim_time', False)
```

View File

@@ -49,10 +49,10 @@ If you are using the marker map, where the markers have equal distances along th
After you fill out the map, you need to apply it. To do it, edit the file `aruco.launch`, located in `~/catkin_ws/src/clover/clover/launch/`. Change the line `<param name="map" value="$(find aruco_pose)/map/map_name.txt"/>`, where `map_name.txt` is the name of your map file. After you fill out the map, you need to apply it. To do it, edit the file `aruco.launch`, located in `~/catkin_ws/src/clover/clover/launch/`. Change the line `<param name="map" value="$(find aruco_pose)/map/map_name.txt"/>`, where `map_name.txt` is the name of your map file.
If you are using markers that are not linked to horizontal surfaces (floor, ceiling), you must blank the `placement` argument in the same file: If you are using markers that are not linked to horizontal surfaces (floor, ceiling), you must disable the parameter `known_tilt` both in the module `aruco_detect` and `aruco_map` in the same file. To do it automatically, enter:
```xml ```bash
<arg name="placement" default=""/> sed -i "/known_tilt/s/value=\".*\"/value=\"\"/" /home/pi/catkin_ws/src/clover/clover/launch/aruco.launch
``` ```
After all the settings, call `sudo systemctl restart clover` to restart the `clover` service. After all the settings, call `sudo systemctl restart clover` to restart the `clover` service.

View File

@@ -20,7 +20,7 @@ Parameters `width`, `height`, etc. re also available. Read more about `web_video
## Browse with rqt_image_view ## Browse with rqt_image_view
To browse images with the rqt tools the user needs a computer with Ubuntu 20.04 and [ROS Noetic](http://wiki.ros.org/noetic/Installation/Ubuntu). To browse images with the rqt tools the user needs a computer with Ubuntu 18.04 and [ROS Melodic](http://wiki.ros.org/melodic/Installation/Ubuntu).
[Connect to the Clover Wi-Fi network](wifi.md) an run `rqt_image_view` with its IP-address: [Connect to the Clover Wi-Fi network](wifi.md) an run `rqt_image_view` with its IP-address:

View File

@@ -109,7 +109,6 @@
* [Виртуальная MAVLink-камера](duocam_mavlink.md) * [Виртуальная MAVLink-камера](duocam_mavlink.md)
* [Настройка DuoCam](duocam_setup.md) * [Настройка DuoCam](duocam_setup.md)
* [Мероприятия](events.md) * [Мероприятия](events.md)
* [CopterHack-2023](copterhack2023.md)
* [CopterHack-2022](copterhack2022.md) * [CopterHack-2022](copterhack2022.md)
* [CopterHack-2021](copterhack2021.md) * [CopterHack-2021](copterhack2021.md)
* [CopterHack-2019](copterhack2019.md) * [CopterHack-2019](copterhack2019.md)

View File

@@ -1,5 +1,7 @@
# Работа с камерой # Работа с камерой
> **Note** В версии образа **0.20** пакет и сервис `clever` был переименован в `clover`. Для более ранних версий см. документацию для версии [**0.19**](https://github.com/CopterExpress/clover/blob/v0.19/docs/ru/camera.md).
<!-- TODO: физическое подключение --> <!-- TODO: физическое подключение -->
Для работы с основной камерой необходимо убедиться что она включена в файле `~/catkin_ws/src/clover/clover/launch/clover.launch`: Для работы с основной камерой необходимо убедиться что она включена в файле `~/catkin_ws/src/clover/clover/launch/clover.launch`:
@@ -54,6 +56,8 @@ raspistill -o test.jpg
### Python ### Python
Основная статья: http://wiki.ros.org/cv_bridge/Tutorials/ConvertingBetweenROSImagesAndOpenCVImagesPython.
Пример создания подписчика на топик с изображением с основной камеры для обработки с использованием OpenCV: Пример создания подписчика на топик с изображением с основной камеры для обработки с использованием OpenCV:
```python ```python
@@ -61,14 +65,12 @@ import rospy
import cv2 import cv2
from sensor_msgs.msg import Image from sensor_msgs.msg import Image
from cv_bridge import CvBridge from cv_bridge import CvBridge
from clover import long_callback
rospy.init_node('cv') rospy.init_node('computer_vision_sample')
bridge = CvBridge() bridge = CvBridge()
@long_callback
def image_callback(data): def image_callback(data):
img = bridge.imgmsg_to_cv2(data, 'bgr8') # OpenCV image cv_image = bridge.imgmsg_to_cv2(data, 'bgr8') # OpenCV image
# Do any image processing with cv2... # Do any image processing with cv2...
image_sub = rospy.Subscriber('main_camera/image_raw', Image, image_callback) image_sub = rospy.Subscriber('main_camera/image_raw', Image, image_callback)
@@ -76,31 +78,19 @@ image_sub = rospy.Subscriber('main_camera/image_raw', Image, image_callback)
rospy.spin() rospy.spin()
``` ```
> **Note** Обработка изображения может занимать значительное время. Это может вызвать [проблему](https://github.com/ros/ros_comm/issues/1901) в библиотеке rospy, которая приведет к обработке устаревших кадров с камеры. Для решения этой проблемы необходимо использовать декоратор `long_callback` из библиотеки `clover`, как в примере выше.
#### Ограничение использования CPU
При использовании топика `main_camera/image_raw` скрипт будет обрабатывать максимальное количество кадров с камеры, активно используя CPU (вплоть до 100%). В задачах, где обработка каждого кадра не критична, можно использовать топик, где кадры публикуются с частотой 5 Гц: `main_camera/image_raw_throttled`:
```python
image_sub = rospy.Subscriber('main_camera/image_raw_throttled', Image, image_callback, queue_size=1)
```
#### Публикация изображений
Для отладки обработки изображения можно публиковать отдельный топик с обработанным изображением: Для отладки обработки изображения можно публиковать отдельный топик с обработанным изображением:
```python ```python
image_pub = rospy.Publisher('~debug', Image) image_pub = rospy.Publisher('~debug', Image)
``` ```
Публикация обработанного изображения: Публикация обработанного изображения (в конце функции image_callback):
```python ```python
image_pub.publish(bridge.cv2_to_imgmsg(img, 'bgr8')) image_pub.publish(bridge.cv2_to_imgmsg(cv_image, 'bgr8'))
``` ```
Получаемые изображения можно просматривать используя [web_video_server](web_video_server.md) или [rqt](rviz.md). Получаемые изображения можно просматривать используя [web_video_server](web_video_server.md).
#### Получение одного кадра #### Получение одного кадра
@@ -111,12 +101,12 @@ import rospy
from sensor_msgs.msg import Image from sensor_msgs.msg import Image
from cv_bridge import CvBridge from cv_bridge import CvBridge
rospy.init_node('cv') rospy.init_node('computer_vision_sample')
bridge = CvBridge() bridge = CvBridge()
# ... # ...
# Retrieve a frame: # Получение кадра:
img = bridge.imgmsg_to_cv2(rospy.wait_for_message('main_camera/image_raw', Image), 'bgr8') img = bridge.imgmsg_to_cv2(rospy.wait_for_message('main_camera/image_raw', Image), 'bgr8')
``` ```
@@ -133,32 +123,38 @@ img = bridge.imgmsg_to_cv2(rospy.wait_for_message('main_camera/image_raw', Image
```python ```python
import rospy import rospy
from pyzbar import pyzbar from pyzbar import pyzbar
import cv2
from cv_bridge import CvBridge from cv_bridge import CvBridge
from sensor_msgs.msg import Image from sensor_msgs.msg import Image
from clover import long_callback
rospy.init_node('cv')
bridge = CvBridge() bridge = CvBridge()
@long_callback rospy.init_node('barcode_test')
def image_callback(msg):
img = bridge.imgmsg_to_cv2(msg, 'bgr8') # Image subscriber callback function
barcodes = pyzbar.decode(img) def image_callback(data):
cv_image = bridge.imgmsg_to_cv2(data, 'bgr8') # OpenCV image
barcodes = pyzbar.decode(cv_image)
for barcode in barcodes: for barcode in barcodes:
b_data = barcode.data.decode('utf-8') b_data = barcode.data.decode("utf-8")
b_type = barcode.type b_type = barcode.type
(x, y, w, h) = barcode.rect (x, y, w, h) = barcode.rect
xc = x + w/2 xc = x + w/2
yc = y + h/2 yc = y + h/2
print('Found {} with data {} with center at x={}, y={}'.format(b_type, b_data, xc, yc)) print("Found {} with data {} with center at x={}, y={}".format(b_type, b_data, xc, yc))
image_sub = rospy.Subscriber('main_camera/image_raw_throttled', Image, image_callback, queue_size=1) image_sub = rospy.Subscriber('main_camera/image_raw', Image, image_callback, queue_size=1)
rospy.spin() rospy.spin()
``` ```
> **Hint** Смотрите другие примеры по работе с компьютерным зрением в каталоге `~/examples` [образа для RPi](image.md). Скрипт будет занимать 100% процессора. Для искусственного замедления работы скрипта можно запустить [throttling](http://wiki.ros.org/topic_tools/throttle) кадров с камеры, например, в 5 Гц (`main_camera.launch`):
```xml
<node pkg="topic_tools" name="cam_throttle" type="throttle"
args="messages main_camera/image_raw 5.0 main_camera/image_raw_throttled"/>
```
Топик для подписчика в этом случае необходимо поменять на `main_camera/image_raw_throttled`.
## Запись видео ## Запись видео

View File

@@ -10,14 +10,14 @@
Основной туториал: http://wiki.ros.org/camera_calibration/Tutorials/MonocularCalibration. Основной туториал: http://wiki.ros.org/camera_calibration/Tutorials/MonocularCalibration.
Для калибровки камеры с использованием ROS-пакета camera_calibration необходим компьютер с установленным ОС GNU/Linux и [ROS Noetic](http://wiki.ros.org/noetic/Installation/Ubuntu). Для калибровки камеры с использованием ROS-пакета camera_calibration необходим компьютер с установленным ОС GNU/Linux и [ROS Melodic](ros-install.md).
<img src="../assets/camera_calibration.png" alt="ROS Camera Calibrator" class="zoom center" width=600> <img src="../assets/camera_calibration.png" alt="ROS Camera Calibrator" class="zoom center" width=600>
1. Используя Терминал, установите на компьютер пакет `camera_calibration`: 1. Используя Терминал, установите на компьютер пакет `camera_calibration`:
```bash ```bash
sudo apt-get install ros-noetic-camera-calibration sudo apt-get install ros-melodic-camera-calibration
``` ```
2. Скачайте калибровочную доску  [`chessboard.pdf`](../assets/chessboard.pdf). Распечатайте доску на принтере либо выведите ее на экран компьютера. 2. Скачайте калибровочную доску  [`chessboard.pdf`](../assets/chessboard.pdf). Распечатайте доску на принтере либо выведите ее на экран компьютера.

View File

@@ -20,14 +20,15 @@
## Подключение по UART ## Подключение по UART
> **Note** В версии образа **0.20** пакет и сервис `clever` был переименован в `clover`. Для более ранних версий см. документацию для версии [**0.19**](https://github.com/CopterExpress/clover/blob/v0.19/docs/ru/connection.md).
<!-- TODO схема подключения --> <!-- TODO схема подключения -->
Дополнительным способом подключения является подключение подключение по интерфейсу UART. Дополнительным способом подключения является подключение подключение по интерфейсу UART.
1. Подключите Raspberry Pi к полетному контроллеру по UART. Для этого соедините кабелем порт TELEM 2 на полетном контроллере к пинам на Raspberry Pi следующем образом: черный провод (GND) к Ground, зеленый (*UART_RX*) к *GPIO14*, желтый (*UART_TX*) к *GPIO15*. Красный провод (*5V*) подключать не нужно. 1. Подключите Raspberry Pi к полетному контроллеру по UART.
2. Измените значения параметров PX4: `MAV_1_CONFIG` на TELEM 2, `SER_TEL2_BAUND` на 921600 8N1. В PX4 до версии v1.10.0 необходима установка параметра `SYS_COMPANION` в значение 921600. 2. [Подключитесь в Raspberry Pi по SSH](ssh.md).
3. [Подключитесь в Raspberry Pi по SSH](ssh.md). 3. Поменяйте в launch-файле Клевера (`~/catkin_ws/src/clover/clover/launch/clover.launch`) тип подключения на UART:
4. Поменяйте в launch-файле Клевера (`~/catkin_ws/src/clover/clover/launch/clover.launch`) тип подключения на UART:
```xml ```xml
<arg name="fcu_conn" default="uart"/> <arg name="fcu_conn" default="uart"/>
@@ -39,4 +40,15 @@
sudo systemctl restart clover sudo systemctl restart clover
``` ```
> **Hint** Для корректной работы подключения Raspberry Pi и полетного контроллера по UART необходимо установить значение параметра `SYS_COMPANION` на 921600.
## Подключение к SITL
Для того, чтобы подсоединиться к локально/удаленно запущенному [SITL](sitl.md), необходимо установить аргумент `fcu_conn` в `udp`, и `fcu_ip` в IP-адрес машины, где запущен SITL (`127.0.0.1` для локального):
```xml
<arg name="fcu_conn" default="udp"/>
<arg name="fcu_ip" default="127.0.0.1"/>
```
**Далее**: [Подключение QGroundControl по Wi-Fi](gcs_bridge.md). **Далее**: [Подключение QGroundControl по Wi-Fi](gcs_bridge.md).

View File

@@ -1,169 +0,0 @@
# CopterHack 2023
<img src="../assets/copterhack2023.svg" width=300 align=right>
CopterHack 2023 — это международный конкурс по разработке проектов по летающей робототехнике с открытым исходным кодом. Основным языком конкурса является английский.
Ознакомиться со статьями команд-финалистов предыдущих лет можно в статьях о [CopterHack 2021](copterhack2021.md), [CopterHack 2022](copterhack2022.md).
На конкурс принимаются проекты с открытым исходным кодом и совместимые с платформой квадрокоптера "Клевер". На протяжении конкурса команды работают на собственными идеями и разработками, приближая их к состоянию готового продукта. В этом участникам помогают эксперты отрасли через лекции и регулярную обратную связь.
## Проекты участников конкурса {#participants}
|Место|Команда|Проект|Балл|
|:-:|-|-|-|
||🇷🇺 Clover Cloud Team|[Clover Cloud Platform](https://github.com/DevMBS/clover/blob/clover-cloud-platform/docs/en/clover-cloud-platform.md)||
||🇰🇬 Zavarka|[Система обмена грузами с помощью конвейера](https://github.com/aiurobotics/clover/blob/conveyance/docs/ru/conveyance.md)||
||🇮🇳 DJS PHOENIX|[Autonomous Racing Drone](https://github.com/DJSPhoenix/clover/blob/DJSPhoenix_chetak/docs/ru/djs_phoenix_chetak.md)||
||🇷🇺 FSOTM|[Дрон-перехватчик](https://github.com/deadln/clover/blob/interceptor/docs/ru/interceptor.md)||
||🇰🇬 Бездомные|[Дрон-бездомный](https://github.com/Isa-jesus/clover/blob/trash-collector/docs/ru/trash-collector.md)||
||🇷🇺 Digital otters|[Digital otters](https://github.com/Mentalsupernova/clover_cool/blob/new-article.md/docs/ru/new-article.md)||
||🇷🇺 Light Flight|[Сопровождение БПЛА при посадке](https://github.com/SirSerow/clover_inertial_ns/blob/inertial-1/Description.md)||
||🇰🇬 LiveSavers|[LiveSavers](https://github.com/Sarvar00/clover/blob/livesavers/docs/ru/livesaver.md)||
||🇷🇺 C305|[Система радио-навигации](https://github.com/Lukerrr/clover-c305/blob/nav_beacon/docs/ru/nav-beacon.md)||
||🇷🇺 XenCOM|[Bound by fate](https://github.com/xenkek/clover/blob/xenkek-patch-1/docs/ru/bound_by_fate.md)||
||🇨🇦 Clover with Motion Capture System|[Clover with Motion Capture System](https://github.com/ssmith-81/clover/blob/MoCap_Clover/docs/en/mocap_clover.md)||
||🇧🇷 Atena|[Swarm in Blocks 2](https://github.com/Grupo-SEMEAR-USP/clover/blob/swarm_in_blocks_2/docs/en/swarm_in_blocks_2.md)||
||🇧🇾 FTL|[Advanced Clover 2](https://github.com/FTL-team/clover/blob/FTL-advancedClover3/docs/ru/advanced_clover_simulator_platform.md)||
||🇷🇺 Лицей №128|[Платформа для зарядки квадрокоптера](https://github.com/Juli-Shvetsova/clover/blob/liceu128-1/docs/ru/liceu128.md)||
||🇷🇺 Ava_Clover|[DoubleClover](https://github.com/bessiaka/clover/blob/Ava_Clover/docs/ru/soosocta.md)||
||🇷🇺 TPU_1|[Совместная транспортировка груза](https://github.com/shamoleg/clover/blob/tpu_1/docs/ru/tpu_1.md)||
||🇷🇺 TPU_2|[Алгоритм полета сквозь лесную местность](https://github.com/shamoleg/clover/blob/tpu_2/docs/ru/tpu_2.md)|&nbsp;|
## Этапы CopterHack 2023
Отборочный и проектный этапы конкурса проходят в онлайн-формате, формат проведения финала гибридный (оффлайн + онлайн). Конкурс подразумевает ежемесячные апдейты от команд с получением регулярной обратной связи от жюри. Для участия в заключительном этапе необходимо подготовить финальное видео и презентацию о результатах проекта.
1. Отборочный этап. Подача заявок (до 31 октября 2022).
2. Проектный этап. Менторство проектов (1 ноября 2022 — 28 февраля 2023).
3. Подготовка финального видео (1 — 31 марта 2023).
4. Заключительный этап. Финальная защита проектов на английском языке (23 апреля 2023).
## Условия и критерии оценки
Условия, предъявляемые к проектам:
1. Открытый исходный код/модели/схемы/чертежи.
2. Совместимость с платформой "Клевер".
Критерии оценивания жюри в финале:
1. Готовность и статья (макс. 10 баллов): степень готовности проекта; доступное и понятное описание проекта в статье; прикреплены код с комментариями, схемы, чертежи. По статье должно быть возможно повторить проект, получить результат.
2. Объем проделанной работы (макс. 6 баллов): объем проделанной командой работы в рамках CopterHack, ее сложность и технический уровень.
3. Полезность для Клевера (макс. 6 баллов): актуальность применения на практике в платформе Клевер и PX4, потенциальный уровень спроса на разработку со стороны других пользователей Клевера.
4. Презентация на финале (макс. 3 балла): качество и зрелищность финальной презентации; полнота освещения проекта; демонстрация; ответы на вопросы жюри.
## Призовой фонд
Призы от компании COEX по результатам оценивания жюри на финале:
* I место: $3000.
* II место: $2000.
* III место: $1000.
* IV место: $500.
* V место: $500.
Партнеры конкурса могут поощрить команды по дополнительным критериям, выявленным в результате оценки проектов в ходе финала.
## Как подать заявку?
> **Note** Для подачи заявки необходимо иметь аккаунт на [GitHub](https://github.com).
Подготовьте вашу заявку и пришлите ее в виде Draft Pull Request в [репозиторий Клевера](https://github.com/CopterExpress/clover).
1. Сделайте форк репозитория Клевера:
<img src="../assets/github_application/github-fork.png" alt="GitHub Fork">
2. На странице вашего форка зайдите в раздел `docs/ru` и создайте новый файл в формате [Markdown](https://ru.wikipedia.org/wiki/Markdown):
<img src="../assets/github_application/create_new_file.png" alt="GitHub Create New File">
3. Введите название вашей статьи. Например, `new-article.md`
<img src="../assets/github_application/new_article.png" alt="GitHub New Article">
4. Оформите вашу заявку в соответствии с рекомендуемым шаблоном:
```markdown
# Название проекта
[CopterHack-2023](copterhack2023.md), команда **Название команды**.
## Информация о команде
Состав команды:
(Опишите состав команды: имя и фамилия, контакты (имя пользователя в Telegram), роль в команде).
* Александр Соколов, @aleksandrsokolov111, инженер.
* Елена Смирнова, @elenasmirnova111, программист.
## Описание проекта
### Идея проекта
Опишите кратко идею и стадию проекта.
### Планируемые результаты
Опишите как вы видите результат проекта.
### Использование платформы "Клевер"
Опишите как в вашем проекте будет использоваться платформа "Клевер".
### Дополнительная информация по желанию участников
Например, информация об опыте работы команды над проектами, прикрепить ссылку на статьи, видео.
```
5. Перейдите вниз страницы и создайте новую ветку с названием вашей статьи:
<img src="../assets/github_application/propose_new_file.png" alt="GitHub Propose New File">
> **Note** Не добавляйте ваши изменения непосредственно в ветку `master`, создайте новую ветку.
6. При необходимости поместите дополнительные визуальные материалы в папку `docs/assets` и оформите на них ссылки в вашей статье.
7. Сделайте Draft Pull Request вашей ветки в master Клевера:
<img src="../assets/github_application/github-pull-request-create.png" alt="GitHub Create Pull">
8. В комментариях Pull Request вам будет дана обратная связь по заявке.
9. Обратите внимание на блок *Checks*, в графе Documentation должна стоять галочка. Если там стоит крестик, перейдите по ссылке *Details*, чтобы увидеть список проблем с оформлением статьи. При необходимости изменения добавляемых файлов, меняйте их в вашей ветке изменения будут появляться в Pull Request автоматически. **Не создавайте новый Pull Request для одной и той же заявки**.
10. На протяжении конкурса вы будете работать над этим документом, приближая его к состоянию статьи. В документе будет видна история разработки и ежемесячные апдейты. К финалу конкурса вы сможете опубликовать вашу статью, это и будет результат вашей работы в CopterHack.
Участники конкурса будут добавлены в Telegram-группу, куда можно отправлять первый апдейт и получить обратную связь от жюри. Для команд-участников предусмотрена скидка 40% на конструктор программируемого квадрокоптера "Клевер".
> **Info** Ограничения по возрасту, образованию и количеству человек в команде отсутствуют.
## Конкурс статей участников проектов CopterHack 2023
Наши участники уже 2 года работают над передовыми проектами в области летающей робототехники. В этом году мы хотим ввести новый конкурс, стимулирующий участников презентовать результаты исследований, выполняющихся в рамках конкурса на престижных международных конференциях, а также публиковать их в российских и международных журналах по тематике конкурса.
На конкурс принимаются оригинальные статьи в следующих номинациях:
* $2000 за статью в журнале первого квартиля (Q1), индексируемом в Scopus, Web of Science.
* $1000 за статью журнале, индексируемом в Scopus, Web of Science.
* $500 за статью, опубликованную в сборнике материалов конференции (Conference Proceedings), индексируемые в Scopus, Web of Science.
> **Note** [Как узнать квартиль журнала в Scopus и WOS](http://russian-science.info/kak-uznat-kvartil-i-protsentil-zhurnala-v-scopus-i-wos).
Правила:
1. Статья должна отражать результаты проекта, разработанного в рамках CopterHack 2023.
2. Статья должна быть принята к печати к моменту подачи заявки на участие в конкурсе статей.
3. В acknowledgment следует указать, что работа выполнена в рамках конкурса.
**Прием заявок**: до 10 декабря 2023 года. Прием заявок осуществляется через [Google Форму](https://docs.google.com/forms/d/e/1FAIpQLSf52x0CTur-wUCG2URwY-p85gEUBUvgC0mPVNot0RHVjqcLZA/viewform).
**Объявление результатов**: 24 декабря 2023 года.
---
По всем вопросам: [группа CopterHack в Telegram](https://t.me/CopterHack).
> **Info** Если вы хотите стать партнером конкурса или членом жюри, обращайтесь к [Олегу Понфиленку в Telegram](https://t.me/ponfilenok).

View File

@@ -26,7 +26,7 @@
Прием заявок осуществляется через [Google Форму](https://docs.google.com/forms/d/e/1FAIpQLScE2kN5dO2OYNSM8hOYzOa5Qvh2uDdd9Fjx8OnL1W93bfEBgw/viewform). Прием заявок осуществляется через [Google Форму](https://docs.google.com/forms/d/e/1FAIpQLScE2kN5dO2OYNSM8hOYzOa5Qvh2uDdd9Fjx8OnL1W93bfEBgw/viewform).
Дедлайн подачи заявок: 30 ноября 2022 года. Дедлайн подачи заявок: 1 сентября 2022 года.
### Призы ### Призы
@@ -64,7 +64,7 @@
Прием заявок осуществляется через [Google Форму](https://docs.google.com/forms/d/e/1FAIpQLSdelVy6yQ1iN6u88KeiEIKGj7gGaM0xccSt2tiYKB46ICmjkQ/viewform). Прием заявок осуществляется через [Google Форму](https://docs.google.com/forms/d/e/1FAIpQLSdelVy6yQ1iN6u88KeiEIKGj7gGaM0xccSt2tiYKB46ICmjkQ/viewform).
Дедлайн подачи заявок: 30 ноября 2022 года. Дедлайн подачи заявок: 1 сентября 2022 года.
### Призы ### Призы
@@ -106,7 +106,7 @@
Прием заявок осуществляется через [Google Форму](https://docs.google.com/forms/d/e/1FAIpQLSdf2Q68X4hPnFE9f3EP95AxPNnzHKqIsFHtTRT6EBKiH93wzg/viewform). Прием заявок осуществляется через [Google Форму](https://docs.google.com/forms/d/e/1FAIpQLSdf2Q68X4hPnFE9f3EP95AxPNnzHKqIsFHtTRT6EBKiH93wzg/viewform).
Дедлайн подачи заявок: 30 ноября 2022 года Дедлайн подачи заявок: 1 сентября 2022 года
### Призы ### Призы

View File

@@ -40,8 +40,6 @@ MAVROS подписывается на определенные ROS-топики
`/mavros/setpoint_position/local` — установить целевую позицию и рысканье \(yaw\) беспилотника \(в системе координат ENU\). `/mavros/setpoint_position/local` — установить целевую позицию и рысканье \(yaw\) беспилотника \(в системе координат ENU\).
`/mavros/setpoint_position/global` установить целевую позицию в глобальных координатах (ширина, долгота и высота) и рысканье беспилотника.
`/mavros/setpoint_velocity/cmd_vel` — установить целевую линейную скорость беспилотника. `/mavros/setpoint_velocity/cmd_vel` — установить целевую линейную скорость беспилотника.
`/mavros/setpoint_attitude/attitude` и `/mavros/setpoint_attitude/att_throttle` — установить целевую ориентацию \(Attitude\) и уровень газа. `/mavros/setpoint_attitude/attitude` и `/mavros/setpoint_attitude/att_throttle` — установить целевую ориентацию \(Attitude\) и уровень газа.
@@ -54,4 +52,4 @@ MAVROS подписывается на определенные ROS-топики
`/mavros/setpoint_raw/attitude` — отправка пакета [SET\_ATTITUDE\_TARGET](https://mavlink.io/en/messages/common.html#SET_ATTITUDE_TARGET). Позволяет установить целевую ориентацию / угловые скорости и уровень газа. Выбор устанавливаемых величин осуществляется с помощью поля `type_mask` `/mavros/setpoint_raw/attitude` — отправка пакета [SET\_ATTITUDE\_TARGET](https://mavlink.io/en/messages/common.html#SET_ATTITUDE_TARGET). Позволяет установить целевую ориентацию / угловые скорости и уровень газа. Выбор устанавливаемых величин осуществляется с помощью поля `type_mask`
`/mavros/setpoint_raw/global` — отправка пакета [SET\_POSITION\_TARGET\_GLOBAL\_INT](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_GLOBAL_INT). Позволяет установить целевую позицию в глобальных координатах \(ширина, долгота, высота\), а также скорости полета. `/mavros/setpoint_raw/global` — отправка пакета [SET\_POSITION\_TARGET\_GLOBAL\_INT](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_GLOBAL_INT). Позволяет установить целевую позицию в глобальных координатах \(ширина, долгота, высота\), а также скорости полета. **Не поддерживается в PX4** \([issue](https://github.com/PX4/Firmware/issues/7552)\).

View File

@@ -22,7 +22,7 @@
|Параметр|Значение|Примечание| |Параметр|Значение|Примечание|
|-|-|-| |-|-|-|
|`LPE_FUSION`|86|Чекбоксы: *flow* + *vis* + *land detector* + *gyro comp*. При полете над ровным полом возможно включение *pub agl as lpos down*. <br>Подробнее: [Optical Flow](optical_flow.md), [ArUco-маркеры](aruco_map.md), [GPS](gps.md).| |`LPE_FUSION`|86|Чекбоксы: *flow* + *vis* + *land Detector* + *gyro comp*. При полете над ровным полом возможно включение *pub agl as lpos down*. <br>Подробнее: [Optical Flow](optical_flow.md), [ArUco-маркеры](aruco_map.md), [GPS](gps.md).|
|`LPE_VIS_DELAY`|0.0|| |`LPE_VIS_DELAY`|0.0||
|`LPE_VIS_Z`|0.1|| |`LPE_VIS_Z`|0.1||
|`LPE_FLW_SCALE`|1.0|| |`LPE_FLW_SCALE`|1.0||
@@ -60,8 +60,8 @@
Estimator это подсистема, которая вычисляет текущее состояние (state) коптера, используя показания с датчиков. В состояние коптера входит: Estimator это подсистема, которая вычисляет текущее состояние (state) коптера, используя показания с датчиков. В состояние коптера входит:
* угловая скорость коптера roll_rate, pitch_rate, yaw_rate; * угловая скорость коптера pitch_rate, roll_rate, yaw_rate;
* ориентация коптера (в локальной системе координат) roll (крен), pitch (тангаж), yaw (рысканье) (одно из представлений); * ориентация коптера (в локальной системе координат) pitch (тангаж), roll (крен), yaw (рысканье) (одно из представлений);
* позиция коптера (в локальной системе координат) x, y, z; * позиция коптера (в локальной системе координат) x, y, z;
* скорость коптера (в локальной системе координат)  vx, vy, vz; * скорость коптера (в локальной системе координат)  vx, vy, vz;
* глобальные координаты коптера  latitude, longitude, altitude; * глобальные координаты коптера  latitude, longitude, altitude;

View File

@@ -11,7 +11,7 @@
> **Hint** Вы можете можете использовать готовый [образ виртуальной машины](simulation_vm.md) с инструментами для Клевера. > **Hint** Вы можете можете использовать готовый [образ виртуальной машины](simulation_vm.md) с инструментами для Клевера.
На него необходимо установить пакет `ros-noetic-desktop-full` или `ros-noetic-desktop`, используя [документацию по установке](http://wiki.ros.org/noetic/Installation/Ubuntu). На него необходимо установить пакет `ros-melodic-desktop-full` или `ros-melodic-desktop`, используя [документацию по установке](http://wiki.ros.org/melodic/Installation/Ubuntu).
Запуск rviz Запуск rviz
--- ---

View File

@@ -51,11 +51,11 @@ land = rospy.ServiceProxy('land', Trigger)
* `lat, lon` широта, долгота *(градусы)*, необходимо наличие [GPS](gps.md); * `lat, lon` широта, долгота *(градусы)*, необходимо наличие [GPS](gps.md);
* `alt` высота в глобальной системе координат (стандарт [WGS-84](https://ru.wikipedia.org/wiki/WGS_84), не <abbr title="Above Mean Sea Level, выше среднего уровня моря">AMSL</abbr>!), необходимо наличие [GPS](gps.md); * `alt` высота в глобальной системе координат (стандарт [WGS-84](https://ru.wikipedia.org/wiki/WGS_84), не <abbr title="Above Mean Sea Level, выше среднего уровня моря">AMSL</abbr>!), необходимо наличие [GPS](gps.md);
* `vx, vy, vz` скорость коптера *(м/с)*; * `vx, vy, vz` скорость коптера *(м/с)*;
* `roll` угол по крену *(радианы)*;
* `pitch`  угол по тангажу *(радианы)*; * `pitch`  угол по тангажу *(радианы)*;
* `roll` угол по крену *(радианы)*;
* `yaw` – угол по рысканью *(радианы)*; * `yaw` – угол по рысканью *(радианы)*;
* `roll_rate` – угловая скорость по крену *(рад/с)*;
* `pitch_rate` – угловая скорость по тангажу *(рад/с)*; * `pitch_rate` – угловая скорость по тангажу *(рад/с)*;
* `roll_rate` – угловая скорость по крену *(рад/с)*;
* `yaw_rate` – угловая скорость по рысканью *(рад/с)*; * `yaw_rate` – угловая скорость по рысканью *(рад/с)*;
* `voltage` общее напряжение аккумулятора *(В)*; * `voltage` общее напряжение аккумулятора *(В)*;
* `cell_voltage` напряжение аккумулятора на ячейку *(В)*. * `cell_voltage` напряжение аккумулятора на ячейку *(В)*.
@@ -265,7 +265,7 @@ set_velocity(vx=1, vy=0.0, vz=0, frame_id='body')
Параметры: Параметры:
* `roll`, `pitch`, `yaw` – необходимый угол по тангажу, крену и рысканью *(радианы)*; * `pitch`, `roll`, `yaw` – необходимый угол по тангажу, крену и рысканью *(радианы)*;
* `thrust` – уровень газа от 0 (нет газа, пропеллеры остановлены) до 1 (полный газ); * `thrust` – уровень газа от 0 (нет газа, пропеллеры остановлены) до 1 (полный газ);
* `auto_arm` перевести коптер в `OFFBOARD` и заармить автоматически (**коптер взлетит**); * `auto_arm` перевести коптер в `OFFBOARD` и заармить автоматически (**коптер взлетит**);
* `frame_id`  [система координат](frames.md), в которой задан `yaw` (по умолчанию: `map`). * `frame_id`  [система координат](frames.md), в которой задан `yaw` (по умолчанию: `map`).
@@ -276,7 +276,7 @@ set_velocity(vx=1, vy=0.0, vz=0, frame_id='body')
Параметры: Параметры:
* `roll_rate`, `pitch_rate`, `yaw_rate` – угловая скорость по тангажу, крену и рыканью *(рад/с)*; * `pitch_rate`, `roll_rate`, `yaw_rate` – угловая скорость по тангажу, крену и рыканью *(рад/с)*;
* `thrust` уровень газа от 0 (нет газа, пропеллеры остановлены) до 1 (полный газ). * `thrust` уровень газа от 0 (нет газа, пропеллеры остановлены) до 1 (полный газ).
* `auto_arm` перевести коптер в `OFFBOARD` и заармить автоматически (**коптер взлетит**); * `auto_arm` перевести коптер в `OFFBOARD` и заармить автоматически (**коптер взлетит**);
@@ -305,16 +305,6 @@ rosservice call /land "{}"
> **Caution** В более новых версиях PX4 коптер выйдет из режима LAND в ручной режим, если сильно перемещать стики. > **Caution** В более новых версиях PX4 коптер выйдет из режима LAND в ручной режим, если сильно перемещать стики.
### release
В случае необходимости приостановки отправки setpoint-сообщений, используйте сервис `simple_offboard/release`:
```python
release = rospy.ServiceProxy('simple_offboard/release', Trigger)
release()
```
## Дополнительные материалы ## Дополнительные материалы
* [Полеты в поле ArUco-маркеров](aruco.md). * [Полеты в поле ArUco-маркеров](aruco.md).

View File

@@ -2,7 +2,7 @@
Настройка среды для симуляции с нуля требует некоторых усилий, однако это приведет к улучшению производительности и к уменьшению вероятности появления проблем с драйверами. Настройка среды для симуляции с нуля требует некоторых усилий, однако это приведет к улучшению производительности и к уменьшению вероятности появления проблем с драйверами.
<!-- > **Hint** Смотрите актуальный набор команд установки необходимого ПО для запуска симулятора Клевера в скрипте сборки виртуальной машины с симулятором: [`install_software.sh`](https://github.com/CopterExpress/clover_vm/blob/master/scripts/install_software.sh). --> > **Hint** Смотрите актуальный набор команд установки необходимого ПО для запуска симулятора Клевера в скрипте сборки виртуальной машины с симулятором: [`install_software.sh`](https://github.com/CopterExpress/clover_vm/blob/master/scripts/install_software.sh).
Требования для сборки: **Ubuntu 20.04**. Требования для сборки: **Ubuntu 20.04**.
@@ -66,7 +66,7 @@ sudo /usr/bin/python3 -m pip install -r ~/catkin_ws/src/clover/clover/requiremen
Склонируйте исходный код PX4 и создайте необходимые симлинки: Склонируйте исходный код PX4 и создайте необходимые симлинки:
```bash ```bash
git clone --recursive --depth 1 --branch v1.12.3 https://github.com/PX4/PX4-Autopilot.git ~/PX4-Autopilot git clone --recursive --depth 1 --branch v1.12.0 https://github.com/PX4/PX4-Autopilot.git ~/PX4-Autopilot
ln -s ~/PX4-Autopilot ~/catkin_ws/src/ ln -s ~/PX4-Autopilot ~/catkin_ws/src/
ln -s ~/PX4-Autopilot/Tools/sitl_gazebo ~/catkin_ws/src/ ln -s ~/PX4-Autopilot/Tools/sitl_gazebo ~/catkin_ws/src/
ln -s ~/PX4-Autopilot/mavlink ~/catkin_ws/src/ ln -s ~/PX4-Autopilot/mavlink ~/catkin_ws/src/
@@ -132,12 +132,6 @@ roslaunch clover_simulation simulator.launch
## Дополнительные шаги ## Дополнительные шаги
Для того, чтобы возможно было запускать среду симуляции Gazebo отдельно (команда `gazebo`), добавьте в `.bashrc` вызов соответствующего скрипта инициализации:
```bash
echo "source /usr/share/gazebo/setup.sh" >> ~/.bashrc
```
Опционально вы можете установить systemd-сервис для roscore для того, чтобы roscore был постоянно запущен в фоне: Опционально вы можете установить systemd-сервис для roscore для того, чтобы roscore был постоянно запущен в фоне:
```bash ```bash
@@ -147,8 +141,6 @@ sudo systemctl enable roscore
sudo systemctl start roscore sudo systemctl start roscore
``` ```
### Конфигурация веб-инструментов
Установите любой веб-сервер, чтобы раздавать веб-инструменты Клевера (директория `~/.ros/www`), например, Monkey: Установите любой веб-сервер, чтобы раздавать веб-инструменты Клевера (директория `~/.ros/www`), например, Monkey:
```bash ```bash
@@ -160,11 +152,3 @@ sudo cp ~/catkin_ws/src/clover/builder/assets/monkey.service /etc/systemd/system
sudo systemctl enable monkey sudo systemctl enable monkey
sudo systemctl start monkey sudo systemctl start monkey
``` ```
Создайте директорию `~/.ros/www` следующей командой:
```bash
rosrun clover www
```
При обновлении набора пакетов, содержащих веб-часть (через каталог `www`), также необходимо выполнение данной команды.

View File

@@ -99,13 +99,3 @@ PX4_SIM_SPEED_FACTOR=0.42 roslaunch clover_simulation simulator.launch
Выделение нескольких процессорных ядер для виртуальной машины может значительно повысить производительность симуляции. В наших испытаниях виртуальная машина, для которой было выделено одно ядро, не позволяла работать в симуляторе: окно Gazebo не реагировало на пользовательский ввод, сообщения ROS терялись. После выделения четырёх ядер для этой же виртуальной машины симуляция стала работать со скоростью 0.25 от реального времени. Выделение нескольких процессорных ядер для виртуальной машины может значительно повысить производительность симуляции. В наших испытаниях виртуальная машина, для которой было выделено одно ядро, не позволяла работать в симуляторе: окно Gazebo не реагировало на пользовательский ввод, сообщения ROS терялись. После выделения четырёх ядер для этой же виртуальной машины симуляция стала работать со скоростью 0.25 от реального времени.
При этом не следует пытаться выделить для виртуальной машины больше ресурсов, чем доступно на основной системе. При этом не следует пытаться выделить для виртуальной машины больше ресурсов, чем доступно на основной системе.
### Изменение карты ArUco-меток в симуляторе
Для того, чтобы изменить карту ArUco-меток в симуляторе, можно использовать следующую команду:
```bash
rosrun clover_simulation aruco_gen --single-model --source-world=$(catkin_find clover_simulation resources/worlds/clover.world) $(catkin_find aruco_pose map/map.txt) > $(catkin_find clover_simulation resources/worlds/clover_aruco.world)
```
В данном примере `map.txt` имя карты меток.

View File

@@ -1,10 +1,10 @@
# Установка виртуальной машины # Установка виртуальной машины
Для работы с платформой Клевер рекомендуется иметь [установленное окружение ROS](ros.md) на своём компьютере. К сожалению, [установка ROS и симулятора](simulation_native.md) сопряжена с рядом трудностей: требуется использовать операционную систему Ubuntu 20.04, процесс установки длительный и требует выполнения большого количества команд в терминале. Для работы с платформой Клевер рекомендуется иметь [установленное окружение ROS](ros.md) на своём компьютере. К сожалению, [установка ROS](ros-install.md) сопряжена с рядом трудностей: требуется использовать операционную систему Ubuntu 18.04, процесс установки длительный и требует выполнения большого количества команд в терминале.
Для облегчения процесса настройки окружения мы предлагаем использовать виртуальную машину со всем необходимым для работы с платформой Клевер. В состав виртуальной машины входят: Для облегчения процесса настройки окружения мы предлагаем использовать виртуальную машину со всем необходимым для работы с платформой Клевер. В состав виртуальной машины входят:
* операционная система Ubuntu 20.04 с легковесной графической оболочкой XFCE; * операционная система Ubuntu 18.04 с легковесной графической оболочкой XFCE;
* предустановленные пакеты ROS для работы с Клевером; * предустановленные пакеты ROS для работы с Клевером;
* QGroundControl; * QGroundControl;
* предварительно настроенный симулятор Gazebo; * предварительно настроенный симулятор Gazebo;
@@ -18,6 +18,8 @@
Скачать текущую версию виртуальной машины можно [в релизах репозитория виртуальной машины](https://github.com/CopterExpress/clover_vm/releases/latest). Скачать текущую версию виртуальной машины можно [в релизах репозитория виртуальной машины](https://github.com/CopterExpress/clover_vm/releases/latest).
> **Warning** Виртуальную машину следует использовать только в тех случаях, когда по каким-то причинам использование Ubuntu 18.04 напрямую невозможно. Производительность всех программ, особенно тех, которые используют 3D-графику - jMAVSim, Gazebo, rviz - будет существенно ниже; кроме того, в ряде случаев будут возникать графические ошибки, приводящие к частичной или полной неработоспособности указанных программ.
## Установка виртуальной машины ## Установка виртуальной машины
Для запуска виртуальной машины разработчика требуется использовать одну из совместимых сред виртуализации: [VirtualBox](https://www.virtualbox.org/wiki/Downloads), [VMware Player](https://www.vmware.com/products/workstation-player.html), [VMware Workstation](https://www.vmware.com/products/workstation-pro.html). Для запуска виртуальной машины разработчика требуется использовать одну из совместимых сред виртуализации: [VirtualBox](https://www.virtualbox.org/wiki/Downloads), [VMware Player](https://www.vmware.com/products/workstation-player.html), [VMware Workstation](https://www.vmware.com/products/workstation-pro.html).

View File

@@ -154,7 +154,7 @@ new_pose = tf_buffer.transform(pose, frame_id, transform_timeout)
PI_2 = math.pi / 2 PI_2 = math.pi / 2
telem = get_telemetry() telem = get_telemetry()
flipped = abs(telem.roll) > PI_2 or abs(telem.pitch) > PI_2 flipped = abs(telem.pitch) > PI_2 or abs(telem.roll) > PI_2
``` ```
### # {#angle-hor} ### # {#angle-hor}
@@ -165,7 +165,7 @@ flipped = abs(telem.roll) > PI_2 or abs(telem.pitch) > PI_2
PI_2 = math.pi / 2 PI_2 = math.pi / 2
telem = get_telemetry() telem = get_telemetry()
flipped = not -PI_2 <= telem.roll <= PI_2 or not -PI_2 <= telem.pitch <= PI_2 flipped = not -PI_2 <= telem.pitch <= PI_2 or not -PI_2 <= telem.roll <= PI_2
angle_to_horizon = math.atan(math.hypot(math.tan(telem.pitch), math.tan(telem.roll))) angle_to_horizon = math.atan(math.hypot(math.tan(telem.pitch), math.tan(telem.roll)))
if flipped: if flipped:
angle_to_horizon = math.pi - angle_to_horizon angle_to_horizon = math.pi - angle_to_horizon
@@ -217,9 +217,9 @@ def pose_update(pose):
# Обработка новых данных о позиции коптера # Обработка новых данных о позиции коптера
pass pass
rospy.Subscriber('mavros/local_position/pose', PoseStamped, pose_update) rospy.Subscriber('/mavros/local_position/pose', PoseStamped, pose_update)
rospy.Subscriber('mavros/local_position/velocity', TwistStamped, velocity_update) rospy.Subscriber('/mavros/local_position/velocity', TwistStamped, velocity_update)
rospy.Subscriber('mavros/battery', BatteryState, battery_update) rospy.Subscriber('/mavros/battery', BatteryState, battery_update)
rospy.Subscriber('mavros/rc/in', RCIn, rc_callback) rospy.Subscriber('mavros/rc/in', RCIn, rc_callback)
rospy.spin() rospy.spin()
@@ -251,30 +251,6 @@ ros_msg = mavlink.convert_to_rosmsg(msg)
mavlink_pub.publish(ros_msg) mavlink_pub.publish(ros_msg)
``` ```
<!-- markdownlint-disable MD044 -->
### # {#mavlink-receive}
<!-- markdownlint-enable MD044 -->
Подписка на все MAVLink-сообщения от полетного контроллера и их декодирование:
```python
from mavros_msgs.msg import Mavlink
from mavros import mavlink
from pymavlink import mavutil
link = mavutil.mavlink.MAVLink('', 255, 1)
def mavlink_cb(msg):
mav_msg = link.decode(mavlink.convert_to_bytes(msg))
print('msgid =', msg.msgid, mav_msg) # print message id and parsed message
mavlink_sub = rospy.Subscriber('mavlink/from', Mavlink, mavlink_cb)
rospy.spin()
```
### # {#rc-sub} ### # {#rc-sub}
Реакция на переключение режима на пульте радиоуправления (может быть использовано для запуска автономного полета, см. [пример](https://gist.github.com/okalachev/b709f04522d2f9af97e835baedeb806b)): Реакция на переключение режима на пульте радиоуправления (может быть использовано для запуска автономного полета, см. [пример](https://gist.github.com/okalachev/b709f04522d2f9af97e835baedeb806b)):
@@ -335,7 +311,7 @@ def flip():
while True: while True:
telem = get_telemetry() telem = get_telemetry()
flipped = abs(telem.roll) > PI_2 or abs(telem.pitch) > PI_2 flipped = abs(telem.pitch) > PI_2 or abs(telem.roll) > PI_2
if flipped: if flipped:
break break
@@ -360,7 +336,7 @@ from pymavlink import mavutil
from mavros_msgs.srv import CommandLong from mavros_msgs.srv import CommandLong
from mavros_msgs.msg import State from mavros_msgs.msg import State
send_command = rospy.ServiceProxy('mavros/cmd/command', CommandLong) send_command = rospy.ServiceProxy('/mavros/cmd/command', CommandLong)
def calibrate_gyro(): def calibrate_gyro():
rospy.loginfo('Calibrate gyro') rospy.loginfo('Calibrate gyro')
@@ -425,26 +401,6 @@ rospy.sleep(5)
flow_client.update_configuration({'enabled': True}) flow_client.update_configuration({'enabled': True})
``` ```
<!-- markdownlint-disable MD044 -->
### # {#aruco-map-dynamic}
> **Info** Для [образа](image.md) версии > 0.23.
Динамически изменить используемый файл с [картой ArUco-маркеров](aruco_map.md):
<!-- markdownlint-enable MD044 -->
```python
import rospy
import dynamic_reconfigure.client
rospy.init_node('flight')
map_client = dynamic_reconfigure.client.Client('aruco_map')
map_client.update_configuration({'map': '/home/pi/catkin_ws/src/clover/aruco_pose/map/office.txt'})
```
### # {#wait-global-position} ### # {#wait-global-position}
Ожидать появления глобальной позиции (окончания инициализации [GPS-приемника](gps.md)): Ожидать появления глобальной позиции (окончания инициализации [GPS-приемника](gps.md)):
@@ -491,11 +447,3 @@ param_set(param_id='COM_FLTMODE1', value=ParamValue(integer=8))
# Изменить параметр типа FLOAT: # Изменить параметр типа FLOAT:
param_set(param_id='MPC_Z_P', value=ParamValue(real=1.5)) param_set(param_id='MPC_Z_P', value=ParamValue(real=1.5))
``` ```
### # {#is-simulation}
Проверить, что код запущен в [симуляции Gazebo](simulation.md):
```python
is_simulation = rospy.get_param('/use_sim_time', False)
```

View File

@@ -51,10 +51,10 @@ sed -i "/direction_y/s/default=\".*\"/default=\"\"/" /home/pi/catkin_ws/src/clov
После того, как вы заполните карту, необходимо применить ее — для этого отредактируйте файл `aruco.launch`, расположенный в `~/catkin_ws/src/clover/clover/launch/`. Измените в нем строку `<param name="map" value="$(find aruco_pose)/map/map_name.txt"/>`, где `map_name.txt` название вашего файла с картой. После того, как вы заполните карту, необходимо применить ее — для этого отредактируйте файл `aruco.launch`, расположенный в `~/catkin_ws/src/clover/clover/launch/`. Измените в нем строку `<param name="map" value="$(find aruco_pose)/map/map_name.txt"/>`, где `map_name.txt` название вашего файла с картой.
При использовании маркеров, не привязанных к горизонтальным плоскостям (пол, потолок), необходимо также сделать пустым значение аргумента `placement` в том же файле: При использовании маркеров, не привязанных к горизонтальным плоскостям(пол, потолок), необходимо отключить параметр `known_tilt` как в модуле `aruco_detect`, так и в модуле `aruco_map` в том же файле. Для того, чтобы сделать это автоматически, введите:
```xml ```bash
<arg name="placement" default=""/> sed -i "/known_tilt/s/value=\".*\"/value=\"\"/" /home/pi/catkin_ws/src/clover/clover/launch/aruco.launch
``` ```
После всех настроек вызовите `sudo systemctl restart clover` для перезагрузки сервиса `clover`. После всех настроек вызовите `sudo systemctl restart clover` для перезагрузки сервиса `clover`.

View File

@@ -20,7 +20,7 @@ http://192.168.11.1:8080/stream_viewer?topic=/main_camera/image_raw&type=mjpeg&q
## Просмотр через rqt_image_view ## Просмотр через rqt_image_view
Для просмотра изображений через инструменты rqt необходим компьютер с установленной Ubuntu 20.04 и [ROS Noetic](http://wiki.ros.org/noetic/Installation/Ubuntu). Для просмотра изображений через инструменты rqt необходим компьютер с установленной Ubuntu 18.04 и [ROS Melodic](http://wiki.ros.org/melodic/Installation/Ubuntu).
[Подключитесь к Wi-Fi сети Клевера](wifi.md) и запустите `rqt_image_view` с указанием его IP-адреса: [Подключитесь к Wi-Fi сети Клевера](wifi.md) и запустите `rqt_image_view` с указанием его IP-адреса:

Some files were not shown because too many files have changed in this diff Show More