Skip to content

Commit

Permalink
Merge branch 'master' into bookworm
Browse files Browse the repository at this point in the history
  • Loading branch information
okalachev committed Feb 6, 2024
2 parents 225d8e8 + e31b69a commit 1154969
Show file tree
Hide file tree
Showing 126 changed files with 4,009 additions and 748 deletions.
1 change: 1 addition & 0 deletions .github/workflows/build-image.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@ on:
branches: [ master ]
release:
types: [ created ]
workflow_dispatch:

jobs:
build:
Expand Down
1 change: 1 addition & 0 deletions .github/workflows/build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@ on:
branches: [ '*' ]
pull_request:
branches: [ master ]
workflow_dispatch:

jobs:
# melodic:
Expand Down
11 changes: 7 additions & 4 deletions .github/workflows/docs.yml
Original file line number Diff line number Diff line change
Expand Up @@ -5,16 +5,13 @@ on:
branches: [ '*' ]
pull_request:
branches: [ '*' ]
workflow_dispatch:

permissions:
contents: read
pages: write
id-token: write

concurrency:
group: "pages"
cancel-in-progress: true

defaults:
run:
shell: bash
Expand Down Expand Up @@ -75,12 +72,18 @@ jobs:

deploy-docs:
if: ${{ github.event_name == 'push' && github.ref == 'refs/heads/master' }}
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
env:
FREEZE_DOCS: ${{ secrets.FREEZE_DOCS }}
if: ${{ !env.FREEZE_DOCS }}
id: deployment
uses: actions/deploy-pages@v1
1 change: 1 addition & 0 deletions .github/workflows/editorconfig.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@ on:
branches: [ '*' ]
pull_request:
branches: [ master ]
workflow_dispatch:

jobs:
editorconfig:
Expand Down
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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).

![GitHub Workflow Status](https://img.shields.io/github/workflow/status/CopterExpress/clover/CI)
![GitHub Workflow Status](https://img.shields.io/github/actions/workflow/status/CopterExpress/clover/build-image.yaml?branch=master)
![GitHub all releases](https://img.shields.io/github/downloads/CopterExpress/clover/total)

Image features:
Expand Down
6 changes: 4 additions & 2 deletions aruco_pose/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,8 @@ 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_`)
* `~length` (*double*) – markers' sides length
* `~length_override` (*map*) – lengths of markers with specified ids
* `~known_tilt` (*string*) – known tilt (pitch and roll) of all the markers as a frame
* `~known_vertical` (*string*) – known vertical (Z axis) of all the markers as a frame
* `~flip_vertical` – flip vertical vector

### Topics

Expand Down Expand Up @@ -71,7 +72,8 @@ It's recommended to run it within the same nodelet manager with the camera nodel

* `~map` – path to text file with markers list
* `~frame_id` – published frame id (default: `aruco_map`)
* `~known_tilt` – known tilt (pitch and roll) of markers map as a frame
* `~known_vertical` – known vertical (Z axis) of markers map as a frame
* `~flip_vertical` – flip vertical vector
* `~image_width` – debug image width (default: 2000)
* `~image_height` – debug image height (default: 2000)
* `~image_margin` – debug image margin (default: 200)
Expand Down
5 changes: 4 additions & 1 deletion aruco_pose/cfg/Detector.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,10 @@ PACKAGE = "aruco_pose"
from dynamic_reconfigure.parameter_generator_catkin import *
import cv2.aruco

p = cv2.aruco.DetectorParameters_create()
try:
p = cv2.aruco.DetectorParameters_create()
except AttributeError:
p = cv2.aruco.DetectorParameters()

gen = ParameterGenerator()

Expand Down
6 changes: 4 additions & 2 deletions aruco_pose/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<package format="3">
<name>aruco_pose</name>
<version>0.23.0</version>
<version>0.24.0</version>
<description>Positioning with ArUco markers</description>

<maintainer email="[email protected]">Oleg Kalachev</maintainer>
Expand All @@ -28,6 +28,8 @@
<depend>sensor_msgs</depend>
<depend>rostest</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>ros_pytest</test_depend>
Expand Down
39 changes: 25 additions & 14 deletions aruco_pose/src/aruco_detect.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@
#include <aruco_pose/DetectorConfig.h>
#include <aruco_pose/SetMarkers.h>

#include "draw.h"
#include "utils.h"
#include <memory>
#include <functional>
Expand All @@ -71,11 +72,12 @@ class ArucoDetect : public nodelet::Nodelet {
ros::Publisher markers_pub_, vis_markers_pub_;
ros::Subscriber map_markers_sub_;
ros::ServiceServer set_markers_srv_;
bool estimate_poses_, send_tf_, auto_flip_;
bool estimate_poses_, send_tf_, flip_vertical_, auto_flip_, use_map_markers_;
bool waiting_for_map_;
double length_;
ros::Duration transform_timeout_;
std::unordered_map<int, double> length_override_;
std::string frame_id_prefix_, known_tilt_;
std::string frame_id_prefix_, known_vertical_;
Mat camera_matrix_, dist_coeffs_;
aruco_pose::MarkerArray array_;
std::unordered_set<int> map_markers_ids_;
Expand All @@ -95,14 +97,17 @@ class ArucoDetect : public nodelet::Nodelet {
dictionary = nh_priv_.param("dictionary", 2);
estimate_poses_ = nh_priv_.param("estimate_poses", 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_)) {
NODELET_FATAL("can't estimate marker's poses as ~length parameter is not defined");
ros::shutdown();
}
readLengthOverride(nh_priv_);
transform_timeout_ = ros::Duration(nh_priv_.param("transform_timeout", 0.02));

known_tilt_ = nh_priv_.param<std::string>("known_tilt", "");
known_vertical_ = nh_priv_.param("known_vertical", nh_priv_.param("known_tilt", std::string(""))); // known_tilt is an old name
flip_vertical_ = nh_priv_.param<bool>("flip_vertical", false);
auto_flip_ = nh_priv_.param("auto_flip", false);

frame_id_prefix_ = nh_priv_.param<std::string>("frame_id_prefix", "aruco_");
Expand Down Expand Up @@ -133,14 +138,15 @@ class ArucoDetect : public nodelet::Nodelet {
void imageCallback(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr &cinfo)
{
if (!enabled_) return;
if (waiting_for_map_) return;

Mat image = cv_bridge::toCvShare(msg, "bgr8")->image;
Mat image = cv_bridge::toCvShare(msg)->image;

vector<int> ids;
vector<vector<cv::Point2f>> corners, rejected;
vector<cv::Vec3d> rvecs, tvecs;
vector<cv::Point3f> obj_points;
geometry_msgs::TransformStamped snap_to;
geometry_msgs::TransformStamped vertical;

// Detect markers
cv::aruco::detectMarkers(image, dictionary_, corners, ids, parameters_, rejected);
Expand Down Expand Up @@ -175,12 +181,12 @@ class ArucoDetect : public nodelet::Nodelet {
}
}

if (!known_tilt_.empty()) {
if (!known_vertical_.empty()) {
try {
snap_to = tf_buffer_->lookupTransform(msg->header.frame_id, known_tilt_,
msg->header.stamp, transform_timeout_);
vertical = tf_buffer_->lookupTransform(msg->header.frame_id, known_vertical_,
msg->header.stamp, transform_timeout_);
} catch (const tf2::TransformException& e) {
NODELET_WARN_THROTTLE(5, "can't snap: %s", e.what());
NODELET_WARN_THROTTLE(5, "can't retrieve known vertical: %s", e.what());
}
}
}
Expand All @@ -201,9 +207,9 @@ class ArucoDetect : public nodelet::Nodelet {
if (estimate_poses_) {
fillPose(marker.pose, rvecs[i], tvecs[i]);

// snap orientation (if enabled and snap frame available)
if (!known_tilt_.empty() && !snap_to.header.frame_id.empty()) {
snapOrientation(marker.pose.orientation, snap_to.transform.rotation, auto_flip_);
// apply known vertical (if enabled and vertical frame available)
if (!known_vertical_.empty() && !vertical.header.frame_id.empty()) {
applyVertical(marker.pose.orientation, vertical.transform.rotation, false, auto_flip_);
}

if (send_tf_) {
Expand Down Expand Up @@ -259,8 +265,7 @@ class ArucoDetect : public nodelet::Nodelet {
cv::aruco::drawDetectedMarkers(debug, corners, ids); // draw markers
if (estimate_poses_)
for (unsigned int i = 0; i < ids.size(); i++)
cv::aruco::drawAxis(debug, camera_matrix_, dist_coeffs_,
rvecs[i], tvecs[i], getMarkerLength(ids[i]));
_drawAxis(debug, camera_matrix_, dist_coeffs_, rvecs[i], tvecs[i], getMarkerLength(ids[i]));

cv_bridge::CvImage out_msg;
out_msg.header.frame_id = msg->header.frame_id;
Expand Down Expand Up @@ -395,7 +400,13 @@ class ArucoDetect : public nodelet::Nodelet {
map_markers_ids_.clear();
for (auto const& marker : msg.markers) {
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)
Expand Down
36 changes: 26 additions & 10 deletions aruco_pose/src/aruco_map.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,9 +81,9 @@ class ArucoMap : public nodelet::Nodelet {
bool enabled_ = true;
std::string type_;
visualization_msgs::MarkerArray vis_array_;
std::string known_tilt_, map_, markers_frame_, markers_parent_frame_;
std::string known_vertical_, map_, markers_frame_, markers_parent_frame_;
int image_width_, image_height_, image_margin_;
bool auto_flip_, image_axis_;
bool flip_vertical_, auto_flip_, image_axis_, put_markers_count_to_covariance_;

public:
virtual void onInit()
Expand All @@ -104,12 +104,14 @@ class ArucoMap : public nodelet::Nodelet {

type_ = nh_priv_.param<std::string>("type", "map");
transform_.child_frame_id = nh_priv_.param<std::string>("frame_id", "aruco_map");
known_tilt_ = nh_priv_.param<std::string>("known_tilt", "");
known_vertical_ = nh_priv_.param("known_vertical", nh_priv_.param("known_tilt", std::string(""))); // known_tilt is an old name
flip_vertical_ = nh_priv_.param<bool>("flip_vertical", false);
auto_flip_ = nh_priv_.param("auto_flip", false);
image_width_ = nh_priv_.param("image_width" , 2000);
image_height_ = nh_priv_.param("image_height", 2000);
image_margin_ = nh_priv_.param("image_margin", 200);
image_axis_ = nh_priv_.param("image_axis", true);
put_markers_count_to_covariance_ = nh_priv_.param("put_markers_count_to_covariance", false);
markers_parent_frame_ = nh_priv_.param<std::string>("markers/frame_id", transform_.child_frame_id);
markers_frame_ = nh_priv_.param<std::string>("markers/child_frame_id_prefix", "");

Expand Down Expand Up @@ -177,7 +179,21 @@ class ArucoMap : public nodelet::Nodelet {
corners.push_back(marker_corners);
}

if (known_tilt_.empty()) {
if (put_markers_count_to_covariance_) {
// HACK: pass markers count using covariance field
int valid_markers = 0;
for (auto const &marker : markers->markers) {
for (auto const &board_marker : board_->ids) {
if (board_marker == marker.id) {
valid_markers++;
break;
}
}
}
pose_.pose.covariance[0] = valid_markers;
}

if (known_vertical_.empty()) {
// simple estimation
valid = cv::aruco::estimatePoseBoard(corners, ids, board_, camera_matrix_, dist_coeffs_,
rvec, tvec, false);
Expand All @@ -191,7 +207,7 @@ class ArucoMap : public nodelet::Nodelet {

} else {
Mat obj_points, img_points;
// estimation with "snapping"
// estimation with known vertical
cv::aruco::getBoardObjectAndImagePoints(board_, corners, ids, obj_points, img_points);
if (obj_points.empty()) goto publish_debug;

Expand All @@ -203,11 +219,11 @@ class ArucoMap : public nodelet::Nodelet {

fillTransform(transform_.transform, rvec, tvec);
try {
geometry_msgs::TransformStamped snap_to = tf_buffer_.lookupTransform(markers->header.frame_id,
known_tilt_, markers->header.stamp, ros::Duration(0.02));
snapOrientation(transform_.transform.rotation, snap_to.transform.rotation, auto_flip_);
geometry_msgs::TransformStamped vertical = tf_buffer_.lookupTransform(markers->header.frame_id,
known_vertical_, markers->header.stamp, ros::Duration(0.02));
applyVertical(transform_.transform.rotation, vertical.transform.rotation, flip_vertical_, auto_flip_);
} catch (const tf2::TransformException& e) {
NODELET_WARN_THROTTLE(1, "can't snap: %s", e.what());
NODELET_WARN_THROTTLE(1, "can't retrieve known vertical: %s", e.what());
}

geometry_msgs::TransformStamped shift;
Expand Down Expand Up @@ -503,7 +519,7 @@ class ArucoMap : public nodelet::Nodelet {
vis_marker.pose.position.x = x;
vis_marker.pose.position.y = y;
vis_marker.pose.position.z = z;
tf::quaternionTFToMsg(q, marker.pose.orientation);
tf::quaternionTFToMsg(q, vis_marker.pose.orientation);
vis_marker.frame_locked = true;
vis_array_.markers.push_back(vis_marker);

Expand Down
27 changes: 13 additions & 14 deletions aruco_pose/src/utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -106,26 +106,25 @@ inline bool isFlipped(tf::Quaternion& q)
return (abs(pitch) > M_PI / 2) || (abs(roll) > M_PI / 2);
}

/* Set roll and pitch from "from" to "to", keeping yaw */
inline void snapOrientation(geometry_msgs::Quaternion& to, const geometry_msgs::Quaternion& from, bool auto_flip = false)
/* Apply a vertical to an orientation */
inline void applyVertical(geometry_msgs::Quaternion& orientation, const geometry_msgs::Quaternion& vertical,
bool flip_vertical = false, bool auto_flip = false) // editorconfig-checker-disable-line
{
tf::Quaternion _from, _to;
tf::quaternionMsgToTF(from, _from);
tf::quaternionMsgToTF(to, _to);

if (auto_flip) {
if (!isFlipped(_from)) {
static const tf::Quaternion flip = tf::createQuaternionFromRPY(M_PI, 0, 0);
_from *= flip; // flip "from"
}
tf::Quaternion _vertical, _orientation;
tf::quaternionMsgToTF(vertical, _vertical);
tf::quaternionMsgToTF(orientation, _orientation);

if (flip_vertical || (auto_flip && !isFlipped(_orientation))) {
static const tf::Quaternion flip = tf::createQuaternionFromRPY(M_PI, 0, 0);
_vertical *= flip; // flip vertical
}

auto diff = tf::Matrix3x3(_to).transposeTimes(tf::Matrix3x3(_from));
auto diff = tf::Matrix3x3(_orientation).transposeTimes(tf::Matrix3x3(_vertical));
double _, yaw;
diff.getRPY(_, _, yaw);
auto q = tf::createQuaternionFromRPY(0, 0, -yaw);
_from = _from * q; // set yaw from "to" to "from"
tf::quaternionTFToMsg(_from, to); // set "from" to "to"
_vertical = _vertical * q; // set yaw from orientation to vertical
tf::quaternionTFToMsg(_vertical, orientation); // set vertical to orientation
}

inline void transformToPose(const geometry_msgs::Transform& transform, geometry_msgs::Pose& pose)
Expand Down
Loading

0 comments on commit 1154969

Please sign in to comment.