mirror of
https://github.com/CopterExpress/clover.git
synced 2026-06-01 15:39:32 +00:00
Compare commits
10 Commits
strict-war
...
install
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
0666bfdf33 | ||
|
|
7c57581c33 | ||
|
|
881daaa389 | ||
|
|
0dcf16de6b | ||
|
|
8abb40249c | ||
|
|
3ab73edb74 | ||
|
|
aeb1c8ac11 | ||
|
|
2d3df6a94e | ||
|
|
0249d01ca7 | ||
|
|
71100a9545 |
6
.github/workflows/build-image.yaml
vendored
6
.github/workflows/build-image.yaml
vendored
@@ -1,4 +1,4 @@
|
|||||||
name: RPi image
|
name: Build RPi image
|
||||||
|
|
||||||
on:
|
on:
|
||||||
push:
|
push:
|
||||||
@@ -9,7 +9,7 @@ on:
|
|||||||
types: [ created ]
|
types: [ created ]
|
||||||
|
|
||||||
jobs:
|
jobs:
|
||||||
build:
|
build-image:
|
||||||
runs-on: ubuntu-latest
|
runs-on: ubuntu-latest
|
||||||
steps:
|
steps:
|
||||||
- uses: actions/checkout@v2
|
- uses: actions/checkout@v2
|
||||||
@@ -18,7 +18,7 @@ jobs:
|
|||||||
docker run --privileged --rm -v /dev:/dev -v $(pwd):/builder/repo -e TRAVIS_TAG="${{ github.event.release.tag_name }}" sfalexrog/img-tool:qemu-update
|
docker run --privileged --rm -v /dev:/dev -v $(pwd):/builder/repo -e TRAVIS_TAG="${{ github.event.release.tag_name }}" sfalexrog/img-tool:qemu-update
|
||||||
- name: Compress image
|
- name: Compress image
|
||||||
run: |
|
run: |
|
||||||
cd images && sudo chmod -R 777 . && zip -9 $(echo clover_*).zip clover_* && ls -l . && unzip -l clover_*.zip
|
sudo chmod -R 777 images && zip -9 $(echo images/clover_*).zip images/clover_* && ls -l images
|
||||||
- name: Upload image
|
- name: Upload image
|
||||||
uses: softprops/action-gh-release@v1
|
uses: softprops/action-gh-release@v1
|
||||||
if: ${{ github.event_name == 'release' }}
|
if: ${{ github.event_name == 'release' }}
|
||||||
|
|||||||
16
.github/workflows/build.yml
vendored
16
.github/workflows/build.yml
vendored
@@ -7,14 +7,14 @@ on:
|
|||||||
branches: [ master ]
|
branches: [ master ]
|
||||||
|
|
||||||
jobs:
|
jobs:
|
||||||
# melodic:
|
build-melodic:
|
||||||
# runs-on: ubuntu-latest
|
runs-on: ubuntu-latest
|
||||||
# steps:
|
steps:
|
||||||
# - uses: actions/checkout@v2
|
- uses: actions/checkout@v2
|
||||||
# - name: Native Melodic build
|
- name: Native Melodic build
|
||||||
# run: |
|
run: |
|
||||||
# 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:
|
build-noetic:
|
||||||
runs-on: ubuntu-latest
|
runs-on: ubuntu-latest
|
||||||
steps:
|
steps:
|
||||||
- uses: actions/checkout@v2
|
- uses: actions/checkout@v2
|
||||||
|
|||||||
24
.github/workflows/docs.yml
vendored
24
.github/workflows/docs.yml
vendored
@@ -7,13 +7,9 @@ on:
|
|||||||
branches: [ master ]
|
branches: [ master ]
|
||||||
|
|
||||||
jobs:
|
jobs:
|
||||||
docs:
|
documentation:
|
||||||
runs-on: ubuntu-18.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
|
||||||
@@ -22,8 +18,9 @@ jobs:
|
|||||||
run: |
|
run: |
|
||||||
sudo sh -c "echo ttf-mscorefonts-installer msttcorefonts/accepted-mscorefonts-eula select true | debconf-set-selections"
|
sudo sh -c "echo ttf-mscorefonts-installer msttcorefonts/accepted-mscorefonts-eula select true | debconf-set-selections"
|
||||||
sudo apt-get update && sudo apt-get install -y calibre msttcorefonts
|
sudo apt-get update && sudo apt-get install -y calibre msttcorefonts
|
||||||
builder/assets/install_gitbook.sh
|
npm install gitbook-cli -g
|
||||||
npm install markdownlint-cli@0.28.1 -g # FIXME: https://github.com/DavidAnson/markdownlint/issues/435
|
gitbook fetch 3.2.3 && npm i npm@3.10.10 --prefix=~/.gitbook/versions/3.2.3/ # fixing https://travis-ci.org/github/CopterExpress/clover/jobs/766541125#L932
|
||||||
|
npm install markdownlint-cli -g
|
||||||
npm install svgexport -g
|
npm install svgexport -g
|
||||||
gitbook -V
|
gitbook -V
|
||||||
markdownlint -V
|
markdownlint -V
|
||||||
@@ -38,11 +35,7 @@ jobs:
|
|||||||
gitbook install
|
gitbook install
|
||||||
gitbook build
|
gitbook build
|
||||||
- name: Generate PDF
|
- name: Generate PDF
|
||||||
id: generate-pdf
|
if: ${{ github.event_name == 'push' && github.ref == 'refs/heads/master' }}
|
||||||
env:
|
|
||||||
GITBOOK_SKIP_PDF: ${{ secrets.GITBOOK_SKIP_PDF }}
|
|
||||||
continue-on-error: ${{ env.GITBOOK_SKIP_PDF != '' }}
|
|
||||||
if: ${{ github.event_name == 'push' }}
|
|
||||||
run: |
|
run: |
|
||||||
for i in 1 2 3 4; do gitbook pdf ./ _book/clover.pdf && break || sleep 1; done
|
for i in 1 2 3 4; do gitbook pdf ./ _book/clover.pdf && break || sleep 1; done
|
||||||
sudo apt-get -q install ghostscript
|
sudo apt-get -q install ghostscript
|
||||||
@@ -51,13 +44,6 @@ jobs:
|
|||||||
rm _book/clover_ru.pdf && mv _book/clover_ru_compressed.pdf _book/clover_ru.pdf
|
rm _book/clover_ru.pdf && mv _book/clover_ru_compressed.pdf _book/clover_ru.pdf
|
||||||
rm _book/clover_en.pdf && mv _book/clover_en_compressed.pdf _book/clover_en.pdf
|
rm _book/clover_en.pdf && mv _book/clover_en_compressed.pdf _book/clover_en.pdf
|
||||||
ls -lah _book/clover*.pdf
|
ls -lah _book/clover*.pdf
|
||||||
echo '::set-output name=GITBOOK_PDF_OK::1'
|
|
||||||
- name: Download older PDFs
|
|
||||||
if: ${{ !steps.generate-pdf.outputs.GITBOOK_PDF_OK }}
|
|
||||||
run: |
|
|
||||||
rm -f _book/clover*.pdf
|
|
||||||
wget --no-verbose https://clover.coex.tech/clover_ru.pdf -P _book/
|
|
||||||
wget --no-verbose https://clover.coex.tech/clover_en.pdf -P _book/
|
|
||||||
- name: Deploy
|
- name: Deploy
|
||||||
uses: JamesIves/github-pages-deploy-action@4.1.3
|
uses: JamesIves/github-pages-deploy-action@4.1.3
|
||||||
if: ${{ github.event_name == 'push' && github.ref == 'refs/heads/master' }}
|
if: ${{ github.event_name == 'push' && github.ref == 'refs/heads/master' }}
|
||||||
|
|||||||
4
.github/workflows/editorconfig.yaml
vendored
4
.github/workflows/editorconfig.yaml
vendored
@@ -1,4 +1,4 @@
|
|||||||
name: Editorconfig
|
name: Editorconfig lint
|
||||||
|
|
||||||
on:
|
on:
|
||||||
push:
|
push:
|
||||||
@@ -15,4 +15,4 @@ jobs:
|
|||||||
run: |
|
run: |
|
||||||
wget --no-verbose https://github.com/okalachev/editorconfig-checker/releases/download/1.2.1-disable-spaces-amount/ec-linux-amd64
|
wget --no-verbose https://github.com/okalachev/editorconfig-checker/releases/download/1.2.1-disable-spaces-amount/ec-linux-amd64
|
||||||
chmod +x ec-linux-amd64
|
chmod +x ec-linux-amd64
|
||||||
./ec-linux-amd64 -spaces-after-tabs -e "roslib.js|ros3d.js|eventemitter2.js|json-to-pretty-yaml.js|draw.cpp|BinUtils.swift|\.idea|apps/android/app|blockly/|clover_blocks/programs/|highlight/|python.js|Assets.xcassets|test_parser_pass.txt|test_node_failure.txt|aruco_pose/vendor|\.stl|\.dxf|\.dae|\.material"
|
./ec-linux-amd64 -spaces-after-tabs -e "roslib.js|ros3d.js|eventemitter2.js|draw.cpp|BinUtils.swift|\.idea|apps/android/app|blockly/|clover_blocks/programs/|highlight/|python.js|Assets.xcassets|test_parser_pass.txt|test_node_failure.txt|aruco_pose/vendor|\.stl|\.dxf|\.dae"
|
||||||
|
|||||||
1
.gitignore
vendored
1
.gitignore
vendored
@@ -6,4 +6,3 @@ _book/
|
|||||||
package-lock.json
|
package-lock.json
|
||||||
clover_blocks/programs/*.*
|
clover_blocks/programs/*.*
|
||||||
!clover_blocks/programs/examples/*
|
!clover_blocks/programs/examples/*
|
||||||
/.vscode/
|
|
||||||
|
|||||||
@@ -1,6 +1,6 @@
|
|||||||
# clover🍀: create autonomous drones easily
|
# clover🍀: create autonomous drones easily
|
||||||
|
|
||||||
<img src="docs/assets/clover42-main-margin.png" align="right" width="400px" alt="COEX Clover Drone">
|
<img src="docs/assets/clover42-main.png" align="right" width="400px" alt="COEX Clover Drone">
|
||||||
|
|
||||||
Clover is an open source [ROS](https://www.ros.org)-based framework, providing user-friendly tools to control [PX4](https://px4.io)-powered drones. Clover is available as a ROS package, but is shipped mainly as a preconfigured image for Raspberry Pi. Once you've installed Raspberry Pi on your drone and flashed the image to its microSD card, taking the drone up in the air is a matter of minutes.
|
Clover is an open source [ROS](https://www.ros.org)-based framework, providing user-friendly tools to control [PX4](https://px4.io)-powered drones. Clover is available as a ROS package, but is shipped mainly as a preconfigured image for Raspberry Pi. Once you've installed Raspberry Pi on your drone and flashed the image to its microSD card, taking the drone up in the air is a matter of minutes.
|
||||||
|
|
||||||
|
|||||||
@@ -1,4 +1,5 @@
|
|||||||
# iOS-приложение для управления Клевером
|
iOS-приложение для управления Клевером
|
||||||
|
--------------------------------------
|
||||||
|
|
||||||
Для установки зависимостей необходим [CocoaPods](https://cocoapods.org):
|
Для установки зависимостей необходим [CocoaPods](https://cocoapods.org):
|
||||||
|
|
||||||
|
|||||||
@@ -4,8 +4,6 @@ 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
|
||||||
@@ -85,10 +83,11 @@ add_message_files(
|
|||||||
)
|
)
|
||||||
|
|
||||||
## Generate services in the 'srv' folder
|
## Generate services in the 'srv' folder
|
||||||
add_service_files(
|
# add_service_files(
|
||||||
FILES
|
# FILES
|
||||||
SetMarkers.srv
|
# Service1.srv
|
||||||
)
|
# Service2.srv
|
||||||
|
# )
|
||||||
|
|
||||||
## Generate actions in the 'action' folder
|
## Generate actions in the 'action' folder
|
||||||
# add_action_files(
|
# add_action_files(
|
||||||
|
|||||||
@@ -51,7 +51,6 @@ It's recommended to run it within the same nodelet manager with the camera nodel
|
|||||||
|
|
||||||
* `image_raw` (*sensor_msgs/Image*) – camera image
|
* `image_raw` (*sensor_msgs/Image*) – camera image
|
||||||
* `camera_info` (*sensor_msgs/CameraInfo*) – camera calibration info
|
* `camera_info` (*sensor_msgs/CameraInfo*) – camera calibration info
|
||||||
* `map_markers` (*aruco_pose/MarkerArray*) – list of markers to disable TF transform publishing
|
|
||||||
|
|
||||||
#### Published
|
#### Published
|
||||||
|
|
||||||
@@ -71,7 +70,7 @@ 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_tilt` – known tilt (pitch and roll) of markers map as a frame
|
* `~known_tilt` – debug image width
|
||||||
* `~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)
|
||||||
@@ -98,7 +97,6 @@ See examples in [`map`](map/) directory.
|
|||||||
#### Published
|
#### Published
|
||||||
|
|
||||||
* `~pose` (*geometry_msgs/PoseWithCovarianceStamped*) – estimated map pose
|
* `~pose` (*geometry_msgs/PoseWithCovarianceStamped*) – estimated map pose
|
||||||
* `~map` (*aruco_pose/MarkerArray*) – list of markers in the loaded map
|
|
||||||
* `~image` (*sensor_msgs/Image*) – planarized map image
|
* `~image` (*sensor_msgs/Image*) – planarized map image
|
||||||
* `~visualization` (*visualization_msgs/MarkerArray*) – markers map visualization for rviz
|
* `~visualization` (*visualization_msgs/MarkerArray*) – markers map visualization for rviz
|
||||||
* `~debug` (*sensor_msgs/Image*) – debug image with detected markers and map axis
|
* `~debug` (*sensor_msgs/Image*) – debug image with detected markers and map axis
|
||||||
|
|||||||
@@ -10,8 +10,6 @@ gen = ParameterGenerator()
|
|||||||
|
|
||||||
gen.add("enabled", bool_t, 0, "if detection enabled", True)
|
gen.add("enabled", bool_t, 0, "if detection enabled", True)
|
||||||
|
|
||||||
gen.add("length", double_t, 0, "markers' side length", min=0, max=10)
|
|
||||||
|
|
||||||
gen.add("adaptiveThreshConstant", double_t, 0,
|
gen.add("adaptiveThreshConstant", double_t, 0,
|
||||||
"Constant for adaptive thresholding before finding contours",
|
"Constant for adaptive thresholding before finding contours",
|
||||||
p.adaptiveThreshConstant, 0, 100)
|
p.adaptiveThreshConstant, 0, 100)
|
||||||
|
|||||||
@@ -1,4 +1,3 @@
|
|||||||
# id length x y z rot_z rot_y rot_x
|
|
||||||
0 0.33 0.0 9.0 0 0 0 0
|
0 0.33 0.0 9.0 0 0 0 0
|
||||||
1 0.33 1.0 9.0 0 0 0 0
|
1 0.33 1.0 9.0 0 0 0 0
|
||||||
2 0.33 2.0 9.0 0 0 0 0
|
2 0.33 2.0 9.0 0 0 0 0
|
||||||
|
|||||||
@@ -1,4 +1,3 @@
|
|||||||
# id length x y z rot_z rot_y rot_x
|
|
||||||
107 0.33 0 0 0 0 0 0
|
107 0.33 0 0 0 0 0 0
|
||||||
106 0.33 0.77 0 0 0 0 0
|
106 0.33 0.77 0 0 0 0 0
|
||||||
105 0.33 0 0.77 0 0 0 0
|
105 0.33 0 0.77 0 0 0 0
|
||||||
|
|||||||
@@ -1,4 +1,3 @@
|
|||||||
# id length x y z rot_z rot_y rot_x
|
|
||||||
14 0.365 0.000 0.0 0 0 0 0
|
14 0.365 0.000 0.0 0 0 0 0
|
||||||
15 0.365 1.335 0.0 0 0 0 0
|
15 0.365 1.335 0.0 0 0 0 0
|
||||||
30 0.365 2.865 0.0 0 0 0 0
|
30 0.365 2.865 0.0 0 0 0 0
|
||||||
|
|||||||
@@ -1,7 +1,7 @@
|
|||||||
<?xml version="1.0"?>
|
<?xml version="1.0"?>
|
||||||
<package format="2">
|
<package format="2">
|
||||||
<name>aruco_pose</name>
|
<name>aruco_pose</name>
|
||||||
<version>0.23.0</version>
|
<version>0.21.1</version>
|
||||||
<description>Positioning with ArUco markers</description>
|
<description>Positioning with ArUco markers</description>
|
||||||
|
|
||||||
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>
|
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>
|
||||||
|
|||||||
@@ -48,7 +48,6 @@
|
|||||||
#include <aruco_pose/Marker.h>
|
#include <aruco_pose/Marker.h>
|
||||||
#include <aruco_pose/MarkerArray.h>
|
#include <aruco_pose/MarkerArray.h>
|
||||||
#include <aruco_pose/DetectorConfig.h>
|
#include <aruco_pose/DetectorConfig.h>
|
||||||
#include <aruco_pose/SetMarkers.h>
|
|
||||||
|
|
||||||
#include "utils.h"
|
#include "utils.h"
|
||||||
#include <memory>
|
#include <memory>
|
||||||
@@ -70,10 +69,8 @@ private:
|
|||||||
image_transport::CameraSubscriber img_sub_;
|
image_transport::CameraSubscriber img_sub_;
|
||||||
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_;
|
|
||||||
bool estimate_poses_, send_tf_, auto_flip_;
|
bool estimate_poses_, send_tf_, auto_flip_;
|
||||||
double length_;
|
double length_;
|
||||||
ros::Duration transform_timeout_;
|
|
||||||
std::unordered_map<int, double> length_override_;
|
std::unordered_map<int, double> length_override_;
|
||||||
std::string frame_id_prefix_, known_tilt_;
|
std::string frame_id_prefix_, known_tilt_;
|
||||||
Mat camera_matrix_, dist_coeffs_;
|
Mat camera_matrix_, dist_coeffs_;
|
||||||
@@ -100,7 +97,6 @@ public:
|
|||||||
ros::shutdown();
|
ros::shutdown();
|
||||||
}
|
}
|
||||||
readLengthOverride(nh_priv_);
|
readLengthOverride(nh_priv_);
|
||||||
transform_timeout_ = ros::Duration(nh_priv_.param("transform_timeout", 0.02));
|
|
||||||
|
|
||||||
known_tilt_ = nh_priv_.param<std::string>("known_tilt", "");
|
known_tilt_ = nh_priv_.param<std::string>("known_tilt", "");
|
||||||
auto_flip_ = nh_priv_.param("auto_flip", false);
|
auto_flip_ = nh_priv_.param("auto_flip", false);
|
||||||
@@ -118,8 +114,6 @@ public:
|
|||||||
dyn_srv_ = std::make_shared<dynamic_reconfigure::Server<aruco_pose::DetectorConfig>>(nh_priv_);
|
dyn_srv_ = std::make_shared<dynamic_reconfigure::Server<aruco_pose::DetectorConfig>>(nh_priv_);
|
||||||
dyn_srv_->setCallback(std::bind(&ArucoDetect::paramCallback, this, std::placeholders::_1, std::placeholders::_2));
|
dyn_srv_->setCallback(std::bind(&ArucoDetect::paramCallback, this, std::placeholders::_1, std::placeholders::_2));
|
||||||
|
|
||||||
set_markers_srv_ = nh_priv_.advertiseService("set_length_override", &ArucoDetect::setMarkers, this);
|
|
||||||
|
|
||||||
debug_pub_ = it_priv.advertise("debug", 1);
|
debug_pub_ = it_priv.advertise("debug", 1);
|
||||||
markers_pub_ = nh_priv_.advertise<aruco_pose::MarkerArray>("markers", 1);
|
markers_pub_ = nh_priv_.advertise<aruco_pose::MarkerArray>("markers", 1);
|
||||||
vis_markers_pub_ = nh_priv_.advertise<visualization_msgs::MarkerArray>("visualization", 1);
|
vis_markers_pub_ = nh_priv_.advertise<visualization_msgs::MarkerArray>("visualization", 1);
|
||||||
@@ -178,7 +172,7 @@ private:
|
|||||||
if (!known_tilt_.empty()) {
|
if (!known_tilt_.empty()) {
|
||||||
try {
|
try {
|
||||||
snap_to = tf_buffer_->lookupTransform(msg->header.frame_id, known_tilt_,
|
snap_to = tf_buffer_->lookupTransform(msg->header.frame_id, known_tilt_,
|
||||||
msg->header.stamp, transform_timeout_);
|
msg->header.stamp, ros::Duration(0.02));
|
||||||
} catch (const tf2::TransformException& e) {
|
} catch (const tf2::TransformException& e) {
|
||||||
NODELET_WARN_THROTTLE(5, "can't snap: %s", e.what());
|
NODELET_WARN_THROTTLE(5, "can't snap: %s", e.what());
|
||||||
}
|
}
|
||||||
@@ -352,29 +346,6 @@ private:
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
bool setMarkers(aruco_pose::SetMarkers::Request& req, aruco_pose::SetMarkers::Response& res)
|
|
||||||
{
|
|
||||||
for (auto const& marker : req.markers) {
|
|
||||||
if (marker.id > 999) {
|
|
||||||
res.message = "Invalid marker id: " + std::to_string(marker.id);
|
|
||||||
ROS_ERROR("%s", res.message.c_str());
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
if (!std::isfinite(marker.length) || marker.length <= 0) {
|
|
||||||
res.message = "Invalid marker " + std::to_string(marker.id) + " length: " + std::to_string(marker.length);
|
|
||||||
ROS_ERROR("%s", res.message.c_str());
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
for (auto const& marker : req.markers) {
|
|
||||||
length_override_[marker.id] = marker.length;
|
|
||||||
}
|
|
||||||
|
|
||||||
res.success = true;
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
void mapMarkersCallback(const aruco_pose::MarkerArray& msg)
|
void mapMarkersCallback(const aruco_pose::MarkerArray& msg)
|
||||||
{
|
{
|
||||||
map_markers_ids_.clear();
|
map_markers_ids_.clear();
|
||||||
@@ -385,8 +356,7 @@ private:
|
|||||||
|
|
||||||
void paramCallback(aruco_pose::DetectorConfig &config, uint32_t level)
|
void paramCallback(aruco_pose::DetectorConfig &config, uint32_t level)
|
||||||
{
|
{
|
||||||
enabled_ = config.enabled && config.length > 0;
|
enabled_ = config.enabled;
|
||||||
length_ = config.length;
|
|
||||||
parameters_->adaptiveThreshConstant = config.adaptiveThreshConstant;
|
parameters_->adaptiveThreshConstant = config.adaptiveThreshConstant;
|
||||||
parameters_->adaptiveThreshWinSizeMin = config.adaptiveThreshWinSizeMin;
|
parameters_->adaptiveThreshWinSizeMin = config.adaptiveThreshWinSizeMin;
|
||||||
parameters_->adaptiveThreshWinSizeMax = config.adaptiveThreshWinSizeMax;
|
parameters_->adaptiveThreshWinSizeMax = config.adaptiveThreshWinSizeMax;
|
||||||
|
|||||||
@@ -89,7 +89,7 @@ public:
|
|||||||
|
|
||||||
// TODO: why image_transport doesn't work here?
|
// TODO: why image_transport doesn't work here?
|
||||||
img_pub_ = nh_priv_.advertise<sensor_msgs::Image>("image", 1, true);
|
img_pub_ = nh_priv_.advertise<sensor_msgs::Image>("image", 1, true);
|
||||||
markers_pub_ = nh_priv_.advertise<aruco_pose::MarkerArray>("map", 1, true);
|
markers_pub_ = nh_priv_.advertise<aruco_pose::MarkerArray>("markers", 1, true);
|
||||||
|
|
||||||
board_ = cv::makePtr<cv::aruco::Board>();
|
board_ = cv::makePtr<cv::aruco::Board>();
|
||||||
board_->dictionary = cv::aruco::getPredefinedDictionary(
|
board_->dictionary = cv::aruco::getPredefinedDictionary(
|
||||||
|
|||||||
@@ -30,7 +30,7 @@ Options:
|
|||||||
-o <filename> Output map file name in the 'map' subdirectory of aruco_pose package
|
-o <filename> Output map file name in the 'map' subdirectory of aruco_pose package
|
||||||
|
|
||||||
Example:
|
Example:
|
||||||
rosrun aruco_pose genmap.py 0.33 2 4 1 1 0 -o test_map.txt
|
rosrun aruco_pose genmap.py 0.33 2 4 1 1 0 > $(catkin_find aruco_pose map)/test_map.txt
|
||||||
"""
|
"""
|
||||||
|
|
||||||
from __future__ import print_function
|
from __future__ import print_function
|
||||||
|
|||||||
@@ -1,7 +0,0 @@
|
|||||||
# * Add or change markers in the map
|
|
||||||
# * Change markers' properties, e. g. lengths
|
|
||||||
|
|
||||||
Marker[] markers # if length or pose is nan - remove from map
|
|
||||||
---
|
|
||||||
bool success
|
|
||||||
string message
|
|
||||||
@@ -143,7 +143,7 @@ def test_map_image(node):
|
|||||||
assert img.encoding in ('mono8', 'rgb8')
|
assert img.encoding in ('mono8', 'rgb8')
|
||||||
|
|
||||||
def test_map_markers(node):
|
def test_map_markers(node):
|
||||||
markers = rospy.wait_for_message('aruco_map/map', MarkerArray, timeout=5)
|
markers = rospy.wait_for_message('aruco_map/markers', MarkerArray, timeout=5)
|
||||||
assert markers.markers[0].id == 1
|
assert markers.markers[0].id == 1
|
||||||
assert markers.markers[1].id == 2
|
assert markers.markers[1].id == 2
|
||||||
assert markers.markers[2].id == 3
|
assert markers.markers[2].id == 3
|
||||||
|
|||||||
@@ -10,7 +10,7 @@
|
|||||||
"yametrika",
|
"yametrika",
|
||||||
"anchors",
|
"anchors",
|
||||||
"collapsible-menu",
|
"collapsible-menu",
|
||||||
"validate-links@https://github.com/okalachev/gitbook-plugin-validate-links.git",
|
"validate-links",
|
||||||
"bulk-redirect@https://github.com/okalachev/gitbook-plugin-bulk-redirect.git",
|
"bulk-redirect@https://github.com/okalachev/gitbook-plugin-bulk-redirect.git",
|
||||||
"sitemap@https://github.com/okalachev/plugin-sitemap.git",
|
"sitemap@https://github.com/okalachev/plugin-sitemap.git",
|
||||||
"toolbar@https://github.com/hamishwillee/gitbook-plugin-toolbar.git",
|
"toolbar@https://github.com/hamishwillee/gitbook-plugin-toolbar.git",
|
||||||
|
|||||||
@@ -8,9 +8,5 @@ ExecStart=/bin/bash -c ". /home/pi/catkin_ws/devel/setup.sh; \
|
|||||||
ROS_HOSTNAME=`hostname`.local exec stdbuf -o L roslaunch clover clover.launch --wait --screen --skip-log-check \
|
ROS_HOSTNAME=`hostname`.local exec stdbuf -o L roslaunch clover clover.launch --wait --screen --skip-log-check \
|
||||||
2> >(tee /tmp/clover.err)"
|
2> >(tee /tmp/clover.err)"
|
||||||
|
|
||||||
ExecStartPre=+rm /var/log/clover.log
|
|
||||||
StandardOutput=file:/var/log/clover.log
|
|
||||||
StandardError=file:/var/log/clover.log
|
|
||||||
|
|
||||||
[Install]
|
[Install]
|
||||||
WantedBy=multi-user.target
|
WantedBy=multi-user.target
|
||||||
|
|||||||
@@ -1,9 +0,0 @@
|
|||||||
#!/usr/bin/env bash
|
|
||||||
|
|
||||||
# GitBook CLI is deprecated, its installation is broken.
|
|
||||||
# This script fixes it until we stop using GitBook.
|
|
||||||
|
|
||||||
export NPM_CONFIG_UNSAFE_PERM=1
|
|
||||||
|
|
||||||
npm install gitbook-cli -g
|
|
||||||
gitbook fetch 3.2.3 && npm i npm@3.10.10 --prefix=~/.gitbook/versions/3.2.3/ # fixing https://travis-ci.org/github/CopterExpress/clover/jobs/766541125#L932
|
|
||||||
@@ -113,11 +113,15 @@ ${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/avahi-s
|
|||||||
# If RPi then use a one thread to build a ROS package on RPi, else use all
|
# If RPi then use a one thread to build a ROS package on RPi, else use all
|
||||||
[[ $(arch) == 'armv7l' ]] && NUMBER_THREADS=1 || NUMBER_THREADS=$(nproc --all)
|
[[ $(arch) == 'armv7l' ]] && NUMBER_THREADS=1 || NUMBER_THREADS=$(nproc --all)
|
||||||
# Clover
|
# Clover
|
||||||
|
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/clover.service' '/lib/systemd/system/'
|
||||||
|
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/roscore.service' '/lib/systemd/system/'
|
||||||
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/noetic-rosdep-clover.yaml' '/etc/ros/rosdep/'
|
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/noetic-rosdep-clover.yaml' '/etc/ros/rosdep/'
|
||||||
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/ros_python_paths' '/etc/sudoers.d/'
|
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/ros_python_paths' '/etc/sudoers.d/'
|
||||||
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/pigpiod.service' '/lib/systemd/system/'
|
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/pigpiod.service' '/lib/systemd/system/'
|
||||||
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/launch.nanorc' '/usr/share/nano/'
|
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/launch.nanorc' '/usr/share/nano/'
|
||||||
# ${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/kinetic-ros-clover.rosinstall' '/home/pi/ros_catkin_ws/'
|
# ${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/kinetic-ros-clover.rosinstall' '/home/pi/ros_catkin_ws/'
|
||||||
|
# Add PX4 udev rules
|
||||||
|
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${REPO_DIR}'/clover/config/99-px4fmu.rules' '/lib/udev/rules.d/'
|
||||||
# Add rename script
|
# Add rename script
|
||||||
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} exec ${SCRIPTS_DIR}'/image-ros.sh' ${REPO_URL} ${IMAGE_VERSION} false false ${NUMBER_THREADS}
|
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} exec ${SCRIPTS_DIR}'/image-ros.sh' ${REPO_URL} ${IMAGE_VERSION} false false ${NUMBER_THREADS}
|
||||||
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} exec ${SCRIPTS_DIR}'/image-validate.sh'
|
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} exec ${SCRIPTS_DIR}'/image-validate.sh'
|
||||||
|
|||||||
@@ -13,7 +13,7 @@
|
|||||||
# copies or substantial portions of the Software.
|
# copies or substantial portions of the Software.
|
||||||
#
|
#
|
||||||
|
|
||||||
set -ex # exit on error, echo commands
|
set -e # Exit immidiately on non-zero result
|
||||||
|
|
||||||
REPO=$1
|
REPO=$1
|
||||||
REF=$2
|
REF=$2
|
||||||
@@ -90,7 +90,7 @@ echo_stamp "Installing OpenCV 4.2-compatible ROS packages"
|
|||||||
apt install -y --no-install-recommends \
|
apt install -y --no-install-recommends \
|
||||||
ros-${ROS_DISTRO}-compressed-image-transport=1.14.0-0buster \
|
ros-${ROS_DISTRO}-compressed-image-transport=1.14.0-0buster \
|
||||||
ros-${ROS_DISTRO}-cv-bridge=1.15.0-0buster \
|
ros-${ROS_DISTRO}-cv-bridge=1.15.0-0buster \
|
||||||
ros-${ROS_DISTRO}-cv-camera=0.5.1-0buster \
|
ros-${ROS_DISTRO}-cv-camera=0.5.0-0buster \
|
||||||
ros-${ROS_DISTRO}-image-publisher=1.15.3-0buster \
|
ros-${ROS_DISTRO}-image-publisher=1.15.3-0buster \
|
||||||
ros-${ROS_DISTRO}-web-video-server=0.2.1-0buster
|
ros-${ROS_DISTRO}-web-video-server=0.2.1-0buster
|
||||||
apt-mark hold \
|
apt-mark hold \
|
||||||
@@ -112,7 +112,7 @@ my_travis_retry pip3 install wheel
|
|||||||
my_travis_retry pip3 install -r /home/pi/catkin_ws/src/clover/clover/requirements.txt
|
my_travis_retry pip3 install -r /home/pi/catkin_ws/src/clover/clover/requirements.txt
|
||||||
source /opt/ros/${ROS_DISTRO}/setup.bash
|
source /opt/ros/${ROS_DISTRO}/setup.bash
|
||||||
# Don't build simulation plugins for actual drone
|
# Don't build simulation plugins for actual drone
|
||||||
catkin_make -j2 -DCMAKE_BUILD_TYPE=RelWithDebInfo
|
catkin_make -j2 -DCMAKE_BUILD_TYPE=RelWithDebInfo -DCATKIN_BLACKLIST_PACKAGES=clover_gazebo_plugins
|
||||||
source devel/setup.bash
|
source devel/setup.bash
|
||||||
|
|
||||||
echo_stamp "Install clever package (for backwards compatibility)"
|
echo_stamp "Install clever package (for backwards compatibility)"
|
||||||
@@ -122,8 +122,9 @@ rm -rf build # remove build artifacts
|
|||||||
|
|
||||||
echo_stamp "Build Clover documentation"
|
echo_stamp "Build Clover documentation"
|
||||||
cd /home/pi/catkin_ws/src/clover
|
cd /home/pi/catkin_ws/src/clover
|
||||||
builder/assets/install_gitbook.sh
|
NPM_CONFIG_UNSAFE_PERM=true npm install gitbook-cli -g
|
||||||
gitbook install
|
NPM_CONFIG_UNSAFE_PERM=true gitbook fetch 3.2.3 && npm i npm@3.10.10 --prefix=~/.gitbook/versions/3.2.3/ # fixing https://travis-ci.org/github/CopterExpress/clover/jobs/766541125#L932
|
||||||
|
NPM_CONFIG_UNSAFE_PERM=true gitbook install
|
||||||
gitbook build
|
gitbook build
|
||||||
touch node_modules/CATKIN_IGNORE docs/CATKIN_IGNORE _book/CATKIN_IGNORE clover/www/CATKIN_IGNORE apps/CATKIN_IGNORE # ignore documentation files by catkin
|
touch node_modules/CATKIN_IGNORE docs/CATKIN_IGNORE _book/CATKIN_IGNORE clover/www/CATKIN_IGNORE apps/CATKIN_IGNORE # ignore documentation files by catkin
|
||||||
|
|
||||||
@@ -155,16 +156,6 @@ 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
|
||||||
|
|
||||||
echo_stamp "Make systemd services symlinks"
|
|
||||||
ln -s /home/pi/catkin_ws/src/clover/builder/assets/clover.service /lib/systemd/system/
|
|
||||||
ln -s /home/pi/catkin_ws/src/clover/builder/assets/roscore.service /lib/systemd/system/
|
|
||||||
# validate
|
|
||||||
[ -f /lib/systemd/system/clover.service ]
|
|
||||||
[ -f /lib/systemd/system/roscore.service ]
|
|
||||||
|
|
||||||
echo_stamp "Make udev rules symlink"
|
|
||||||
ln -s "$(catkin_find clover udev --first-only)"/* /lib/udev/rules.d/
|
|
||||||
|
|
||||||
echo_stamp "Setup ROS environment"
|
echo_stamp "Setup ROS environment"
|
||||||
cat << EOF >> /home/pi/.bashrc
|
cat << EOF >> /home/pi/.bashrc
|
||||||
LANG='C.UTF-8'
|
LANG='C.UTF-8'
|
||||||
|
|||||||
@@ -137,8 +137,6 @@ pip3 --version
|
|||||||
echo_stamp "Install and enable Butterfly (web terminal)"
|
echo_stamp "Install and enable Butterfly (web terminal)"
|
||||||
echo_stamp "Workaround for tornado >= 6.0 breaking butterfly"
|
echo_stamp "Workaround for tornado >= 6.0 breaking butterfly"
|
||||||
export CRYPTOGRAPHY_DONT_BUILD_RUST=1
|
export CRYPTOGRAPHY_DONT_BUILD_RUST=1
|
||||||
my_travis_retry pip3 install cryptography==3.4.6 # https://stackoverflow.com/a/68472128/6850197
|
|
||||||
my_travis_retry pip3 install pyOpenSSL==20.0.1
|
|
||||||
my_travis_retry pip3 install tornado==5.1.1
|
my_travis_retry pip3 install tornado==5.1.1
|
||||||
my_travis_retry pip3 install butterfly
|
my_travis_retry pip3 install butterfly
|
||||||
my_travis_retry pip3 install butterfly[systemd]
|
my_travis_retry pip3 install butterfly[systemd]
|
||||||
|
|||||||
@@ -31,9 +31,5 @@ cd /home/pi/catkin_ws/src/clover/builder/test/
|
|||||||
|
|
||||||
systemctl stop roscore
|
systemctl stop roscore
|
||||||
|
|
||||||
# check documented packages available
|
|
||||||
apt-cache show gst-rtsp-launch
|
|
||||||
apt-cache show openvpn
|
|
||||||
|
|
||||||
echo "Move /etc/ld.so.preload back to its original position"
|
echo "Move /etc/ld.so.preload back to its original position"
|
||||||
mv /etc/ld.so.preload.disabled-for-build /etc/ld.so.preload
|
mv /etc/ld.so.preload.disabled-for-build /etc/ld.so.preload
|
||||||
|
|||||||
@@ -34,7 +34,6 @@ i2cdetect -V
|
|||||||
butterfly -h
|
butterfly -h
|
||||||
# espeak --version
|
# espeak --version
|
||||||
mjpg_streamer --version
|
mjpg_streamer --version
|
||||||
systemctl --version
|
|
||||||
|
|
||||||
# ros stuff
|
# ros stuff
|
||||||
|
|
||||||
@@ -58,9 +57,5 @@ rosversion rosshow
|
|||||||
rosversion nodelet
|
rosversion nodelet
|
||||||
rosversion image_view
|
rosversion image_view
|
||||||
|
|
||||||
# validate some versions
|
|
||||||
[[ $(rosversion cv_camera) == "0.5.1" ]] # patched version with init fix
|
|
||||||
[[ $(rosversion ws281x) == "0.0.12" ]]
|
|
||||||
|
|
||||||
# validate examples are present
|
# validate examples are present
|
||||||
[[ $(ls /home/pi/examples/*) ]]
|
[[ $(ls /home/pi/examples/*) ]]
|
||||||
|
|||||||
@@ -5,7 +5,7 @@ import sys
|
|||||||
import subprocess
|
import subprocess
|
||||||
|
|
||||||
EXCLUDE = ('clever4-front-white.png', 'clever4-front-white-large.png', '.DS_Store',
|
EXCLUDE = ('clever4-front-white.png', 'clever4-front-white-large.png', '.DS_Store',
|
||||||
'clever4-front-black-large.png','clover42-black.png', 'clover42-main-margin.png')
|
'clever4-front-black-large.png','clover42-black.png')
|
||||||
|
|
||||||
code = 0
|
code = 0
|
||||||
|
|
||||||
|
|||||||
@@ -4,8 +4,6 @@ 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
|
||||||
@@ -26,7 +24,6 @@ find_package(catkin REQUIRED COMPONENTS
|
|||||||
tf2_ros
|
tf2_ros
|
||||||
image_transport
|
image_transport
|
||||||
cv_bridge
|
cv_bridge
|
||||||
dynamic_reconfigure
|
|
||||||
)
|
)
|
||||||
|
|
||||||
list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}/cmake")
|
list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}/cmake")
|
||||||
@@ -129,9 +126,10 @@ generate_messages(
|
|||||||
## and list every .cfg file to be processed
|
## and list every .cfg file to be processed
|
||||||
|
|
||||||
## 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/Flow.cfg
|
# cfg/DynReconf1.cfg
|
||||||
)
|
# cfg/DynReconf2.cfg
|
||||||
|
# )
|
||||||
|
|
||||||
###################################
|
###################################
|
||||||
## catkin specific configuration ##
|
## catkin specific configuration ##
|
||||||
@@ -213,8 +211,6 @@ add_dependencies(clover_led ${PROJECT_NAME}_generate_messages_cpp)
|
|||||||
|
|
||||||
add_dependencies(shell ${PROJECT_NAME}_generate_messages_cpp)
|
add_dependencies(shell ${PROJECT_NAME}_generate_messages_cpp)
|
||||||
|
|
||||||
add_dependencies(${PROJECT_NAME} ${PROJECT_NAME}_gencfg)
|
|
||||||
|
|
||||||
## Rename C++ executable without prefix
|
## Rename C++ executable without prefix
|
||||||
## The above recommended prefix causes long target names, the following renames the
|
## The above recommended prefix causes long target names, the following renames the
|
||||||
## target back to the shorter version for ease of user use
|
## target back to the shorter version for ease of user use
|
||||||
@@ -274,8 +270,6 @@ install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
|
|||||||
|
|
||||||
install(DIRECTORY examples DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
|
install(DIRECTORY examples DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
|
||||||
|
|
||||||
install(DIRECTORY www DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
|
|
||||||
|
|
||||||
# TODO: install www
|
# TODO: install www
|
||||||
|
|
||||||
# Only install udev rules when building a Debian package
|
# Only install udev rules when building a Debian package
|
||||||
@@ -284,7 +278,7 @@ string(FIND ${CMAKE_INSTALL_PREFIX} "/opt/ros" _PREFIX_INDEX)
|
|||||||
if (${_PREFIX_INDEX} EQUAL 0)
|
if (${_PREFIX_INDEX} EQUAL 0)
|
||||||
message(STATUS "Building as a Debian package - adding udev rules as installable files")
|
message(STATUS "Building as a Debian package - adding udev rules as installable files")
|
||||||
install(FILES
|
install(FILES
|
||||||
udev/99-px4fmu.rules
|
config/99-px4fmu.rules
|
||||||
DESTINATION /lib/udev/rules.d
|
DESTINATION /lib/udev/rules.d
|
||||||
)
|
)
|
||||||
else()
|
else()
|
||||||
|
|||||||
@@ -36,7 +36,7 @@ curl https://raw.githubusercontent.com/mavlink/mavros/master/mavros/scripts/inst
|
|||||||
You may optionally install udev rules to provide `/dev/px4fmu` symlink to your PX4-based flight controller connected over USB. Copy `99-px4fmu.rules` to your `/lib/udev/rules.d` folder:
|
You may optionally install udev rules to provide `/dev/px4fmu` symlink to your PX4-based flight controller connected over USB. Copy `99-px4fmu.rules` to your `/lib/udev/rules.d` folder:
|
||||||
|
|
||||||
```bash
|
```bash
|
||||||
cd ~/catkin_ws/src/clover/clover/udev
|
cd ~/catkin_ws/src/clover/clover/config
|
||||||
sudo cp 99-px4fmu.rules /lib/udev/rules.d
|
sudo cp 99-px4fmu.rules /lib/udev/rules.d
|
||||||
```
|
```
|
||||||
|
|
||||||
|
|||||||
@@ -1,10 +0,0 @@
|
|||||||
#!/usr/bin/env python
|
|
||||||
PACKAGE = "clover"
|
|
||||||
|
|
||||||
from dynamic_reconfigure.parameter_generator_catkin import *
|
|
||||||
|
|
||||||
gen = ParameterGenerator()
|
|
||||||
|
|
||||||
gen.add("enabled", bool_t, 0, "if optical flow enabled", True)
|
|
||||||
|
|
||||||
exit(gen.generate(PACKAGE, "clover", "Flow"))
|
|
||||||
@@ -12,6 +12,4 @@ SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0016", ATTRS{produ
|
|||||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0013", ATTRS{product}=="PX4 FMU v4.x PRO", SYMLINK+="px4fmu"
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0013", ATTRS{product}=="PX4 FMU v4.x PRO", SYMLINK+="px4fmu"
|
||||||
# Omnibus
|
# Omnibus
|
||||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0001", ATTRS{product}=="PX4 OmnibusF4SD", SYMLINK+="px4fmu"
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="26ac", ATTRS{idProduct}=="0001", ATTRS{product}=="PX4 OmnibusF4SD", SYMLINK+="px4fmu"
|
||||||
# CUAV X7 Pro
|
|
||||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="3163", ATTRS{idProduct}=="004c", ATTRS{product}=="PX4 CUAV X7Pro", SYMLINK+="px4fmu"
|
|
||||||
|
|
||||||
@@ -15,17 +15,17 @@ 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)
|
||||||
|
|
||||||
print('Take off and hover 1 m above the ground')
|
# Take off and hover 1 m above the ground
|
||||||
navigate(x=0, y=0, z=1, frame_id='body', auto_arm=True)
|
navigate(x=0, y=0, z=1, frame_id='body', auto_arm=True)
|
||||||
|
|
||||||
# Wait for 5 seconds
|
# Wait for 3 seconds
|
||||||
rospy.sleep(5)
|
rospy.sleep(3)
|
||||||
|
|
||||||
print('Fly forward 1 m')
|
# Fly forward 1 m
|
||||||
navigate(x=1, y=0, z=0, frame_id='body')
|
navigate(x=1, y=0, z=0, frame_id='body')
|
||||||
|
|
||||||
# Wait for 5 seconds
|
# Wait for 3 seconds
|
||||||
rospy.sleep(5)
|
rospy.sleep(3)
|
||||||
|
|
||||||
print('Perform landing')
|
# Perform landing
|
||||||
land()
|
land()
|
||||||
|
|||||||
@@ -15,23 +15,23 @@ 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)
|
||||||
|
|
||||||
print('Take off and hover 1 m above the ground')
|
# Take off and hover 1 m above the ground
|
||||||
navigate(x=0, y=0, z=1, frame_id='body', auto_arm=True)
|
navigate(x=0, y=0, z=1, frame_id='body', auto_arm=True)
|
||||||
|
|
||||||
# Wait for 5 seconds
|
# Wait for 3 seconds
|
||||||
rospy.sleep(5)
|
rospy.sleep(3)
|
||||||
|
|
||||||
print('Fly 1 meter above ArUco marker 0')
|
# Fly 1 meter above ArUco marker 0
|
||||||
navigate(x=0, y=0, z=1, frame_id='aruco_0')
|
navigate(x=0, y=0, z=1, frame_id='aruco_0')
|
||||||
|
|
||||||
# Wait for 5 seconds
|
# Wait for 3 seconds
|
||||||
rospy.sleep(5)
|
rospy.sleep(3)
|
||||||
|
|
||||||
print('Fly to x=1 y=1 z=1 relative to ArUco markers map')
|
# Fly to x=1 y=1 z=1 relative to ArUco markers map
|
||||||
navigate(x=1, y=1, z=1, frame_id='aruco_map')
|
navigate(x=1, y=1, z=1, frame_id='aruco_map')
|
||||||
|
|
||||||
# Wait for 5 seconds
|
# Wait for 3 seconds
|
||||||
rospy.sleep(5)
|
rospy.sleep(3)
|
||||||
|
|
||||||
print('Perform landing')
|
# Perform landing
|
||||||
land()
|
land()
|
||||||
|
|||||||
@@ -1,47 +0,0 @@
|
|||||||
# Information: https://clover.coex.tech/en/simple_offboard.html#navigateglobal
|
|
||||||
|
|
||||||
import rospy
|
|
||||||
from clover import srv
|
|
||||||
from std_srvs.srv import Trigger
|
|
||||||
import math
|
|
||||||
|
|
||||||
rospy.init_node('flight')
|
|
||||||
|
|
||||||
get_telemetry = rospy.ServiceProxy('get_telemetry', srv.GetTelemetry)
|
|
||||||
navigate = rospy.ServiceProxy('navigate', srv.Navigate)
|
|
||||||
navigate_global = rospy.ServiceProxy('navigate_global', srv.NavigateGlobal)
|
|
||||||
set_position = rospy.ServiceProxy('set_position', srv.SetPosition)
|
|
||||||
set_velocity = rospy.ServiceProxy('set_velocity', srv.SetVelocity)
|
|
||||||
set_attitude = rospy.ServiceProxy('set_attitude', srv.SetAttitude)
|
|
||||||
set_rates = rospy.ServiceProxy('set_rates', srv.SetRates)
|
|
||||||
land = rospy.ServiceProxy('land', Trigger)
|
|
||||||
|
|
||||||
# https://clover.coex.tech/en/snippets.html#wait_arrival
|
|
||||||
def wait_arrival(tolerance=0.2):
|
|
||||||
while not rospy.is_shutdown():
|
|
||||||
telem = get_telemetry(frame_id='navigate_target')
|
|
||||||
if math.sqrt(telem.x ** 2 + telem.y ** 2 + telem.z ** 2) < tolerance:
|
|
||||||
break
|
|
||||||
rospy.sleep(0.2)
|
|
||||||
|
|
||||||
start = get_telemetry()
|
|
||||||
|
|
||||||
if math.isnan(start.lat):
|
|
||||||
raise Exception('No global position, install and configure GPS sensor: https://clover.coex.tech/gps')
|
|
||||||
|
|
||||||
print('Start point global position: lat={}, lon={}'.format(start.lat, start.lon))
|
|
||||||
|
|
||||||
print('Take off 3 meters')
|
|
||||||
navigate(x=0, y=0, z=3, frame_id='body', auto_arm=True)
|
|
||||||
wait_arrival()
|
|
||||||
|
|
||||||
print('Fly 1 arcsecond to the North (approx. 30 meters)')
|
|
||||||
navigate_global(lat=start.lat+1.0/60/60, lon=start.lon, z=start.z+3, yaw=math.inf, speed=5)
|
|
||||||
wait_arrival()
|
|
||||||
|
|
||||||
print('Fly to home position')
|
|
||||||
navigate_global(lat=start.lat, lon=start.lon, z=start.z+3, yaw=math.inf, speed=5)
|
|
||||||
wait_arrival()
|
|
||||||
|
|
||||||
print('Land')
|
|
||||||
land()
|
|
||||||
@@ -31,11 +31,11 @@ def navigate_wait(x=0, y=0, z=0, yaw=float('nan'), yaw_rate=0, speed=0.5, \
|
|||||||
return res
|
return res
|
||||||
rospy.sleep(0.2)
|
rospy.sleep(0.2)
|
||||||
|
|
||||||
print('Take off 1 meter')
|
# Take off 1 meter
|
||||||
navigate_wait(z=1, frame_id='body', auto_arm=True)
|
navigate_wait(z=1, frame_id='body', auto_arm=True)
|
||||||
|
|
||||||
print('Fly forward 1 m')
|
# Fly forward 1 m
|
||||||
navigate_wait(x=1, frame_id='body')
|
navigate_wait(x=1, frame_id='body')
|
||||||
|
|
||||||
print('Land')
|
# Land
|
||||||
land()
|
land()
|
||||||
|
|||||||
@@ -1,15 +0,0 @@
|
|||||||
# Information: https://clover.coex.tech/en/laser.html
|
|
||||||
|
|
||||||
import rospy
|
|
||||||
from sensor_msgs.msg import Range
|
|
||||||
|
|
||||||
rospy.init_node('process_rangefinder')
|
|
||||||
|
|
||||||
def range_callback(msg):
|
|
||||||
# Process data from the rangefinder
|
|
||||||
print('Rangefinder distance:', msg.range)
|
|
||||||
|
|
||||||
# Subscribe to laser rangefinder data
|
|
||||||
rospy.Subscriber('rangefinder/range', Range, range_callback)
|
|
||||||
|
|
||||||
rospy.spin()
|
|
||||||
@@ -3,25 +3,21 @@
|
|||||||
<arg name="aruco_map" default="false"/>
|
<arg name="aruco_map" default="false"/>
|
||||||
<arg name="aruco_vpe" default="false"/>
|
<arg name="aruco_vpe" default="false"/>
|
||||||
<arg name="placement" default="floor"/> <!-- markers placement: floor, ceiling, unknown -->
|
<arg name="placement" default="floor"/> <!-- markers placement: floor, ceiling, unknown -->
|
||||||
<arg name="length" default="0.22"/> <!-- not-in-map markers length, m -->
|
<arg name="length" default="0.33"/> <!-- not-in-map markers length, m -->
|
||||||
<arg name="map" default="map.txt"/> <!-- markers map file name -->
|
<arg name="map" default="map.txt"/> <!-- markers map file name -->
|
||||||
|
|
||||||
<!-- For additional help go to https://clover.coex.tech/aruco -->
|
<!-- For additional help go to https://clover.coex.tech/aruco -->
|
||||||
|
|
||||||
<arg name="force_init" default="false"/>
|
|
||||||
<arg name="disable" default="false"/> <!-- only force init -->
|
|
||||||
|
|
||||||
<!-- aruco_detect: detect aruco markers, estimate poses -->
|
<!-- aruco_detect: detect aruco markers, estimate poses -->
|
||||||
<node name="aruco_detect" pkg="nodelet" if="$(eval aruco_detect and not disable)" type="nodelet" args="load aruco_pose/aruco_detect main_camera_nodelet_manager" output="screen" clear_params="true" respawn="true">
|
<node name="aruco_detect" pkg="nodelet" if="$(arg aruco_detect)" type="nodelet" args="load aruco_pose/aruco_detect main_camera_nodelet_manager" output="screen" clear_params="true" respawn="true">
|
||||||
<remap from="image_raw" to="main_camera/image_raw"/>
|
<remap from="image_raw" to="main_camera/image_raw"/>
|
||||||
<remap from="camera_info" to="main_camera/camera_info"/>
|
<remap from="camera_info" to="main_camera/camera_info"/>
|
||||||
<remap from="map_markers" to="aruco_map/map"/>
|
<remap from="map_markers" to="aruco_map/markers" if="$(arg aruco_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="known_tilt" value="map" if="$(eval placement == 'floor')"/>
|
<param name="known_tilt" value="map" if="$(eval placement == 'floor')"/>
|
||||||
<param name="known_tilt" value="map_flipped" if="$(eval placement == 'ceiling')"/>
|
<param name="known_tilt" value="map_flipped" if="$(eval placement == 'ceiling')"/>
|
||||||
<param name="length" value="$(arg length)"/>
|
<param name="length" value="$(arg length)"/>
|
||||||
<param name="transform_timeout" value="0.1"/>
|
|
||||||
<!-- aruco detector parameters -->
|
<!-- aruco detector parameters -->
|
||||||
<param name="cornerRefinementMethod" value="2"/> <!-- contour refinement -->
|
<param name="cornerRefinementMethod" value="2"/> <!-- contour refinement -->
|
||||||
<param name="minMarkerPerimeterRate" value="0.075"/> <!-- 0.075 for 320x240, 0.0375 for 640x480 -->
|
<param name="minMarkerPerimeterRate" value="0.075"/> <!-- 0.075 for 320x240, 0.0375 for 640x480 -->
|
||||||
@@ -30,7 +26,7 @@
|
|||||||
</node>
|
</node>
|
||||||
|
|
||||||
<!-- aruco_map: estimate aruco map pose -->
|
<!-- aruco_map: estimate aruco map pose -->
|
||||||
<node name="aruco_map" pkg="nodelet" type="nodelet" if="$(eval aruco_map and not disable)" args="load aruco_pose/aruco_map main_camera_nodelet_manager" output="screen" clear_params="true" respawn="true">
|
<node name="aruco_map" pkg="nodelet" type="nodelet" if="$(arg aruco_map)" args="load aruco_pose/aruco_map main_camera_nodelet_manager" output="screen" clear_params="true" respawn="true">
|
||||||
<remap from="image_raw" to="main_camera/image_raw"/>
|
<remap from="image_raw" to="main_camera/image_raw"/>
|
||||||
<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"/>
|
||||||
@@ -45,11 +41,11 @@
|
|||||||
</node>
|
</node>
|
||||||
|
|
||||||
<!-- vpe publisher from aruco markers -->
|
<!-- vpe publisher from aruco markers -->
|
||||||
<node name="vpe_publisher" pkg="clover" type="vpe_publisher" if="$(eval aruco_vpe or force_init)" output="screen" clear_params="true">
|
<node name="vpe_publisher" pkg="clover" type="vpe_publisher" if="$(arg aruco_vpe)" output="screen" clear_params="true">
|
||||||
<remap from="~pose_cov" to="aruco_map/pose" if="$(arg aruco_vpe)"/>
|
<remap from="~pose_cov" to="aruco_map/pose"/>
|
||||||
<remap from="~vpe" to="mavros/vision_pose/pose"/>
|
<remap from="~vpe" to="mavros/vision_pose/pose"/>
|
||||||
<param name="frame_id" value="aruco_map_detected" if="$(arg aruco_vpe)"/>
|
<param name="frame_id" value="aruco_map_detected"/>
|
||||||
<param name="force_init" value="$(arg force_init)"/>
|
<param name="publish_zero" value="true"/>
|
||||||
<param name="offset_frame_id" value="aruco_map"/>
|
<param name="offset_frame_id" value="aruco_map"/>
|
||||||
</node>
|
</node>
|
||||||
</launch>
|
</launch>
|
||||||
|
|||||||
@@ -12,7 +12,6 @@
|
|||||||
<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" 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 -->
|
||||||
|
|
||||||
@@ -34,10 +33,7 @@
|
|||||||
</node>
|
</node>
|
||||||
|
|
||||||
<!-- aruco markers -->
|
<!-- aruco markers -->
|
||||||
<include file="$(find clover)/launch/aruco.launch" if="$(eval aruco or force_init)">
|
<include file="$(find clover)/launch/aruco.launch" if="$(arg aruco)"/>
|
||||||
<arg name="force_init" value="$(arg force_init)"/>
|
|
||||||
<arg name="disable" value="$(eval not aruco)"/>
|
|
||||||
</include>
|
|
||||||
|
|
||||||
<!-- optical flow -->
|
<!-- optical flow -->
|
||||||
<node pkg="nodelet" type="nodelet" name="optical_flow" args="load clover/optical_flow main_camera_nodelet_manager" if="$(arg optical_flow)" clear_params="true" output="screen" respawn="true">
|
<node pkg="nodelet" type="nodelet" name="optical_flow" args="load clover/optical_flow main_camera_nodelet_manager" if="$(arg optical_flow)" clear_params="true" output="screen" respawn="true">
|
||||||
@@ -51,6 +47,9 @@
|
|||||||
|
|
||||||
<!-- 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/body" value="map"/>
|
||||||
|
<param name="reference_frames/base_link" value="map"/>
|
||||||
|
<param name="reference_frames/navigate_target" value="map"/>
|
||||||
<param name="reference_frames/main_camera_optical" value="map"/>
|
<param name="reference_frames/main_camera_optical" value="map"/>
|
||||||
</node>
|
</node>
|
||||||
|
|
||||||
|
|||||||
@@ -39,7 +39,7 @@
|
|||||||
<rosparam command="load" file="$(find clover)/launch/mavros_config.yaml"/>
|
<rosparam command="load" file="$(find clover)/launch/mavros_config.yaml"/>
|
||||||
|
|
||||||
<!-- remap rangefinder -->
|
<!-- remap rangefinder -->
|
||||||
<remap from="mavros/distance_sensor/rangefinder_sub" to="$(arg distance_sensor_remap)" if="$(eval bool(distance_sensor_remap))"/>
|
<remap from="mavros/distance_sensor/rangefinder_sub" to="rangefinder/range"/>
|
||||||
|
|
||||||
<rosparam param="plugin_whitelist">
|
<rosparam param="plugin_whitelist">
|
||||||
- altitude
|
- altitude
|
||||||
|
|||||||
@@ -1,11 +1,11 @@
|
|||||||
# Config file for mavros
|
# Config file for mavros
|
||||||
# Based on https://raw.githubusercontent.com/mavlink/mavros/master/mavros/launch/px4_config.yaml
|
# Based on https://raw.githubusercontent.com/mavlink/mavros/master/mavros/launch/px4_config.yaml
|
||||||
|
|
||||||
startup_px4_usb_quirk: false
|
startup_px4_usb_quirk: true
|
||||||
|
|
||||||
conn:
|
conn:
|
||||||
heartbeat_rate: 1.0 # send heartbeat rate in Hertz
|
heartbeat_rate: 1.0 # send hertbeat rate in Hertz
|
||||||
timeout: 10.0 # heartbeat timeout in seconds
|
timeout: 10.0 # hertbeat timeout in seconds
|
||||||
timesync_rate: 10.0 # TIMESYNC rate in Hertz (feature disabled if 0.0)
|
timesync_rate: 10.0 # TIMESYNC rate in Hertz (feature disabled if 0.0)
|
||||||
system_time_rate: 1.0 # send system time to FCU rate in Hertz (disabled if 0.0)
|
system_time_rate: 1.0 # send system time to FCU rate in Hertz (disabled if 0.0)
|
||||||
|
|
||||||
@@ -13,7 +13,6 @@ time:
|
|||||||
time_ref_source: "fcu" # time_reference source
|
time_ref_source: "fcu" # time_reference source
|
||||||
timesync_mode: MAVLINK
|
timesync_mode: MAVLINK
|
||||||
timesync_avg_alpha: 0.6 # timesync averaging factor
|
timesync_avg_alpha: 0.6 # timesync averaging factor
|
||||||
publish_sim_time: false # don't publish /clock
|
|
||||||
|
|
||||||
global_position:
|
global_position:
|
||||||
frame_id: "map" # origin frame
|
frame_id: "map" # origin frame
|
||||||
@@ -78,9 +77,6 @@ distance_sensor:
|
|||||||
field_of_view: 0.5
|
field_of_view: 0.5
|
||||||
rangefinder_sub:
|
rangefinder_sub:
|
||||||
subscriber: true
|
subscriber: true
|
||||||
id: 1
|
|
||||||
orientation: PITCH_270
|
|
||||||
covariance: 1 # cm
|
|
||||||
|
|
||||||
# fake_gps
|
# fake_gps
|
||||||
fake_gps:
|
fake_gps:
|
||||||
|
|||||||
@@ -1,7 +1,7 @@
|
|||||||
<?xml version="1.0"?>
|
<?xml version="1.0"?>
|
||||||
<package format="3">
|
<package format="3">
|
||||||
<name>clover</name>
|
<name>clover</name>
|
||||||
<version>0.23.0</version>
|
<version>0.21.1</version>
|
||||||
<description>The Clover package</description>
|
<description>The Clover package</description>
|
||||||
|
|
||||||
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>
|
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>
|
||||||
@@ -39,7 +39,6 @@
|
|||||||
<depend>tf2_web_republisher</depend>
|
<depend>tf2_web_republisher</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>
|
|
||||||
<exec_depend>python-pymavlink</exec_depend>
|
<exec_depend>python-pymavlink</exec_depend>
|
||||||
<!-- Use test_depend for packages you need only for testing: -->
|
<!-- Use test_depend for packages you need only for testing: -->
|
||||||
<!-- <test_depend>gtest</test_depend> -->
|
<!-- <test_depend>gtest</test_depend> -->
|
||||||
|
|||||||
@@ -1,87 +0,0 @@
|
|||||||
#!/usr/bin/env python3
|
|
||||||
|
|
||||||
import rospy
|
|
||||||
import math
|
|
||||||
import signal
|
|
||||||
import sys
|
|
||||||
import dynamic_reconfigure.client
|
|
||||||
from clover import srv
|
|
||||||
from std_srvs.srv import Trigger
|
|
||||||
from sensor_msgs.msg import Range
|
|
||||||
from aruco_pose.msg import MarkerArray
|
|
||||||
from util import handle_response
|
|
||||||
|
|
||||||
rospy.init_node('autotest_aruco', disable_signals=True) # disable signals to allow interrupting with ctrl+c
|
|
||||||
|
|
||||||
flow_client = dynamic_reconfigure.client.Client('optical_flow')
|
|
||||||
get_telemetry = rospy.ServiceProxy('get_telemetry', srv.GetTelemetry)
|
|
||||||
navigate = handle_response(rospy.ServiceProxy('navigate', srv.Navigate))
|
|
||||||
land = handle_response(rospy.ServiceProxy('land', Trigger))
|
|
||||||
|
|
||||||
def interrupt(sig, frame):
|
|
||||||
print('\nInterrupted, landing...')
|
|
||||||
land()
|
|
||||||
sys.exit(0)
|
|
||||||
|
|
||||||
signal.signal(signal.SIGINT, interrupt)
|
|
||||||
|
|
||||||
def print_current_map_position():
|
|
||||||
telem = get_telemetry()
|
|
||||||
dist = rospy.wait_for_message('rangefinder/range', Range).range
|
|
||||||
print('Map position:\tx={:.1f}\ty={:.1f}\tz={:.1f}\tyaw={:.1f}\tdist={:.2f}'.format(telem.x, telem.y, telem.z, telem.yaw, dist))
|
|
||||||
|
|
||||||
def navigate_wait(x=0, y=0, z=0, yaw=float('nan'), yaw_rate=0, speed=0.5, \
|
|
||||||
frame_id='body', tolerance=0.2, auto_arm=False):
|
|
||||||
|
|
||||||
res = navigate(x=x, y=y, z=z, yaw=yaw, yaw_rate=yaw_rate, speed=speed, \
|
|
||||||
frame_id=frame_id, auto_arm=auto_arm)
|
|
||||||
|
|
||||||
if not res.success:
|
|
||||||
return res
|
|
||||||
|
|
||||||
while not rospy.is_shutdown():
|
|
||||||
telem = get_telemetry(frame_id='navigate_target')
|
|
||||||
if math.sqrt(telem.x ** 2 + telem.y ** 2 + telem.z ** 2) < tolerance:
|
|
||||||
return res
|
|
||||||
rospy.sleep(0.2)
|
|
||||||
|
|
||||||
markers = rospy.wait_for_message('aruco_map/map', MarkerArray, timeout=3)
|
|
||||||
left = min(marker.pose.position.x for marker in markers.markers)
|
|
||||||
bottom = min(marker.pose.position.y for marker in markers.markers)
|
|
||||||
width = max(marker.pose.position.x for marker in markers.markers)
|
|
||||||
height = max(marker.pose.position.y for marker in markers.markers)
|
|
||||||
center_x = left + width / 2
|
|
||||||
center_y = bottom + height / 2
|
|
||||||
|
|
||||||
print('Map rect: %g %g - %g %g' % (left, bottom, width, height))
|
|
||||||
|
|
||||||
input('Take off and hover 1 m [enter] ')
|
|
||||||
navigate_wait(x=0, y=0, z=1, frame_id='body', auto_arm=True)
|
|
||||||
print_current_map_position()
|
|
||||||
|
|
||||||
input('Go to corner %g %g 1.5 speed 1 [enter] ' % (width, height))
|
|
||||||
navigate_wait(x=width, y=height, z=1.5, speed=1, frame_id='aruco_map')
|
|
||||||
print_current_map_position()
|
|
||||||
|
|
||||||
input('Go to center %g %g 1.5 speed 5 [enter] ' % (center_x, center_y))
|
|
||||||
navigate_wait(x=center_x, y=center_y, z=1.5, speed=5, frame_id='aruco_map')
|
|
||||||
print_current_map_position()
|
|
||||||
|
|
||||||
input('Disable optical flow and keep hovering [enter] ')
|
|
||||||
flow_client.update_configuration({'enabled': False})
|
|
||||||
rospy.sleep(5)
|
|
||||||
|
|
||||||
input('Enable optical flow back [enter] ')
|
|
||||||
flow_client.update_configuration({'enabled': True})
|
|
||||||
|
|
||||||
input('Go to side 1 %g 2 heading top [enter] ' % (center_y))
|
|
||||||
navigate_wait(x=1, y=center_y, z=2, yaw=1.57, frame_id='aruco_map')
|
|
||||||
print_current_map_position()
|
|
||||||
|
|
||||||
marker_id = markers.markers[0].id
|
|
||||||
input('Go to marker %d z=1.5 [enter] ' % marker_id)
|
|
||||||
navigate_wait(x=0, y=0, z=1.5, yaw=0, frame_id='aruco_%d' % marker_id)
|
|
||||||
print_current_map_position()
|
|
||||||
|
|
||||||
input('Perform landing [enter] ')
|
|
||||||
land()
|
|
||||||
@@ -1,100 +0,0 @@
|
|||||||
#!/usr/bin/env python3
|
|
||||||
|
|
||||||
import rospy
|
|
||||||
import math
|
|
||||||
from math import nan
|
|
||||||
import signal
|
|
||||||
import sys
|
|
||||||
from clover import srv
|
|
||||||
from std_srvs.srv import Trigger
|
|
||||||
from sensor_msgs.msg import Range
|
|
||||||
from util import handle_response
|
|
||||||
|
|
||||||
rospy.init_node('autotest_flight', disable_signals=True) # disable signals to allow interrupting with ctrl+c
|
|
||||||
|
|
||||||
get_telemetry = rospy.ServiceProxy('get_telemetry', srv.GetTelemetry)
|
|
||||||
navigate = handle_response(rospy.ServiceProxy('navigate', srv.Navigate))
|
|
||||||
navigate_global = handle_response(rospy.ServiceProxy('navigate_global', srv.NavigateGlobal))
|
|
||||||
set_position = handle_response(rospy.ServiceProxy('set_position', srv.SetPosition))
|
|
||||||
set_velocity = handle_response(rospy.ServiceProxy('set_velocity', srv.SetVelocity))
|
|
||||||
set_attitude = handle_response(rospy.ServiceProxy('set_attitude', srv.SetAttitude))
|
|
||||||
set_rates = handle_response(rospy.ServiceProxy('set_rates', srv.SetRates))
|
|
||||||
land = handle_response(rospy.ServiceProxy('land', Trigger))
|
|
||||||
|
|
||||||
def interrupt(sig, frame):
|
|
||||||
print('\nInterrupted, landing...')
|
|
||||||
land()
|
|
||||||
sys.exit(0)
|
|
||||||
|
|
||||||
signal.signal(signal.SIGINT, interrupt)
|
|
||||||
|
|
||||||
def navigate_wait(x=0, y=0, z=0, yaw=nan, yaw_rate=0, speed=0.5, \
|
|
||||||
frame_id='body', tolerance=0.2, auto_arm=False):
|
|
||||||
|
|
||||||
res = navigate(x=x, y=y, z=z, yaw=yaw, yaw_rate=yaw_rate, speed=speed, \
|
|
||||||
frame_id=frame_id, auto_arm=auto_arm)
|
|
||||||
|
|
||||||
if not res.success:
|
|
||||||
return res
|
|
||||||
|
|
||||||
while not rospy.is_shutdown():
|
|
||||||
telem = get_telemetry(frame_id='navigate_target')
|
|
||||||
if math.sqrt(telem.x ** 2 + telem.y ** 2 + telem.z ** 2) < tolerance:
|
|
||||||
return res
|
|
||||||
rospy.sleep(0.2)
|
|
||||||
|
|
||||||
def print_distance():
|
|
||||||
dist = rospy.wait_for_message('rangefinder/range', Range).range
|
|
||||||
print('Distance: {:.2f}'.format(dist))
|
|
||||||
|
|
||||||
input('Take off and hover 1 m [enter] ')
|
|
||||||
navigate_wait(z=1, frame_id='body', auto_arm=True)
|
|
||||||
print_distance()
|
|
||||||
start = get_telemetry()
|
|
||||||
|
|
||||||
input('Fly forward 2 m [enter] ')
|
|
||||||
navigate_wait(x=2, frame_id='navigate_target')
|
|
||||||
print_distance()
|
|
||||||
|
|
||||||
input('Climb 0.5 m [enter] ')
|
|
||||||
navigate_wait(z=0.5, frame_id='navigate_target')
|
|
||||||
print_distance()
|
|
||||||
|
|
||||||
input('Rotate left 90° [enter] ')
|
|
||||||
navigate(yaw=math.pi / 2, frame_id='navigate_target')
|
|
||||||
rospy.sleep(3)
|
|
||||||
|
|
||||||
input('Use set_velocity to fly forward 2 m speed 1 [enter]')
|
|
||||||
set_velocity(vx=1, vy=0.0, vz=0, frame_id='body')
|
|
||||||
rospy.sleep(2)
|
|
||||||
set_position(frame_id='body')
|
|
||||||
|
|
||||||
input('Rotate right 90° [enter] ')
|
|
||||||
navigate(yaw=-math.pi / 2, frame_id='navigate_target')
|
|
||||||
rospy.sleep(3)
|
|
||||||
|
|
||||||
input('Use set_attitude to fly backwards [enter]')
|
|
||||||
set_attitude(pitch=-0.3, roll=0, yaw=0, thrust=0.5, frame_id='body')
|
|
||||||
rospy.sleep(0.3)
|
|
||||||
set_position(frame_id='body')
|
|
||||||
|
|
||||||
input('Use set_attitude to fly right [enter]')
|
|
||||||
set_attitude(pitch=0, roll=0.3, yaw=0, thrust=0.5, frame_id='body')
|
|
||||||
rospy.sleep(0.5)
|
|
||||||
set_position(frame_id='body')
|
|
||||||
|
|
||||||
input('Use set_rates to fly right [enter]')
|
|
||||||
set_rates(roll_rate=1.2, thrust=0.5)
|
|
||||||
rospy.sleep(0.4)
|
|
||||||
set_position(frame_id='body')
|
|
||||||
|
|
||||||
input('Rotate 360° to the right using yaw_rate [enter]')
|
|
||||||
set_position(x=nan, y=nan, z=nan, frame_id='body', yaw=nan, yaw_rate=-1)
|
|
||||||
rospy.sleep(2 * math.pi)
|
|
||||||
set_position(frame_id='body')
|
|
||||||
|
|
||||||
input('Return to start point [enter]')
|
|
||||||
navigate_wait(x=start.x, y=start.y, z=start.z, yaw=start.yaw, speed=1, frame_id='map')
|
|
||||||
|
|
||||||
input('Land [enter]')
|
|
||||||
land()
|
|
||||||
@@ -1,72 +0,0 @@
|
|||||||
#!/usr/bin/env python3
|
|
||||||
|
|
||||||
import rospy
|
|
||||||
import functools
|
|
||||||
from clover.srv import SetLEDEffect
|
|
||||||
from led_msgs.srv import SetLEDs
|
|
||||||
from led_msgs.msg import LEDStateArray, LEDState
|
|
||||||
from util import handle_response
|
|
||||||
|
|
||||||
rospy.init_node('autotest_led', disable_signals=True)
|
|
||||||
|
|
||||||
set_leds = handle_response(rospy.ServiceProxy('led/set_leds', SetLEDs))
|
|
||||||
set_effect = handle_response(rospy.ServiceProxy('led/set_effect', SetLEDEffect))
|
|
||||||
|
|
||||||
led_count = len(rospy.wait_for_message('led/state', LEDStateArray, timeout=10).leds)
|
|
||||||
print('LED count =', led_count)
|
|
||||||
|
|
||||||
print('== Testing effects ==')
|
|
||||||
|
|
||||||
input('Fill red [enter] ')
|
|
||||||
set_effect(r=255, g=0, b=0)
|
|
||||||
|
|
||||||
input('Fill green [enter] ')
|
|
||||||
set_effect(r=0, g=100, b=0)
|
|
||||||
|
|
||||||
input('Blink white [enter] ')
|
|
||||||
set_effect(effect='blink', r=255, g=255, b=255)
|
|
||||||
rospy.sleep(3)
|
|
||||||
|
|
||||||
input('Blink fast violet [enter] ')
|
|
||||||
set_effect(effect='blink_fast', r=220, g=20, b=250)
|
|
||||||
rospy.sleep(3)
|
|
||||||
|
|
||||||
input('Fade to blue [enter] ')
|
|
||||||
set_effect(effect='fade', r=0, g=0, b=255)
|
|
||||||
|
|
||||||
input('Wipe to yellow [enter] ')
|
|
||||||
set_effect(effect='wipe', r=255, g=255, b=40)
|
|
||||||
|
|
||||||
input('Flash red [enter] ')
|
|
||||||
set_effect(effect='flash', r=255, g=0, b=0)
|
|
||||||
rospy.sleep(1)
|
|
||||||
|
|
||||||
input('Rainbow [enter] ')
|
|
||||||
set_effect(effect='rainbow')
|
|
||||||
rospy.sleep(4)
|
|
||||||
|
|
||||||
input('Rainbow fill [enter] ')
|
|
||||||
set_effect(effect='rainbow_fill')
|
|
||||||
rospy.sleep(4)
|
|
||||||
|
|
||||||
input('Turn off [enter] ')
|
|
||||||
set_effect()
|
|
||||||
|
|
||||||
print('== Testing low-level control ==')
|
|
||||||
|
|
||||||
input('Fill orange [enter] ')
|
|
||||||
set_leds(leds=[LEDState(index=i, r=245, g=155, b=0) for i in range(led_count)])
|
|
||||||
|
|
||||||
input('Fill blue gradient [enter] ')
|
|
||||||
set_leds(leds=[LEDState(index=i, r=0, g=20, b=int(255 * i / led_count)) for i in range(led_count)])
|
|
||||||
|
|
||||||
input('Animate green dot [enter] ')
|
|
||||||
set_effect()
|
|
||||||
for i in range(led_count):
|
|
||||||
if i > 0:
|
|
||||||
set_leds(leds=[LEDState(index=i - 1, r=0, g=0, b=0)])
|
|
||||||
set_leds(leds=[LEDState(index=i, r=0, g=255, b=0)])
|
|
||||||
rospy.sleep(0.05)
|
|
||||||
|
|
||||||
input('Turn off [enter] ')
|
|
||||||
set_effect()
|
|
||||||
@@ -1,11 +0,0 @@
|
|||||||
import functools
|
|
||||||
|
|
||||||
# decorator to handle response and print error message
|
|
||||||
def handle_response(fn):
|
|
||||||
@functools.wraps(fn)
|
|
||||||
def wrapper(*args, **kwargs):
|
|
||||||
res = fn(*args, **kwargs)
|
|
||||||
if not res.success:
|
|
||||||
print('\033[91mError:\033[0m {}'.format(res.message))
|
|
||||||
return res
|
|
||||||
return wrapper
|
|
||||||
@@ -22,13 +22,11 @@
|
|||||||
#include <tf2/utils.h>
|
#include <tf2/utils.h>
|
||||||
#include <tf2_ros/transform_listener.h>
|
#include <tf2_ros/transform_listener.h>
|
||||||
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
|
#include <tf2_geometry_msgs/tf2_geometry_msgs.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/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>
|
||||||
#include <clover/FlowConfig.h>
|
|
||||||
|
|
||||||
using cv::Mat;
|
using cv::Mat;
|
||||||
|
|
||||||
@@ -40,7 +38,6 @@ public:
|
|||||||
{}
|
{}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
bool enabled_;
|
|
||||||
ros::Publisher flow_pub_, velo_pub_, shift_pub_;
|
ros::Publisher flow_pub_, velo_pub_, shift_pub_;
|
||||||
ros::Time prev_stamp_;
|
ros::Time prev_stamp_;
|
||||||
std::string fcu_frame_id_, local_frame_id_;
|
std::string fcu_frame_id_, local_frame_id_;
|
||||||
@@ -56,8 +53,6 @@ private:
|
|||||||
std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
|
std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
|
||||||
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_;
|
|
||||||
std::shared_ptr<dynamic_reconfigure::Server<clover::FlowConfig>> dyn_srv_;
|
|
||||||
|
|
||||||
void onInit()
|
void onInit()
|
||||||
{
|
{
|
||||||
@@ -74,25 +69,21 @@ private:
|
|||||||
roi_px_ = nh_priv.param("roi", 128);
|
roi_px_ = nh_priv.param("roi", 128);
|
||||||
roi_rad_ = nh_priv.param("roi_rad", 0.0);
|
roi_rad_ = nh_priv.param("roi_rad", 0.0);
|
||||||
calc_flow_gyro_ = nh_priv.param("calc_flow_gyro", false);
|
calc_flow_gyro_ = nh_priv.param("calc_flow_gyro", false);
|
||||||
flow_gyro_default_ = nh_priv.param("flow_gyro_default", NAN);
|
|
||||||
|
|
||||||
img_pub_ = it_priv.advertise("debug", 1);
|
img_pub_ = it_priv.advertise("debug", 1);
|
||||||
flow_pub_ = nh.advertise<mavros_msgs::OpticalFlowRad>("mavros/px4flow/raw/send", 1);
|
flow_pub_ = nh.advertise<mavros_msgs::OpticalFlowRad>("mavros/px4flow/raw/send", 1);
|
||||||
velo_pub_ = nh_priv.advertise<geometry_msgs::TwistStamped>("angular_velocity", 1);
|
velo_pub_ = nh_priv.advertise<geometry_msgs::TwistStamped>("angular_velocity", 1);
|
||||||
shift_pub_ = nh_priv.advertise<geometry_msgs::Vector3Stamped>("shift", 1);
|
shift_pub_ = nh_priv.advertise<geometry_msgs::Vector3Stamped>("shift", 1);
|
||||||
|
|
||||||
|
flow_.integrated_xgyro = NAN; // no IMU available
|
||||||
|
flow_.integrated_ygyro = NAN;
|
||||||
|
flow_.integrated_zgyro = NAN;
|
||||||
flow_.time_delta_distance_us = 0;
|
flow_.time_delta_distance_us = 0;
|
||||||
flow_.distance = -1; // no distance sensor available
|
flow_.distance = -1; // no distance sensor available
|
||||||
flow_.temperature = 0;
|
flow_.temperature = 0;
|
||||||
|
|
||||||
img_sub_ = it.subscribeCamera("image_raw", 1, &OpticalFlow::flow, this);
|
img_sub_ = it.subscribeCamera("image_raw", 1, &OpticalFlow::flow, this);
|
||||||
|
|
||||||
dyn_srv_ = std::make_shared<dynamic_reconfigure::Server<clover::FlowConfig>>(nh_priv);
|
|
||||||
dynamic_reconfigure::Server<clover::FlowConfig>::CallbackType cb;
|
|
||||||
|
|
||||||
cb = std::bind(&OpticalFlow::paramCallback, this, std::placeholders::_1, std::placeholders::_2);
|
|
||||||
dyn_srv_->setCallback(cb);
|
|
||||||
|
|
||||||
NODELET_INFO("Optical Flow initialized");
|
NODELET_INFO("Optical Flow initialized");
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -119,8 +110,6 @@ private:
|
|||||||
|
|
||||||
void flow(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cinfo)
|
void flow(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cinfo)
|
||||||
{
|
{
|
||||||
if (!enabled_) return;
|
|
||||||
|
|
||||||
parseCameraInfo(cinfo);
|
parseCameraInfo(cinfo);
|
||||||
|
|
||||||
auto img = cv_bridge::toCvShare(msg, "mono8")->image;
|
auto img = cv_bridge::toCvShare(msg, "mono8")->image;
|
||||||
@@ -190,7 +179,7 @@ private:
|
|||||||
double flow_x = atan2(points_undist[0].x, focal_length_x);
|
double flow_x = atan2(points_undist[0].x, focal_length_x);
|
||||||
double flow_y = atan2(points_undist[0].y, focal_length_y);
|
double flow_y = atan2(points_undist[0].y, focal_length_y);
|
||||||
|
|
||||||
// Convert to FCU frame
|
// // Convert to FCU frame
|
||||||
geometry_msgs::Vector3Stamped flow_camera, flow_fcu;
|
geometry_msgs::Vector3Stamped flow_camera, flow_fcu;
|
||||||
flow_camera.header.frame_id = msg->header.frame_id;
|
flow_camera.header.frame_id = msg->header.frame_id;
|
||||||
flow_camera.header.stamp = msg->header.stamp;
|
flow_camera.header.stamp = msg->header.stamp;
|
||||||
@@ -207,11 +196,6 @@ private:
|
|||||||
ros::Duration integration_time = msg->header.stamp - prev_stamp_;
|
ros::Duration integration_time = msg->header.stamp - prev_stamp_;
|
||||||
uint32_t integration_time_us = integration_time.toSec() * 1.0e6;
|
uint32_t integration_time_us = integration_time.toSec() * 1.0e6;
|
||||||
|
|
||||||
// Calculate flow gyro
|
|
||||||
flow_.integrated_xgyro = flow_gyro_default_;
|
|
||||||
flow_.integrated_ygyro = flow_gyro_default_;
|
|
||||||
flow_.integrated_zgyro = flow_gyro_default_;
|
|
||||||
|
|
||||||
if (calc_flow_gyro_) {
|
if (calc_flow_gyro_) {
|
||||||
try {
|
try {
|
||||||
auto flow_gyro_camera = calcFlowGyro(msg->header.frame_id, prev_stamp_, msg->header.stamp);
|
auto flow_gyro_camera = calcFlowGyro(msg->header.frame_id, prev_stamp_, msg->header.stamp);
|
||||||
@@ -221,7 +205,9 @@ private:
|
|||||||
flow_.integrated_ygyro = flow_gyro_fcu.vector.y;
|
flow_.integrated_ygyro = flow_gyro_fcu.vector.y;
|
||||||
flow_.integrated_zgyro = flow_gyro_fcu.vector.z;
|
flow_.integrated_zgyro = flow_gyro_fcu.vector.z;
|
||||||
} catch (const tf2::TransformException& e) {
|
} catch (const tf2::TransformException& e) {
|
||||||
// Transform not available, keep NANs in flow gyro
|
// Invalidate previous frame
|
||||||
|
prev_.release();
|
||||||
|
goto publish_debug;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -236,6 +222,7 @@ private:
|
|||||||
prev_ = curr_.clone();
|
prev_ = curr_.clone();
|
||||||
prev_stamp_ = msg->header.stamp;
|
prev_stamp_ = msg->header.stamp;
|
||||||
|
|
||||||
|
publish_debug:
|
||||||
// Publish debug image
|
// Publish debug image
|
||||||
if (img_pub_.getNumSubscribers() > 0) {
|
if (img_pub_.getNumSubscribers() > 0) {
|
||||||
// publish debug image
|
// publish debug image
|
||||||
@@ -275,14 +262,6 @@ private:
|
|||||||
|
|
||||||
return flow;
|
return flow;
|
||||||
}
|
}
|
||||||
|
|
||||||
void paramCallback(clover::FlowConfig &config, [[maybe_unused]] uint32_t level)
|
|
||||||
{
|
|
||||||
enabled_ = config.enabled;
|
|
||||||
if (!enabled_) {
|
|
||||||
prev_ = Mat(); // clear previous frame
|
|
||||||
}
|
|
||||||
}
|
|
||||||
};
|
};
|
||||||
|
|
||||||
PLUGINLIB_EXPORT_CLASS(OpticalFlow, nodelet::Nodelet)
|
PLUGINLIB_EXPORT_CLASS(OpticalFlow, nodelet::Nodelet)
|
||||||
|
|||||||
@@ -30,7 +30,6 @@ from visualization_msgs.msg import MarkerArray as VisualizationMarkerArray
|
|||||||
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
|
|
||||||
|
|
||||||
|
|
||||||
# TODO: check attitude is present
|
# TODO: check attitude is present
|
||||||
@@ -44,10 +43,6 @@ import locale
|
|||||||
|
|
||||||
rospy.init_node('selfcheck')
|
rospy.init_node('selfcheck')
|
||||||
|
|
||||||
os.environ['ROSCONSOLE_FORMAT']='[${severity}]: ${message}'
|
|
||||||
|
|
||||||
# use user's locale to convert numbers, etc
|
|
||||||
locale.setlocale(locale.LC_ALL, '')
|
|
||||||
|
|
||||||
tf_buffer = tf2_ros.Buffer()
|
tf_buffer = tf2_ros.Buffer()
|
||||||
tf_listener = tf2_ros.TransformListener(tf_buffer)
|
tf_listener = tf2_ros.TransformListener(tf_buffer)
|
||||||
@@ -198,27 +193,24 @@ def check_fcu():
|
|||||||
failure('no connection to the FCU (check wiring)')
|
failure('no connection to the FCU (check wiring)')
|
||||||
return
|
return
|
||||||
|
|
||||||
clover_tag = re.compile(r'-cl[oe]ver\.\d+$')
|
|
||||||
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'):
|
r = re.compile(r'^FW (git tag|version): (v?\d\.\d\.\d.*)$')
|
||||||
if line.startswith('FW version: '):
|
is_clover_firmware = False
|
||||||
info(line[len('FW version: '):])
|
for ver_line in version_str.split('\n'):
|
||||||
elif line.startswith('FW git tag: '): # only Clover's firmware
|
match = r.search(ver_line)
|
||||||
tag = line[len('FW git tag: '):]
|
if match is not None:
|
||||||
clover_fw = clover_tag.search(tag)
|
field, version = match.groups()
|
||||||
info(tag)
|
info('firmware %s: %s' % (field, version))
|
||||||
elif line.startswith('HW arch: '):
|
if 'clover' in version or 'clever' in version:
|
||||||
info(line[len('HW arch: '):])
|
is_clover_firmware = True
|
||||||
|
|
||||||
if not clover_fw:
|
if not is_clover_firmware:
|
||||||
info('not Clover PX4 firmware, check https://clover.coex.tech/firmware')
|
failure('not running Clover PX4 firmware, 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:
|
||||||
@@ -491,12 +483,6 @@ def check_local_position():
|
|||||||
failure('roll is %.2f deg; place copter horizontally or redo level horizon calib',
|
failure('roll is %.2f deg; place copter horizontally or redo level horizon calib',
|
||||||
math.degrees(roll))
|
math.degrees(roll))
|
||||||
|
|
||||||
if not tf_buffer.can_transform('base_link', pose.header.frame_id, rospy.get_rostime(), rospy.Duration(0.5)):
|
|
||||||
failure('can\'t transform from %s to base_link (timeout 0.5 s): is TF enabled?', pose.header.frame_id)
|
|
||||||
|
|
||||||
if not tf_buffer.can_transform('body', pose.header.frame_id, rospy.get_rostime(), rospy.Duration(0.5)):
|
|
||||||
failure('can\'t transform from %s to body (timeout 0.5 s)', pose.header.frame_id)
|
|
||||||
|
|
||||||
except rospy.ROSException:
|
except rospy.ROSException:
|
||||||
failure('no local position')
|
failure('no local position')
|
||||||
|
|
||||||
@@ -626,13 +612,13 @@ def check_boot_duration():
|
|||||||
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])
|
||||||
if duration > 20:
|
if duration > 15:
|
||||||
failure('long Raspbian boot duration: %ss (systemd-analyze for analyzing)', duration)
|
failure('long Raspbian boot duration: %ss (systemd-analyze for analyzing)', duration)
|
||||||
|
|
||||||
|
|
||||||
@check('CPU usage')
|
@check('CPU usage')
|
||||||
def check_cpu_usage():
|
def check_cpu_usage():
|
||||||
WHITELIST = 'nodelet', 'gzclient', 'gzserver'
|
WHITELIST = 'nodelet',
|
||||||
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')
|
||||||
@@ -641,7 +627,7 @@ def check_cpu_usage():
|
|||||||
continue
|
continue
|
||||||
pid, cpu, cmd = process.split('\t')
|
pid, cpu, cmd = process.split('\t')
|
||||||
|
|
||||||
if cmd.strip() not in WHITELIST and locale.atof(cpu) > 30:
|
if cmd.strip() not in WHITELIST and float(cpu) > 30:
|
||||||
failure('high CPU usage (%s%%) detected: %s (PID %s)',
|
failure('high CPU usage (%s%%) detected: %s (PID %s)',
|
||||||
cpu.strip(), cmd.strip(), pid.strip())
|
cpu.strip(), cmd.strip(), pid.strip())
|
||||||
|
|
||||||
@@ -660,22 +646,13 @@ def check_clover_service():
|
|||||||
elif 'failed' in output:
|
elif 'failed' in output:
|
||||||
failure('service failed to run, check your launch-files')
|
failure('service failed to run, check your launch-files')
|
||||||
|
|
||||||
BLACKLIST = 'Unexpected command 520', 'Time jump detected', 'different index:'
|
r = re.compile(r'^(.*)\[(FATAL|ERROR)\] \[\d+.\d+\]: (.*?)(\x1b(.*))?$')
|
||||||
|
|
||||||
r = re.compile(r'^(.*)\[(FATAL|ERROR| WARN)\] \[\d+.\d+\]: (.*?)(\x1b(.*))?$')
|
|
||||||
error_count = OrderedDict()
|
error_count = OrderedDict()
|
||||||
try:
|
try:
|
||||||
for line in open('/tmp/clover.err', 'r'):
|
for line in open('/tmp/clover.err', 'r'):
|
||||||
skip = False
|
|
||||||
for substr in BLACKLIST:
|
|
||||||
if substr in line:
|
|
||||||
skip = True
|
|
||||||
if skip:
|
|
||||||
continue
|
|
||||||
|
|
||||||
node_error = r.search(line)
|
node_error = r.search(line)
|
||||||
if node_error:
|
if node_error:
|
||||||
msg = node_error.groups()[1].strip() + ': ' + node_error.groups()[2]
|
msg = node_error.groups()[1] + ': ' + node_error.groups()[2]
|
||||||
if msg in error_count:
|
if msg in error_count:
|
||||||
error_count[msg] += 1
|
error_count[msg] += 1
|
||||||
else:
|
else:
|
||||||
@@ -746,14 +723,6 @@ def check_network():
|
|||||||
|
|
||||||
@check('RPi health')
|
@check('RPi health')
|
||||||
def check_rpi_health():
|
def check_rpi_health():
|
||||||
try:
|
|
||||||
import shutil
|
|
||||||
total, used, free = shutil.disk_usage('/')
|
|
||||||
if free < 1024 * 1024 * 1024:
|
|
||||||
failure('disk space is less than 1 GB; consider removing logs (~/.ros/log/)')
|
|
||||||
except Exception as e:
|
|
||||||
info('could not check the disk free space: %s', str(e))
|
|
||||||
|
|
||||||
# `vcgencmd get_throttled` output codes taken from
|
# `vcgencmd get_throttled` output codes taken from
|
||||||
# https://github.com/raspberrypi/documentation/blob/JamesH65-patch-vcgencmd-vcdbg-docs/raspbian/applications/vcgencmd.md#get_throttled
|
# https://github.com/raspberrypi/documentation/blob/JamesH65-patch-vcgencmd-vcdbg-docs/raspbian/applications/vcgencmd.md#get_throttled
|
||||||
# TODO: support more base platforms?
|
# TODO: support more base platforms?
|
||||||
@@ -784,7 +753,7 @@ def check_rpi_health():
|
|||||||
# with some of the FLAGs OR'ed together
|
# with some of the FLAGs OR'ed together
|
||||||
output = subprocess.check_output(['vcgencmd', 'get_throttled']).decode()
|
output = subprocess.check_output(['vcgencmd', 'get_throttled']).decode()
|
||||||
except OSError:
|
except OSError:
|
||||||
info('could not call vcgencmd binary; not a Raspberry Pi?')
|
failure('could not call vcgencmd binary; not a Raspberry Pi?')
|
||||||
return
|
return
|
||||||
|
|
||||||
throttle_mask = int(output.split('=')[1], base=16)
|
throttle_mask = int(output.split('=')[1], base=16)
|
||||||
|
|||||||
@@ -61,7 +61,6 @@ std::shared_ptr<tf2_ros::TransformBroadcaster> transform_broadcaster;
|
|||||||
std::shared_ptr<tf2_ros::StaticTransformBroadcaster> static_transform_broadcaster;
|
std::shared_ptr<tf2_ros::StaticTransformBroadcaster> static_transform_broadcaster;
|
||||||
|
|
||||||
// Parameters
|
// Parameters
|
||||||
string mavros;
|
|
||||||
string local_frame;
|
string local_frame;
|
||||||
string fcu_frame;
|
string fcu_frame;
|
||||||
ros::Duration transform_timeout;
|
ros::Duration transform_timeout;
|
||||||
@@ -182,10 +181,9 @@ inline bool waitTransform(const string& target, const string& source,
|
|||||||
ros::spinOnce();
|
ros::spinOnce();
|
||||||
r.sleep();
|
r.sleep();
|
||||||
}
|
}
|
||||||
return false;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#define TIMEOUT(msg, timeout) (msg.header.stamp.isZero() || (ros::Time::now() - msg.header.stamp > timeout))
|
#define TIMEOUT(msg, timeout) (ros::Time::now() - msg.header.stamp > timeout)
|
||||||
|
|
||||||
bool getTelemetry(GetTelemetry::Request& req, GetTelemetry::Response& res)
|
bool getTelemetry(GetTelemetry::Request& req, GetTelemetry::Response& res)
|
||||||
{
|
{
|
||||||
@@ -443,10 +441,6 @@ void publish(const ros::Time stamp)
|
|||||||
|
|
||||||
// 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) {
|
|
||||||
return; // avoid TF_REPEATED_DATA warnings
|
|
||||||
}
|
|
||||||
|
|
||||||
setpoint.transform.translation.x = position_msg.pose.position.x;
|
setpoint.transform.translation.x = position_msg.pose.position.x;
|
||||||
setpoint.transform.translation.y = position_msg.pose.position.y;
|
setpoint.transform.translation.y = position_msg.pose.position.y;
|
||||||
setpoint.transform.translation.z = position_msg.pose.position.z;
|
setpoint.transform.translation.z = position_msg.pose.position.z;
|
||||||
@@ -503,10 +497,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
|
||||||
[[maybe_unused]] const uint8_t SWITCH_POS_NONE = 0; // switch is not mapped
|
const uint8_t SWITCH_POS_NONE = 0; // switch is not mapped
|
||||||
[[maybe_unused]] const uint8_t SWITCH_POS_ON = 1; // switch activated
|
const uint8_t SWITCH_POS_ON = 1; // switch activated
|
||||||
[[maybe_unused]] const uint8_t SWITCH_POS_MIDDLE = 2; // middle position
|
const uint8_t SWITCH_POS_MIDDLE = 2; // middle position
|
||||||
[[maybe_unused]] const uint8_t SWITCH_POS_OFF = 3; // switch not activated
|
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;
|
||||||
@@ -691,7 +685,7 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
|
|||||||
// }
|
// }
|
||||||
|
|
||||||
if (sp_type == POSITION || sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL || sp_type == VELOCITY || sp_type == ATTITUDE) {
|
if (sp_type == POSITION || sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL || sp_type == VELOCITY || sp_type == ATTITUDE) {
|
||||||
// destination point and/or attitude
|
// destination point and/or yaw
|
||||||
PoseStamped ps;
|
PoseStamped ps;
|
||||||
ps.header.frame_id = frame_id;
|
ps.header.frame_id = frame_id;
|
||||||
ps.header.stamp = stamp;
|
ps.header.stamp = stamp;
|
||||||
@@ -700,12 +694,7 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
|
|||||||
ps.pose.position.z = z;
|
ps.pose.position.z = z;
|
||||||
ps.pose.orientation.w = 1.0; // Ensure quaternion is always valid
|
ps.pose.orientation.w = 1.0; // Ensure quaternion is always valid
|
||||||
|
|
||||||
if (sp_type == ATTITUDE) {
|
if (std::isnan(yaw)) {
|
||||||
ps.pose.position.x = 0;
|
|
||||||
ps.pose.position.y = 0;
|
|
||||||
ps.pose.position.z = 0;
|
|
||||||
ps.pose.orientation = tf::createQuaternionMsgFromRollPitchYaw(roll, pitch, yaw);
|
|
||||||
} else if (std::isnan(yaw)) {
|
|
||||||
setpoint_yaw_type = YAW_RATE;
|
setpoint_yaw_type = YAW_RATE;
|
||||||
setpoint_yaw_rate = yaw_rate;
|
setpoint_yaw_rate = yaw_rate;
|
||||||
} else if (std::isinf(yaw) && yaw > 0) {
|
} else if (std::isinf(yaw) && yaw > 0) {
|
||||||
@@ -808,7 +797,7 @@ bool setRates(SetRates::Request& req, SetRates::Response& res) {
|
|||||||
return serve(RATES, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, req.pitch_rate, req.roll_rate, req.yaw_rate, NAN, NAN, req.thrust, NAN, "", req.auto_arm, res.success, res.message);
|
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([[maybe_unused]] std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
|
bool land(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
|
||||||
{
|
{
|
||||||
try {
|
try {
|
||||||
if (busy)
|
if (busy)
|
||||||
@@ -854,7 +843,6 @@ bool land([[maybe_unused]] std_srvs::Trigger::Request& req, std_srvs::Trigger::R
|
|||||||
busy = false;
|
busy = false;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
return false;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
int main(int argc, char **argv)
|
int main(int argc, char **argv)
|
||||||
@@ -867,9 +855,8 @@ int main(int argc, char **argv)
|
|||||||
static_transform_broadcaster = std::make_shared<tf2_ros::StaticTransformBroadcaster>();
|
static_transform_broadcaster = std::make_shared<tf2_ros::StaticTransformBroadcaster>();
|
||||||
|
|
||||||
// Params
|
// Params
|
||||||
nh_priv.param("mavros", mavros, string("mavros")); // for case of using multiple connections
|
nh.param<string>("mavros/local_position/tf/frame_id", local_frame, "map");
|
||||||
nh.param<string>(mavros + "/local_position/tf/frame_id", local_frame, "map");
|
nh.param<string>("mavros/local_position/tf/child_frame_id", fcu_frame, "base_link");
|
||||||
nh.param<string>(mavros + "/local_position/tf/child_frame_id", fcu_frame, "base_link");
|
|
||||||
nh_priv.param("target_frame", target.child_frame_id, string("navigate_target"));
|
nh_priv.param("target_frame", target.child_frame_id, string("navigate_target"));
|
||||||
nh_priv.param("setpoint", setpoint.child_frame_id, string("setpoint"));
|
nh_priv.param("setpoint", setpoint.child_frame_id, string("setpoint"));
|
||||||
nh_priv.param("auto_release", auto_release, true);
|
nh_priv.param("auto_release", auto_release, true);
|
||||||
@@ -880,13 +867,6 @@ int main(int argc, char **argv)
|
|||||||
nh_priv.param<string>("body_frame", body.child_frame_id, "body");
|
nh_priv.param<string>("body_frame", body.child_frame_id, "body");
|
||||||
nh_priv.getParam("reference_frames", reference_frames);
|
nh_priv.getParam("reference_frames", reference_frames);
|
||||||
|
|
||||||
// Default reference frames
|
|
||||||
std::map<string, string> default_reference_frames;
|
|
||||||
default_reference_frames[body.child_frame_id] = local_frame;
|
|
||||||
default_reference_frames[fcu_frame] = local_frame;
|
|
||||||
if (!target.child_frame_id.empty()) default_reference_frames[target.child_frame_id] = local_frame;
|
|
||||||
reference_frames.insert(default_reference_frames.begin(), default_reference_frames.end()); // merge defaults
|
|
||||||
|
|
||||||
state_timeout = ros::Duration(nh_priv.param("state_timeout", 3.0));
|
state_timeout = ros::Duration(nh_priv.param("state_timeout", 3.0));
|
||||||
local_position_timeout = ros::Duration(nh_priv.param("local_position_timeout", 2.0));
|
local_position_timeout = ros::Duration(nh_priv.param("local_position_timeout", 2.0));
|
||||||
velocity_timeout = ros::Duration(nh_priv.param("velocity_timeout", 2.0));
|
velocity_timeout = ros::Duration(nh_priv.param("velocity_timeout", 2.0));
|
||||||
@@ -901,25 +881,25 @@ int main(int argc, char **argv)
|
|||||||
arming_timeout = ros::Duration(nh_priv.param("arming_timeout", 4.0));
|
arming_timeout = ros::Duration(nh_priv.param("arming_timeout", 4.0));
|
||||||
|
|
||||||
// Service clients
|
// Service clients
|
||||||
arming = nh.serviceClient<mavros_msgs::CommandBool>(mavros + "/cmd/arming");
|
arming = nh.serviceClient<mavros_msgs::CommandBool>("mavros/cmd/arming");
|
||||||
set_mode = nh.serviceClient<mavros_msgs::SetMode>(mavros + "/set_mode");
|
set_mode = nh.serviceClient<mavros_msgs::SetMode>("mavros/set_mode");
|
||||||
|
|
||||||
// Telemetry subscribers
|
// Telemetry subscribers
|
||||||
auto state_sub = nh.subscribe(mavros + "/state", 1, &handleState);
|
auto state_sub = nh.subscribe("mavros/state", 1, &handleState);
|
||||||
auto velocity_sub = nh.subscribe(mavros + "/local_position/velocity_body", 1, &handleMessage<TwistStamped, velocity>);
|
auto velocity_sub = nh.subscribe("mavros/local_position/velocity_body", 1, &handleMessage<TwistStamped, velocity>);
|
||||||
auto global_position_sub = nh.subscribe(mavros + "/global_position/global", 1, &handleMessage<NavSatFix, global_position>);
|
auto global_position_sub = nh.subscribe("mavros/global_position/global", 1, &handleMessage<NavSatFix, global_position>);
|
||||||
auto battery_sub = nh.subscribe(mavros + "/battery", 1, &handleMessage<BatteryState, battery>);
|
auto battery_sub = nh.subscribe("mavros/battery", 1, &handleMessage<BatteryState, battery>);
|
||||||
auto statustext_sub = nh.subscribe(mavros + "/statustext/recv", 1, &handleMessage<mavros_msgs::StatusText, statustext>);
|
auto statustext_sub = nh.subscribe("mavros/statustext/recv", 1, &handleMessage<mavros_msgs::StatusText, statustext>);
|
||||||
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);
|
||||||
|
|
||||||
// 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);
|
||||||
attitude_pub = nh.advertise<PoseStamped>(mavros + "/setpoint_attitude/attitude", 1);
|
attitude_pub = nh.advertise<PoseStamped>("mavros/setpoint_attitude/attitude", 1);
|
||||||
attitude_raw_pub = nh.advertise<AttitudeTarget>(mavros + "/setpoint_raw/attitude", 1);
|
attitude_raw_pub = nh.advertise<AttitudeTarget>("mavros/setpoint_raw/attitude", 1);
|
||||||
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);
|
||||||
|
|
||||||
// Service servers
|
// Service servers
|
||||||
auto gt_serv = nh.advertiseService("get_telemetry", &getTelemetry);
|
auto gt_serv = nh.advertiseService("get_telemetry", &getTelemetry);
|
||||||
|
|||||||
@@ -38,9 +38,9 @@ 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_timout) return; // have vpe
|
if (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_timout) { // have local position
|
if (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([[maybe_unused]] std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
|
bool reset(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
|
||||||
{
|
{
|
||||||
reset_flag = true;
|
reset_flag = true;
|
||||||
res.success = true;
|
res.success = true;
|
||||||
@@ -141,11 +141,11 @@ int main(int argc, char **argv) {
|
|||||||
vpe_pub = nh_priv.advertise<PoseStamped>("vpe", 1);
|
vpe_pub = nh_priv.advertise<PoseStamped>("vpe", 1);
|
||||||
//vpe_cov_pub = nh_priv_.advertise<PoseStamped>("pose_cov_pub", 1);
|
//vpe_cov_pub = nh_priv_.advertise<PoseStamped>("pose_cov_pub", 1);
|
||||||
|
|
||||||
if (nh_priv.param("force_init", false) || nh_priv.param("publish_zero", false)) { // publish_zero is old name
|
if (nh_priv.param("publish_zero", false)) {
|
||||||
// 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_timout = ros::Duration(nh_priv.param("force_init_timeout", 5.0));
|
publish_zero_timout = ros::Duration(nh_priv.param("publish_zero_timout", 5.0));
|
||||||
publish_zero_duration = ros::Duration(nh_priv.param("force_init_duration", 5.0));
|
publish_zero_duration = ros::Duration(nh_priv.param("publish_zero_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);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -33,29 +33,3 @@ def test_web_video_server(node):
|
|||||||
# Python 3
|
# Python 3
|
||||||
import urllib.request as urllib
|
import urllib.request as urllib
|
||||||
urllib.urlopen("http://localhost:8080").read()
|
urllib.urlopen("http://localhost:8080").read()
|
||||||
|
|
||||||
def test_blocks(node):
|
|
||||||
rospy.wait_for_service('clover_blocks/run', timeout=5)
|
|
||||||
rospy.wait_for_service('clover_blocks/stop', timeout=5)
|
|
||||||
rospy.wait_for_service('clover_blocks/load', timeout=5)
|
|
||||||
rospy.wait_for_service('clover_blocks/store', timeout=5)
|
|
||||||
|
|
||||||
from std_msgs.msg import String
|
|
||||||
from clover_blocks.srv import Run
|
|
||||||
|
|
||||||
def wait_print():
|
|
||||||
try:
|
|
||||||
wait_print.result = rospy.wait_for_message('clover_blocks/print', String, timeout=5).data
|
|
||||||
except Exception as e:
|
|
||||||
wait_print.result = str(e)
|
|
||||||
|
|
||||||
import threading
|
|
||||||
t = threading.Thread(target=wait_print)
|
|
||||||
t.start()
|
|
||||||
rospy.sleep(0.1)
|
|
||||||
|
|
||||||
run = rospy.ServiceProxy('clover_blocks/run', Run)
|
|
||||||
assert run(code='print("test")').success == True
|
|
||||||
|
|
||||||
t.join()
|
|
||||||
assert wait_print.result == 'test'
|
|
||||||
|
|||||||
@@ -23,7 +23,10 @@
|
|||||||
|
|
||||||
<node pkg="tf2_ros" type="static_transform_publisher" name="map_flipped_frame" args="0 0 0 3.1415926 3.1415926 0 map map_flipped" required="true"/>
|
<node pkg="tf2_ros" type="static_transform_publisher" name="map_flipped_frame" args="0 0 0 3.1415926 3.1415926 0 map map_flipped" required="true"/>
|
||||||
|
|
||||||
<node name="simple_offboard" pkg="clover" type="simple_offboard" required="true" output="screen"/>
|
<node name="simple_offboard" pkg="clover" type="simple_offboard" required="true" output="screen">
|
||||||
|
<param name="reference_frames/body" value="map"/>
|
||||||
|
<param name="reference_frames/base_link" value="map"/>
|
||||||
|
</node>
|
||||||
|
|
||||||
<node name="tf2_web_republisher" pkg="tf2_web_republisher" type="tf2_web_republisher" required="true"/>
|
<node name="tf2_web_republisher" pkg="tf2_web_republisher" type="tf2_web_republisher" required="true"/>
|
||||||
|
|
||||||
@@ -35,8 +38,6 @@
|
|||||||
<rosparam param="notify">startup: { r: 255, g: 255, b: 255 }</rosparam>
|
<rosparam param="notify">startup: { r: 255, g: 255, b: 255 }</rosparam>
|
||||||
</node>
|
</node>
|
||||||
|
|
||||||
<node name="clover_blocks" pkg="clover_blocks" type="clover_blocks" output="screen" 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>
|
||||||
|
|||||||
1
clover/www/clover.err
Symbolic link
1
clover/www/clover.err
Symbolic link
@@ -0,0 +1 @@
|
|||||||
|
/tmp/clover.err
|
||||||
@@ -1 +0,0 @@
|
|||||||
/var/log/clover.log
|
|
||||||
@@ -1,23 +0,0 @@
|
|||||||
<h1>
|
|
||||||
/var/log/clover.log
|
|
||||||
<a style="font-size: 0.5em; vertical-align: super; font-weight: normal" href="clover.log" download>download</a>
|
|
||||||
</h1>
|
|
||||||
|
|
||||||
<pre></pre>
|
|
||||||
|
|
||||||
<script type="module">
|
|
||||||
var pre = document.querySelector('pre');
|
|
||||||
|
|
||||||
fetch('clover.log?' + Math.random()).then(function(response) { // random to forbid caching
|
|
||||||
if (response.status == 404) {
|
|
||||||
pre.innerHTML = '/var/log/clover.log does not exist';
|
|
||||||
return;
|
|
||||||
} else if (response.status !== 200) {
|
|
||||||
pre.innerHTML('Error ' + response.status);
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
response.text().then(function(content) {
|
|
||||||
pre.innerHTML = content;
|
|
||||||
});
|
|
||||||
});
|
|
||||||
</script>
|
|
||||||
@@ -4,12 +4,12 @@
|
|||||||
|
|
||||||
<ul>
|
<ul>
|
||||||
<li><a href="docs">View documentation</a> (snapshot of <a href="https://clover.coex.tech">clover.coex.tech</a>)</li>
|
<li><a href="docs">View documentation</a> (snapshot of <a href="https://clover.coex.tech">clover.coex.tech</a>)</li>
|
||||||
<li><a href="topics.html">View topics</a></li>
|
|
||||||
<li><a href="" id="wvs">View image topics</a> (<code>web_video_server</code>)</li>
|
<li><a href="" id="wvs">View image topics</a> (<code>web_video_server</code>)</li>
|
||||||
<li><a href="" id="butterfly">Open web terminal</a> (<code>Butterfly</code>)</li>
|
<li><a href="" id="butterfly">Open web terminal</a> (<code>Butterfly</code>)</li>
|
||||||
<li>View <a href="viz.html">View 3D visualization</a>, <a href="aruco_map.html">3D visualization for markers map</a> (<code>ros3djs</code>)</li>
|
<li><a href="viz.html">View 3D visualization</a> (<code>ros3djs</code>)</li>
|
||||||
|
<li><a href="aruco_map.html">3D visualization for markers map</a> (<code>ros3djs</code>)</li>
|
||||||
<li><a href="../clover_blocks/">Blocks programming</a> (<code>Blockly</code>)</li>
|
<li><a href="../clover_blocks/">Blocks programming</a> (<code>Blockly</code>)</li>
|
||||||
<li><a href="console.html">Clover console</a> (<code>/var/log/clover.log</code>)</li>
|
<li><a href="clover.err">Clover console</a> (<code>/tmp/clover.err</code>)</li>
|
||||||
</ul>
|
</ul>
|
||||||
|
|
||||||
<div class="version"></div>
|
<div class="version"></div>
|
||||||
@@ -18,14 +18,6 @@
|
|||||||
document.querySelector("#wvs").href = location.protocol + '//' + location.hostname + ':8080';
|
document.querySelector("#wvs").href = location.protocol + '//' + location.hostname + ':8080';
|
||||||
document.querySelector("#butterfly").href = location.protocol + '//' + location.hostname + ':57575';
|
document.querySelector("#butterfly").href = location.protocol + '//' + location.hostname + ':57575';
|
||||||
|
|
||||||
document.querySelector("#butterfly").addEventListener('click', function(e) {
|
|
||||||
if (location.hostname == 'localhost' || location.hostname == '127.0.0.1') {
|
|
||||||
if (!confirm('Please use regular Terminal app on a local machine.\nClick OK to proceed to Butterfly anyway.')) {
|
|
||||||
e.preventDefault();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
});
|
|
||||||
|
|
||||||
// Determine image version
|
// Determine image version
|
||||||
fetch('clover_version').then(function(response) {
|
fetch('clover_version').then(function(response) {
|
||||||
if (response.status !== 200) return;
|
if (response.status !== 200) return;
|
||||||
|
|||||||
@@ -1,236 +0,0 @@
|
|||||||
// Browserified https://www.npmjs.com/package/json-to-pretty-yaml module
|
|
||||||
|
|
||||||
(function(){function r(e,n,t){function o(i,f){if(!n[i]){if(!e[i]){var c="function"==typeof require&&require;if(!f&&c)return c(i,!0);if(u)return u(i,!0);var a=new Error("Cannot find module '"+i+"'");throw a.code="MODULE_NOT_FOUND",a}var p=n[i]={exports:{}};e[i][0].call(p.exports,function(r){var n=e[i][1][r];return o(n||r)},p,p.exports,r,e,n,t)}return n[i].exports}for(var u="function"==typeof require&&require,i=0;i<t.length;i++)o(t[i]);return o}return r})()({1:[function(require,module,exports){
|
|
||||||
(function() {
|
|
||||||
"use strict";
|
|
||||||
|
|
||||||
var typeOf = require('remedial').typeOf;
|
|
||||||
var trimWhitespace = require('remove-trailing-spaces');
|
|
||||||
|
|
||||||
function stringify(data) {
|
|
||||||
var handlers, indentLevel = '';
|
|
||||||
|
|
||||||
handlers = {
|
|
||||||
"undefined": function() {
|
|
||||||
// objects will not have `undefined` converted to `null`
|
|
||||||
// as this may have unintended consequences
|
|
||||||
// For arrays, however, this behavior seems appropriate
|
|
||||||
return 'null';
|
|
||||||
},
|
|
||||||
"null": function() {
|
|
||||||
return 'null';
|
|
||||||
},
|
|
||||||
"number": function(x) {
|
|
||||||
return x;
|
|
||||||
},
|
|
||||||
"boolean": function(x) {
|
|
||||||
return x ? 'true' : 'false';
|
|
||||||
},
|
|
||||||
"string": function(x) {
|
|
||||||
// to avoid the string "true" being confused with the
|
|
||||||
// the literal `true`, we always wrap strings in quotes
|
|
||||||
return JSON.stringify(x);
|
|
||||||
},
|
|
||||||
"array": function(x) {
|
|
||||||
var output = '';
|
|
||||||
|
|
||||||
if (0 === x.length) {
|
|
||||||
output += '[]';
|
|
||||||
return output;
|
|
||||||
}
|
|
||||||
|
|
||||||
indentLevel = indentLevel.replace(/$/, ' ');
|
|
||||||
x.forEach(function(y, i) {
|
|
||||||
// TODO how should `undefined` be handled?
|
|
||||||
var handler = handlers[typeOf(y)];
|
|
||||||
|
|
||||||
if (!handler) {
|
|
||||||
throw new Error('what the crap: ' + typeOf(y));
|
|
||||||
}
|
|
||||||
|
|
||||||
output += '\n' + indentLevel + '- ' + handler(y, true);
|
|
||||||
|
|
||||||
});
|
|
||||||
indentLevel = indentLevel.replace(/ /, '');
|
|
||||||
|
|
||||||
return output;
|
|
||||||
},
|
|
||||||
"object": function(x, inArray, rootNode) {
|
|
||||||
var output = '';
|
|
||||||
|
|
||||||
if (0 === Object.keys(x).length) {
|
|
||||||
output += '{}';
|
|
||||||
return output;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!rootNode) {
|
|
||||||
indentLevel = indentLevel.replace(/$/, ' ');
|
|
||||||
}
|
|
||||||
|
|
||||||
Object.keys(x).forEach(function(k, i) {
|
|
||||||
var val = x[k],
|
|
||||||
handler = handlers[typeOf(val)];
|
|
||||||
|
|
||||||
if ('undefined' === typeof val) {
|
|
||||||
// the user should do
|
|
||||||
// delete obj.key
|
|
||||||
// and not
|
|
||||||
// obj.key = undefined
|
|
||||||
// but we'll error on the side of caution
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!handler) {
|
|
||||||
throw new Error('what the crap: ' + typeOf(val));
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!(inArray && i === 0)) {
|
|
||||||
output += '\n' + indentLevel;
|
|
||||||
}
|
|
||||||
|
|
||||||
output += k + ': ' + handler(val);
|
|
||||||
});
|
|
||||||
indentLevel = indentLevel.replace(/ /, '');
|
|
||||||
|
|
||||||
return output;
|
|
||||||
},
|
|
||||||
"function": function() {
|
|
||||||
// TODO this should throw or otherwise be ignored
|
|
||||||
return '[object Function]';
|
|
||||||
}
|
|
||||||
};
|
|
||||||
return trimWhitespace(handlers[typeOf(data)](data, true, true) + '\n');
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
window.yamlStringify = stringify;
|
|
||||||
module.exports.stringify = stringify;
|
|
||||||
}());
|
|
||||||
|
|
||||||
},{"remedial":2,"remove-trailing-spaces":3}],2:[function(require,module,exports){
|
|
||||||
/*jslint onevar: true, undef: true, nomen: true, eqeqeq: true, plusplus: true, bitwise: true, regexp: true, newcap: true, immed: true */
|
|
||||||
(function () {
|
|
||||||
"use strict";
|
|
||||||
|
|
||||||
var global = Function('return this')()
|
|
||||||
, classes = "Boolean Number String Function Array Date RegExp Object".split(" ")
|
|
||||||
, i
|
|
||||||
, name
|
|
||||||
, class2type = {}
|
|
||||||
;
|
|
||||||
|
|
||||||
for (i in classes) {
|
|
||||||
if (classes.hasOwnProperty(i)) {
|
|
||||||
name = classes[i];
|
|
||||||
class2type["[object " + name + "]"] = name.toLowerCase();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
function typeOf(obj) {
|
|
||||||
return (null === obj || undefined === obj) ? String(obj) : class2type[Object.prototype.toString.call(obj)] || "object";
|
|
||||||
}
|
|
||||||
|
|
||||||
function isEmpty(o) {
|
|
||||||
var i, v;
|
|
||||||
if (typeOf(o) === 'object') {
|
|
||||||
for (i in o) { // fails jslint
|
|
||||||
v = o[i];
|
|
||||||
if (v !== undefined && typeOf(v) !== 'function') {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!String.prototype.entityify) {
|
|
||||||
String.prototype.entityify = function () {
|
|
||||||
return this.replace(/&/g, "&").replace(/</g,
|
|
||||||
"<").replace(/>/g, ">");
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!String.prototype.quote) {
|
|
||||||
String.prototype.quote = function () {
|
|
||||||
var c, i, l = this.length, o = '"';
|
|
||||||
for (i = 0; i < l; i += 1) {
|
|
||||||
c = this.charAt(i);
|
|
||||||
if (c >= ' ') {
|
|
||||||
if (c === '\\' || c === '"') {
|
|
||||||
o += '\\';
|
|
||||||
}
|
|
||||||
o += c;
|
|
||||||
} else {
|
|
||||||
switch (c) {
|
|
||||||
case '\b':
|
|
||||||
o += '\\b';
|
|
||||||
break;
|
|
||||||
case '\f':
|
|
||||||
o += '\\f';
|
|
||||||
break;
|
|
||||||
case '\n':
|
|
||||||
o += '\\n';
|
|
||||||
break;
|
|
||||||
case '\r':
|
|
||||||
o += '\\r';
|
|
||||||
break;
|
|
||||||
case '\t':
|
|
||||||
o += '\\t';
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
c = c.charCodeAt();
|
|
||||||
o += '\\u00' + Math.floor(c / 16).toString(16) +
|
|
||||||
(c % 16).toString(16);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
return o + '"';
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!String.prototype.supplant) {
|
|
||||||
String.prototype.supplant = function (o) {
|
|
||||||
return this.replace(/{([^{}]*)}/g,
|
|
||||||
function (a, b) {
|
|
||||||
var r = o[b];
|
|
||||||
return typeof r === 'string' || typeof r === 'number' ? r : a;
|
|
||||||
}
|
|
||||||
);
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!String.prototype.trim) {
|
|
||||||
String.prototype.trim = function () {
|
|
||||||
return this.replace(/^\s*(\S*(?:\s+\S+)*)\s*$/, "$1");
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
// CommonJS / npm / Ender.JS
|
|
||||||
module.exports = {
|
|
||||||
typeOf: typeOf,
|
|
||||||
isEmpty: isEmpty
|
|
||||||
};
|
|
||||||
global.typeOf = global.typeOf || typeOf;
|
|
||||||
global.isEmpty = global.isEmpty || isEmpty;
|
|
||||||
}());
|
|
||||||
|
|
||||||
},{}],3:[function(require,module,exports){
|
|
||||||
"use strict";
|
|
||||||
|
|
||||||
/**
|
|
||||||
* removeTrailingSpaces
|
|
||||||
* Remove the trailing spaces from a string.
|
|
||||||
*
|
|
||||||
* @name removeTrailingSpaces
|
|
||||||
* @function
|
|
||||||
* @param {String} input The input string.
|
|
||||||
* @returns {String} The output string.
|
|
||||||
*/
|
|
||||||
|
|
||||||
module.exports = function removeTrailingSpaces(input) {
|
|
||||||
// TODO If possible, use a regex
|
|
||||||
return input.split("\n").map(function (x) {
|
|
||||||
return x.trimRight();
|
|
||||||
}).join("\n");
|
|
||||||
};
|
|
||||||
},{}]},{},[1]);
|
|
||||||
@@ -1,83 +0,0 @@
|
|||||||
const url = 'ws://' + location.hostname + ':9090';
|
|
||||||
const ros = new ROSLIB.Ros({ url: url });
|
|
||||||
const params = Object.fromEntries(new URLSearchParams(window.location.search).entries());
|
|
||||||
|
|
||||||
ros.on('connection', function () {
|
|
||||||
document.body.classList.add('connected');
|
|
||||||
document.body.classList.remove('closed');
|
|
||||||
init();
|
|
||||||
});
|
|
||||||
|
|
||||||
ros.on('close', function () {
|
|
||||||
document.body.classList.remove('connected');
|
|
||||||
document.body.classList.add('closed');
|
|
||||||
setTimeout(function() {
|
|
||||||
// reconnect
|
|
||||||
ros.connect(url);
|
|
||||||
}, 2000);
|
|
||||||
});
|
|
||||||
|
|
||||||
const title = document.querySelector('h1');
|
|
||||||
const topicsList = document.querySelector('#topics');
|
|
||||||
const topicMessage = document.querySelector('#topic-message');
|
|
||||||
|
|
||||||
function viewTopicsList() {
|
|
||||||
title.innerHTML = 'Topics:';
|
|
||||||
|
|
||||||
ros.getTopics(function(topics) {
|
|
||||||
topicsList.innerHTML = topics.topics.map(function(topic, i) {
|
|
||||||
const type = topics.types[i];
|
|
||||||
if (type == 'sensor_msgs/Image') {
|
|
||||||
let url = `${location.protocol}//${location.hostname}:8080/stream_viewer?topic=${topic}`;
|
|
||||||
return `<li><a href="${url}" class=topic title=${type}>${topic}</a> 🖼</li>`;
|
|
||||||
} else {
|
|
||||||
return `<li><a href="?topic=${topic}" class=topic title=${type}>${topic}</a></li>`;
|
|
||||||
}
|
|
||||||
}).join('');
|
|
||||||
});
|
|
||||||
}
|
|
||||||
|
|
||||||
let rosdistro;
|
|
||||||
|
|
||||||
function viewTopic(topic) {
|
|
||||||
let index = '<a href=topics.html>Topics</a>';
|
|
||||||
title.innerHTML = `${index}: ${topic}`;
|
|
||||||
topicMessage.style.display = 'block';
|
|
||||||
|
|
||||||
ros.getTopicType(topic, function(typeStr) {
|
|
||||||
const [pack, type] = typeStr.split('/');
|
|
||||||
let href = `https://docs.ros.org/en/${rosdistro}/api/${pack}/html/msg/${type}.html`;
|
|
||||||
title.innerHTML = `${index}: ${topic} <a id="topic-type" href=${href} target="_blank">${typeStr}</a>`;
|
|
||||||
});
|
|
||||||
|
|
||||||
new ROSLIB.Topic({ ros: ros, name: topic }).subscribe(function(msg) {
|
|
||||||
document.title = topic;
|
|
||||||
if (mouseDown) return;
|
|
||||||
|
|
||||||
if (msg.header.stamp) {
|
|
||||||
if (params.date || params.offset) {
|
|
||||||
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.offset) msg.header.offset = (new Date() - date) * 1e-3;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
topicMessage.innerHTML = yamlStringify(msg); // JSON.stringify(msg, null, 4);
|
|
||||||
});
|
|
||||||
}
|
|
||||||
|
|
||||||
let mouseDown;
|
|
||||||
|
|
||||||
topicMessage.addEventListener('mousedown', function() { mouseDown = true; });
|
|
||||||
topicMessage.addEventListener('mouseup', function() { mouseDown = false; });
|
|
||||||
|
|
||||||
function init() {
|
|
||||||
if (!params.topic) {
|
|
||||||
viewTopicsList();
|
|
||||||
} else {
|
|
||||||
new ROSLIB.Param({ ros: ros, name: '/rosdistro'}).get(function(value) {
|
|
||||||
rosdistro = value.trim();
|
|
||||||
viewTopic(params.topic);
|
|
||||||
});
|
|
||||||
}
|
|
||||||
}
|
|
||||||
@@ -1,28 +0,0 @@
|
|||||||
<html lang="en">
|
|
||||||
<head>
|
|
||||||
<title>ROS topics</title>
|
|
||||||
<script src="js/roslib.js"></script>
|
|
||||||
<link rel="icon" href="data:,"> <!-- make chrome don't request icon -->
|
|
||||||
<script type="module" src="js/topics.js"></script>
|
|
||||||
<script src="js/json-to-pretty-yaml.js"></script>
|
|
||||||
<style>
|
|
||||||
#topics { line-height: 1.2em; }
|
|
||||||
#topic-view {
|
|
||||||
display: none;
|
|
||||||
}
|
|
||||||
#topic-message {
|
|
||||||
display: none;
|
|
||||||
white-space: pre;
|
|
||||||
font-family: monospace;
|
|
||||||
}
|
|
||||||
#topic-type { font-family: monospace; font-size: 0.5em; vertical-align: super; font-weight: normal; }
|
|
||||||
.topic { font-family: monospace; }
|
|
||||||
body.closed { background-color: rgb(207, 207, 207); }
|
|
||||||
</style>
|
|
||||||
</head>
|
|
||||||
<body>
|
|
||||||
<h1> </h1>
|
|
||||||
<ul id="topics"></ul>
|
|
||||||
<code id="topic-message">No messages received</code>
|
|
||||||
</body>
|
|
||||||
</html>
|
|
||||||
@@ -78,8 +78,6 @@ install(DIRECTORY programs
|
|||||||
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
|
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
|
||||||
)
|
)
|
||||||
|
|
||||||
install(DIRECTORY www DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
|
|
||||||
|
|
||||||
#############
|
#############
|
||||||
## Testing ##
|
## Testing ##
|
||||||
#############
|
#############
|
||||||
|
|||||||
@@ -10,7 +10,7 @@ Internal package documentation is given below.
|
|||||||
|
|
||||||
## Frontend
|
## Frontend
|
||||||
|
|
||||||
The frontend files are located in [`www`](./www/) subdirectory. The frontend application uses [`roslib.js`](http://wiki.ros.org/roslibjs) library for communicating with backend node and other ROS resources.
|
The frontend files are located in [`www`](./www/) subdirectory. The frontend application uses [`roblib.js`](http://wiki.ros.org/roslibjs) library for communicating with backend node and other ROS resources.
|
||||||
|
|
||||||
## `clover_blocks` node
|
## `clover_blocks` node
|
||||||
|
|
||||||
@@ -30,8 +30,7 @@ The frontend files are located in [`www`](./www/) subdirectory. The frontend app
|
|||||||
Parameters read by frontend:
|
Parameters read by frontend:
|
||||||
|
|
||||||
* `~navigate_tolerance` (*float*) – distance tolerance in meters, used for navigate-like blocks (default: 0.2).
|
* `~navigate_tolerance` (*float*) – distance tolerance in meters, used for navigate-like blocks (default: 0.2).
|
||||||
* `~navigate_global_tolerance` (*float*) – distance tolerance for global coordinates navigation (default: 1).
|
* `~yaw_tolerance` (*float*) – yaw angle tolerance in degrees, used in set_yaw block (default: 20).
|
||||||
* `~yaw_tolerance` (*float*) – yaw angle tolerance in degrees, used in set_yaw block (default: 1).
|
|
||||||
* `~sleep_time` (*float*) – duration of sleep in loop cycles, used for navigate-like blocks (default: 0.2).
|
* `~sleep_time` (*float*) – duration of sleep in loop cycles, used for navigate-like blocks (default: 0.2).
|
||||||
* `~confirm_run` (*bool*) – enable confirmation to run the program (default: true).
|
* `~confirm_run` (*bool*) – enable confirmation to run the program (default: true).
|
||||||
|
|
||||||
|
|||||||
@@ -1,7 +1,7 @@
|
|||||||
<?xml version="1.0"?>
|
<?xml version="1.0"?>
|
||||||
<package format="2">
|
<package format="2">
|
||||||
<name>clover_blocks</name>
|
<name>clover_blocks</name>
|
||||||
<version>0.23.0</version>
|
<version>0.21.1</version>
|
||||||
<description>Blockly programming support for Clover</description>
|
<description>Blockly programming support for Clover</description>
|
||||||
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>
|
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>
|
||||||
<license>MIT</license>
|
<license>MIT</license>
|
||||||
|
|||||||
@@ -31,14 +31,6 @@ function considerFrameId(e) {
|
|||||||
this.getInput('Y').fieldRow[0].setValue('y');
|
this.getInput('Y').fieldRow[0].setValue('y');
|
||||||
this.getInput('Z').fieldRow[0].setValue('z');
|
this.getInput('Z').fieldRow[0].setValue('z');
|
||||||
}
|
}
|
||||||
if (this.getInput('LAT')) { // block has global coordinates
|
|
||||||
let global = frameId.startsWith('GLOBAL');
|
|
||||||
this.getInput('LAT').setVisible(global);
|
|
||||||
this.getInput('LON').setVisible(global);
|
|
||||||
this.getInput('X').setVisible(!global);
|
|
||||||
this.getInput('Y').setVisible(!global);
|
|
||||||
this.getInput('Z').fieldRow[0].setValue(frameId == 'GLOBAL' ? 'altitude' : 'z');
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
if (this.getInput('ID')) { // block has marker id field
|
if (this.getInput('ID')) { // block has marker id field
|
||||||
this.getInput('ID').setVisible(frameId == 'ARUCO'); // toggle id field
|
this.getInput('ID').setVisible(frameId == 'ARUCO'); // toggle id field
|
||||||
@@ -73,9 +65,6 @@ function updateSetpointBlock(e) {
|
|||||||
|
|
||||||
Blockly.Blocks['navigate'] = {
|
Blockly.Blocks['navigate'] = {
|
||||||
init: function () {
|
init: function () {
|
||||||
let navFrameId = frameIds.slice();
|
|
||||||
navFrameId.push(['global', 'GLOBAL_LOCAL'])
|
|
||||||
navFrameId.push(['global, WGS 84 alt.', 'GLOBAL'])
|
|
||||||
this.appendDummyInput()
|
this.appendDummyInput()
|
||||||
.appendField("navigate to point");
|
.appendField("navigate to point");
|
||||||
this.appendValueInput("X")
|
this.appendValueInput("X")
|
||||||
@@ -84,20 +73,12 @@ Blockly.Blocks['navigate'] = {
|
|||||||
this.appendValueInput("Y")
|
this.appendValueInput("Y")
|
||||||
.setCheck("Number")
|
.setCheck("Number")
|
||||||
.appendField("left");
|
.appendField("left");
|
||||||
this.appendValueInput("LAT")
|
|
||||||
.setCheck("Number")
|
|
||||||
.appendField("latitude")
|
|
||||||
.setVisible(false);
|
|
||||||
this.appendValueInput("LON")
|
|
||||||
.setCheck("Number")
|
|
||||||
.appendField("longitude")
|
|
||||||
.setVisible(false)
|
|
||||||
this.appendValueInput("Z")
|
this.appendValueInput("Z")
|
||||||
.setCheck("Number")
|
.setCheck("Number")
|
||||||
.appendField("up");
|
.appendField("up");
|
||||||
this.appendDummyInput()
|
this.appendDummyInput()
|
||||||
.appendField("relative to")
|
.appendField("relative to")
|
||||||
.appendField(new Blockly.FieldDropdown(navFrameId), "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")
|
||||||
@@ -287,7 +268,7 @@ Blockly.Blocks['mode'] = {
|
|||||||
.appendField("current flight mode");
|
.appendField("current flight mode");
|
||||||
this.setOutput(true, "String");
|
this.setOutput(true, "String");
|
||||||
this.setColour(COLOR_STATE);
|
this.setColour(COLOR_STATE);
|
||||||
this.setTooltip("Returns current flight mode (POSCTL, OFFBOARD, etc).");
|
this.setTooltip("");
|
||||||
this.setHelpUrl(DOCS_URL + '#' + this.type);
|
this.setHelpUrl(DOCS_URL + '#' + this.type);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
@@ -394,7 +375,7 @@ Blockly.Blocks['take_off'] = {
|
|||||||
this.setPreviousStatement(true, null);
|
this.setPreviousStatement(true, null);
|
||||||
this.setNextStatement(true, null);
|
this.setNextStatement(true, null);
|
||||||
this.setColour(COLOR_FLIGHT);
|
this.setColour(COLOR_FLIGHT);
|
||||||
this.setTooltip("Take off on desired altitude in meters.");
|
this.setTooltip("Take off on desired altitude in meters");
|
||||||
this.setHelpUrl(DOCS_URL + '#' + this.type);
|
this.setHelpUrl(DOCS_URL + '#' + this.type);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
@@ -410,7 +391,7 @@ Blockly.Blocks['land'] = {
|
|||||||
this.setPreviousStatement(true, null);
|
this.setPreviousStatement(true, null);
|
||||||
this.setNextStatement(true, null);
|
this.setNextStatement(true, null);
|
||||||
this.setColour(COLOR_FLIGHT);
|
this.setColour(COLOR_FLIGHT);
|
||||||
this.setTooltip("Land the drone.");
|
this.setTooltip("");
|
||||||
this.setHelpUrl(DOCS_URL + '#' + this.type);
|
this.setHelpUrl(DOCS_URL + '#' + this.type);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
@@ -419,10 +400,10 @@ Blockly.Blocks['global_position'] = {
|
|||||||
init: function () {
|
init: function () {
|
||||||
this.appendDummyInput()
|
this.appendDummyInput()
|
||||||
.appendField("current")
|
.appendField("current")
|
||||||
.appendField(new Blockly.FieldDropdown([["latitude", "LAT"], ["longitude", "LON"], ["altitude", "ALT"]]), "FIELD");
|
.appendField(new Blockly.FieldDropdown([["latitude", "LATITUDE"], ["longitude", "LONGITUDE"], ["altitude", "ALTITUDE"]]), "NAME");
|
||||||
this.setOutput(true, "Number");
|
this.setOutput(true, "Number");
|
||||||
this.setColour(COLOR_STATE);
|
this.setColour(230);
|
||||||
this.setTooltip("Returns current global position (latitude, longitude, altitude above the WGS 84 ellipsoid).");
|
this.setTooltip("");
|
||||||
this.setHelpUrl(DOCS_URL + '#' + this.type);
|
this.setHelpUrl(DOCS_URL + '#' + this.type);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -52,8 +52,6 @@
|
|||||||
<value name="X"><shadow type="math_number"><field name="NUM">0</field></shadow></value>
|
<value name="X"><shadow type="math_number"><field name="NUM">0</field></shadow></value>
|
||||||
<value name="Y"><shadow type="math_number"><field name="NUM">0</field></shadow></value>
|
<value name="Y"><shadow type="math_number"><field name="NUM">0</field></shadow></value>
|
||||||
<value name="Z"><shadow type="math_number"><field name="NUM">0</field></shadow></value>
|
<value name="Z"><shadow type="math_number"><field name="NUM">0</field></shadow></value>
|
||||||
<value name="LAT"><shadow type="math_number"><field name="NUM">47.397503</field></shadow></value>
|
|
||||||
<value name="LON"><shadow type="math_number"><field name="NUM">8.544945</field></shadow></value>
|
|
||||||
<value name="SPEED"><shadow type="math_number"><field name="NUM">0.5</field></shadow></value>
|
<value name="SPEED"><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>
|
||||||
</block>
|
</block>
|
||||||
@@ -87,7 +85,6 @@
|
|||||||
<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>
|
||||||
</block>
|
</block>
|
||||||
<block type="get_attitude"></block>
|
<block type="get_attitude"></block>
|
||||||
<block type="global_position"></block>
|
|
||||||
<block type="distance">
|
<block type="distance">
|
||||||
<value name="X"><shadow type="math_number"><field name="NUM">0</field></shadow></value>
|
<value name="X"><shadow type="math_number"><field name="NUM">0</field></shadow></value>
|
||||||
<value name="Y"><shadow type="math_number"><field name="NUM">0</field></shadow></value>
|
<value name="Y"><shadow type="math_number"><field name="NUM">0</field></shadow></value>
|
||||||
|
|||||||
@@ -39,8 +39,7 @@ var workspace = Blockly.inject('blockly', {
|
|||||||
function readParams() {
|
function readParams() {
|
||||||
return Promise.all([
|
return Promise.all([
|
||||||
ros.readParam('navigate_tolerance', true, 0.2),
|
ros.readParam('navigate_tolerance', true, 0.2),
|
||||||
ros.readParam('navigate_global_tolerance', true, 1),
|
ros.readParam('yaw_tolerance', true, 20),
|
||||||
ros.readParam('yaw_tolerance', true, 1),
|
|
||||||
ros.readParam('sleep_time', true, 0.2),
|
ros.readParam('sleep_time', true, 0.2),
|
||||||
ros.readParam('confirm_run', true, true),
|
ros.readParam('confirm_run', true, true),
|
||||||
]);
|
]);
|
||||||
@@ -211,7 +210,7 @@ function loadPrograms() {
|
|||||||
updateChanged();
|
updateChanged();
|
||||||
}, function(err) {
|
}, function(err) {
|
||||||
document.querySelector('.backend-fail').style.display = 'inline';
|
document.querySelector('.backend-fail').style.display = 'inline';
|
||||||
alert(`Error loading programs list.\n\nHave you enabled 'blocks' in clover.launch?`);
|
alert(`Error loading programs list.\n\nHave you enabled clover_blocks in clover.launch?`);
|
||||||
runButton.disabled = true;
|
runButton.disabled = true;
|
||||||
})
|
})
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -33,18 +33,6 @@ const NAVIGATE_WAIT = () => `\ndef navigate_wait(x=0, y=0, z=0, speed=0.5, frame
|
|||||||
return
|
return
|
||||||
rospy.sleep(${params.sleep_time})\n`;
|
rospy.sleep(${params.sleep_time})\n`;
|
||||||
|
|
||||||
const NAVIGATE_GLOBAL_WAIT = () => `\ndef navigate_global_wait(lat, lon, z, speed=0.5):
|
|
||||||
res = navigate_global(lat=lat, lon=lon, z=z, yaw=float('inf'), speed=speed)
|
|
||||||
|
|
||||||
if not res.success:
|
|
||||||
raise Exception(res.message)
|
|
||||||
|
|
||||||
while not rospy.is_shutdown():
|
|
||||||
telem = get_telemetry(frame_id='navigate_target')
|
|
||||||
if math.sqrt(telem.x ** 2 + telem.y ** 2 + telem.z ** 2) < ${params.navigate_global_tolerance}:
|
|
||||||
return
|
|
||||||
rospy.sleep(${params.sleep_time})\n`;
|
|
||||||
|
|
||||||
const LAND_WAIT = () => `\ndef land_wait():
|
const LAND_WAIT = () => `\ndef land_wait():
|
||||||
land()
|
land()
|
||||||
while get_telemetry().armed:
|
while get_telemetry().armed:
|
||||||
@@ -80,9 +68,6 @@ function generateROSDefinitions() {
|
|||||||
if (rosDefinitions.offboard) {
|
if (rosDefinitions.offboard) {
|
||||||
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) {
|
|
||||||
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`;
|
||||||
}
|
}
|
||||||
@@ -109,10 +94,6 @@ function generateROSDefinitions() {
|
|||||||
Blockly.Python.definitions_['import_math'] = 'import math';
|
Blockly.Python.definitions_['import_math'] = 'import math';
|
||||||
code += NAVIGATE_WAIT();
|
code += NAVIGATE_WAIT();
|
||||||
}
|
}
|
||||||
if (rosDefinitions.navigateGlobalWait) {
|
|
||||||
Blockly.Python.definitions_['import_math'] = 'import math';
|
|
||||||
code += NAVIGATE_GLOBAL_WAIT();
|
|
||||||
}
|
|
||||||
if (rosDefinitions.landWait) {
|
if (rosDefinitions.landWait) {
|
||||||
code += LAND_WAIT();
|
code += LAND_WAIT();
|
||||||
}
|
}
|
||||||
@@ -180,37 +161,14 @@ Blockly.Python.navigate = function(block) {
|
|||||||
let x = Blockly.Python.valueToCode(block, 'X', Blockly.Python.ORDER_NONE);
|
let x = Blockly.Python.valueToCode(block, 'X', Blockly.Python.ORDER_NONE);
|
||||||
let y = Blockly.Python.valueToCode(block, 'Y', Blockly.Python.ORDER_NONE);
|
let y = Blockly.Python.valueToCode(block, 'Y', Blockly.Python.ORDER_NONE);
|
||||||
let z = Blockly.Python.valueToCode(block, 'Z', Blockly.Python.ORDER_NONE);
|
let z = Blockly.Python.valueToCode(block, 'Z', Blockly.Python.ORDER_NONE);
|
||||||
let lat = Blockly.Python.valueToCode(block, 'LAT', Blockly.Python.ORDER_NONE);
|
let frameId = buildFrameId(block);
|
||||||
let lon = Blockly.Python.valueToCode(block, 'LON', Blockly.Python.ORDER_NONE);
|
|
||||||
let wait = block.getFieldValue('WAIT') == 'TRUE';
|
|
||||||
let frameId = block.getFieldValue('FRAME_ID');
|
|
||||||
let speed = Blockly.Python.valueToCode(block, 'SPEED', Blockly.Python.ORDER_NONE);
|
let speed = Blockly.Python.valueToCode(block, 'SPEED', Blockly.Python.ORDER_NONE);
|
||||||
|
|
||||||
simpleOffboard();
|
|
||||||
|
|
||||||
// global coordinates
|
|
||||||
if (frameId.startsWith('GLOBAL')) {
|
|
||||||
rosDefinitions.navigateGlobal = true;
|
|
||||||
simpleOffboard();
|
|
||||||
|
|
||||||
if (frameId == 'GLOBAL') {
|
|
||||||
z = `${z} + get_telemetry().alt - get_telemetry().z`;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (wait) {
|
|
||||||
rosDefinitions.navigateGlobalWait = true;
|
|
||||||
simpleOffboard();
|
|
||||||
return `navigate_global_wait(lat=${lat}, lon=${lon}, z=${z}, speed=${speed})\n`;
|
|
||||||
|
|
||||||
} else {
|
|
||||||
return `navigate_global(lat=${lat}, lon=${lon}, z=${z}, yaw=float('inf'), speed=${speed})\n`;
|
|
||||||
}
|
|
||||||
|
|
||||||
} else {
|
|
||||||
frameId = buildFrameId(block);
|
|
||||||
let params = [`x=${x}`, `y=${y}`, `z=${z}`, `frame_id=${frameId}`, `speed=${speed}`];
|
let params = [`x=${x}`, `y=${y}`, `z=${z}`, `frame_id=${frameId}`, `speed=${speed}`];
|
||||||
|
|
||||||
if (wait) {
|
simpleOffboard();
|
||||||
|
|
||||||
|
if (block.getFieldValue('WAIT') == 'TRUE') {
|
||||||
rosDefinitions.navigateWait = true;
|
rosDefinitions.navigateWait = true;
|
||||||
simpleOffboard();
|
simpleOffboard();
|
||||||
|
|
||||||
@@ -223,7 +181,6 @@ Blockly.Python.navigate = function(block) {
|
|||||||
return `navigate(${params.join(', ')})\n`;
|
return `navigate(${params.join(', ')})\n`;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
|
||||||
|
|
||||||
Blockly.Python.set_velocity = function(block) {
|
Blockly.Python.set_velocity = function(block) {
|
||||||
let x = Blockly.Python.valueToCode(block, 'X', Blockly.Python.ORDER_NONE);
|
let x = Blockly.Python.valueToCode(block, 'X', Blockly.Python.ORDER_NONE);
|
||||||
@@ -358,12 +315,6 @@ Blockly.Python.get_attitude = function(block) {
|
|||||||
return [code, Blockly.Python.ORDER_FUNCTION_CALL];
|
return [code, Blockly.Python.ORDER_FUNCTION_CALL];
|
||||||
}
|
}
|
||||||
|
|
||||||
Blockly.Python.global_position = function(block) {
|
|
||||||
simpleOffboard();
|
|
||||||
var code = `get_telemetry().${block.getFieldValue('FIELD').toLowerCase()}`;
|
|
||||||
return [code, Blockly.Python.ORDER_FUNCTION_CALL];
|
|
||||||
}
|
|
||||||
|
|
||||||
Blockly.Python.distance = function(block) {
|
Blockly.Python.distance = function(block) {
|
||||||
rosDefinitions.distance = true;
|
rosDefinitions.distance = true;
|
||||||
simpleOffboard();
|
simpleOffboard();
|
||||||
@@ -464,7 +415,7 @@ Blockly.Python.led_count = function(block) {
|
|||||||
|
|
||||||
function pigpio() {
|
function pigpio() {
|
||||||
Blockly.Python.definitions_['import_pigpio'] = 'import pigpio';
|
Blockly.Python.definitions_['import_pigpio'] = 'import pigpio';
|
||||||
Blockly.Python.definitions_['init_pigpio'] = 'pi = pigpio.pi()\nif not pi.connected: raise Exception(\'Cannot connect to pigpiod\')';
|
Blockly.Python.definitions_['init_pigpio'] = 'pi = pigpio.pi()';
|
||||||
}
|
}
|
||||||
|
|
||||||
const GPIO_READ = `\ndef gpio_read(pin):
|
const GPIO_READ = `\ndef gpio_read(pin):
|
||||||
|
|||||||
@@ -14,7 +14,7 @@ You may provide additional parameters for `spawn_drone.launch` as well:
|
|||||||
* `rangefinder` (*boolean*, default: *true*) - controls whether the drone will have a downward-facing laser rangefinder attached;
|
* `rangefinder` (*boolean*, default: *true*) - controls whether the drone will have a downward-facing laser rangefinder attached;
|
||||||
* `led` (*boolean*, default: *true*) - controls whether the drone will have a programmable LED strip (requires plugins from `clover_simulation`);
|
* `led` (*boolean*, default: *true*) - controls whether the drone will have a programmable LED strip (requires plugins from `clover_simulation`);
|
||||||
* `gps` (*boolean*, default: *true*) - controls whether the drone will have a simulated GPS attached (requires plugins from `sitl_gazebo`);
|
* `gps` (*boolean*, default: *true*) - controls whether the drone will have a simulated GPS attached (requires plugins from `sitl_gazebo`);
|
||||||
* `maintain_camera_rate` (*boolean*, default: *false*) - slow down the simulation to maintain camera publishing rate (internally changes the camera plugin from `libgazebo_ros_camera.so` to `libthrottling_camera.so` from [`clover_simulation`](../clover_simulation/README.md#throttling-camera-plugin-throttling_camera)).
|
* `maintain_camera_rate` (*boolean*, default: *false*) - slow down the simultion to maintain camera publishing rate (internally changes the camera plugin from `libgazebo_ros_camera.so` to `libthrottling_camera.so` from [`clover_simulation`](../clover_simulation/README.md#throttling-camera-plugin-throttling_camera)).
|
||||||
|
|
||||||
For example, in order to spawn a drone without a GPS module, you may use the following command:
|
For example, in order to spawn a drone without a GPS module, you may use the following command:
|
||||||
|
|
||||||
|
|||||||
@@ -1,7 +1,7 @@
|
|||||||
<launch>
|
<launch>
|
||||||
<arg name="model" default="$(find clover_description)/urdf/clover/clover4.xacro"/>
|
<arg name="model" default="$(find clover_description)/urdf/drones/clover4.xacro"/>
|
||||||
|
|
||||||
<param name="robot_description" command="xacro $(arg model)"/>
|
<param name="robot_description" command="$(find xacro)/xacro.py $(arg model)"/>
|
||||||
|
|
||||||
<node name="rviz" pkg="rviz" type="rviz" required="true"/>
|
<node name="rviz" pkg="rviz" type="rviz" required="true"/>
|
||||||
</launch>
|
</launch>
|
||||||
|
|||||||
@@ -1,6 +1,6 @@
|
|||||||
<package format="2">
|
<package format="2">
|
||||||
<name>clover_description</name>
|
<name>clover_description</name>
|
||||||
<version>0.23.0</version>
|
<version>0.21.1</version>
|
||||||
<description>The clover_description package provides URDF models of the Clover series of quadcopters.</description>
|
<description>The clover_description package provides URDF models of the Clover series of quadcopters.</description>
|
||||||
|
|
||||||
<maintainer email="sfalexrog@gmail.com">Alexey Rogachevskiy</maintainer>
|
<maintainer email="sfalexrog@gmail.com">Alexey Rogachevskiy</maintainer>
|
||||||
|
|||||||
@@ -1,5 +1,5 @@
|
|||||||
<?xml version="1.0"?>
|
<?xml version="1.0"?>
|
||||||
<robot name="clover" xmlns:xacro="http://ros.org/wiki/xacro">
|
<robot name="clover_camera" xmlns:xacro="http://ros.org/wiki/xacro">
|
||||||
|
|
||||||
<xacro:arg name="main_camera" default="true"/>
|
<xacro:arg name="main_camera" default="true"/>
|
||||||
<xacro:arg name="rangefinder" default="true"/>
|
<xacro:arg name="rangefinder" default="true"/>
|
||||||
@@ -8,10 +8,10 @@
|
|||||||
<xacro:arg name="maintain_camera_rate" default="false"/>
|
<xacro:arg name="maintain_camera_rate" default="false"/>
|
||||||
<xacro:arg name="use_clover_physics" default="false"/>
|
<xacro:arg name="use_clover_physics" default="false"/>
|
||||||
|
|
||||||
<xacro:include filename="clover4_base.xacro" />
|
<xacro:include filename="$(find clover_description)/urdf/clover/clover4_base.xacro" />
|
||||||
<xacro:include filename="../sensors/rpi_cam.urdf.xacro"/>
|
<xacro:include filename="$(find clover_description)/urdf/sensors/rpi_cam.urdf.xacro"/>
|
||||||
<xacro:include filename="../sensors/distance_sensor.urdf.xacro"/>
|
<xacro:include filename="$(find clover_description)/urdf/sensors/distance_sensor.urdf.xacro"/>
|
||||||
<xacro:include filename="../leds/led_strip.xacro"/>
|
<xacro:include filename="$(find clover_description)/urdf/leds/led_strip.xacro"/>
|
||||||
|
|
||||||
<!-- Create camera plugin -->
|
<!-- Create camera plugin -->
|
||||||
<xacro:if value="$(arg main_camera)">
|
<xacro:if value="$(arg main_camera)">
|
||||||
@@ -36,17 +36,11 @@
|
|||||||
</xacro:if>
|
</xacro:if>
|
||||||
|
|
||||||
<xacro:if value="$(arg gps)">
|
<xacro:if value="$(arg gps)">
|
||||||
<gazebo>
|
<!-- Instantiate gps plugin. -->
|
||||||
<include>
|
<xacro:gps_plugin_macro
|
||||||
<uri>model://gps</uri>
|
namespace="${namespace}"
|
||||||
<pose>0.1 0 0 0 0 0</pose>
|
gps_noise="true"
|
||||||
<name>gps0</name>
|
/>
|
||||||
</include>
|
|
||||||
<joint name='gps0_joint' type='fixed'>
|
|
||||||
<child>gps0::link</child>
|
|
||||||
<parent>base_link</parent>
|
|
||||||
</joint>
|
|
||||||
</gazebo>
|
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
|
|
||||||
</robot>
|
</robot>
|
||||||
|
|||||||
@@ -1,15 +1,40 @@
|
|||||||
<?xml version="1.0"?>
|
<?xml version="1.0"?>
|
||||||
|
|
||||||
<robot name="clover" xmlns:xacro="http://ros.org/wiki/xacro">
|
<robot name="clover" xmlns:xacro="http://ros.org/wiki/xacro">
|
||||||
|
<!-- Properties that can be assigned at build time as arguments.
|
||||||
|
Is there a reason not to make all properties arguments?
|
||||||
|
-->
|
||||||
|
<xacro:arg name='name' default='iris' />
|
||||||
|
<xacro:arg name='mavlink_addr' default='INADDR_ANY' />
|
||||||
|
<xacro:arg name='mavlink_udp_port' default='14560' />
|
||||||
|
<xacro:arg name='mavlink_tcp_port' default='4560' />
|
||||||
|
<xacro:arg name='serial_enabled' default='false' />
|
||||||
|
<xacro:arg name='serial_device' default='/dev/ttyACM0' />
|
||||||
|
<xacro:arg name='baudrate' default='921600' />
|
||||||
|
<xacro:arg name='qgc_addr' default='INADDR_ANY' />
|
||||||
|
<xacro:arg name='qgc_udp_port' default='14550' />
|
||||||
|
<xacro:arg name='sdk_addr' default='INADDR_ANY' />
|
||||||
|
<xacro:arg name='sdk_udp_port' default='14540' />
|
||||||
|
<xacro:arg name='hil_mode' default='false' />
|
||||||
|
<xacro:arg name='hil_state_level' default='false' />
|
||||||
|
<xacro:arg name='send_vision_estimation' default='false' />
|
||||||
|
<xacro:arg name='send_odometry' default='false' />
|
||||||
|
<xacro:arg name='enable_lockstep' default='true' />
|
||||||
|
<xacro:arg name='use_tcp' default='true' />
|
||||||
|
<xacro:arg name='vehicle_is_tailsitter' default='false' />
|
||||||
|
<xacro:arg name='visual_material' default='DarkGrey' />
|
||||||
|
<xacro:arg name='enable_mavlink_interface' default='true' />
|
||||||
<xacro:arg name='enable_wind' default='false' />
|
<xacro:arg name='enable_wind' default='false' />
|
||||||
|
<!-- The following causes segfault with multiple vehicles if defaults to true!!! -->
|
||||||
|
<xacro:arg name='enable_ground_truth' default='false' />
|
||||||
<xacro:arg name='enable_logging' default='false' />
|
<xacro:arg name='enable_logging' default='false' />
|
||||||
<xacro:arg name='log_file' default='clover' />
|
<xacro:arg name='log_file' default='iris' />
|
||||||
|
|
||||||
<!-- macros for gazebo plugins, sensors -->
|
<!-- macros for gazebo plugins, sensors -->
|
||||||
<xacro:include filename="../component_snippets.urdf.xacro" />
|
<xacro:include filename="$(find clover_description)/urdf/component_snippets.urdf.xacro" />
|
||||||
|
|
||||||
<!-- Instantiate iris "mechanics" -->
|
<!-- Instantiate iris "mechanics" -->
|
||||||
<xacro:include filename="clover4_physics.xacro" />
|
<xacro:include filename="$(find clover_description)/urdf/clover/clover4_physics.xacro" />
|
||||||
|
|
||||||
<xacro:if value="$(arg enable_wind)">
|
<xacro:if value="$(arg enable_wind)">
|
||||||
<xacro:wind_plugin_macro
|
<xacro:wind_plugin_macro
|
||||||
@@ -24,8 +49,126 @@
|
|||||||
/>
|
/>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
|
|
||||||
<!-- Gazebo plugins -->
|
<!-- Instantiate magnetometer plugin. -->
|
||||||
<xacro:include filename="$(find clover_description)/urdf/clover/clover4_gazebo.xacro" />
|
<xacro:magnetometer_plugin_macro
|
||||||
|
namespace="${namespace}"
|
||||||
|
pub_rate="20"
|
||||||
|
noise_density="0.0004"
|
||||||
|
random_walk="0.0000064"
|
||||||
|
bias_correlation_time="600"
|
||||||
|
mag_topic="/mag"
|
||||||
|
>
|
||||||
|
</xacro:magnetometer_plugin_macro>
|
||||||
|
|
||||||
|
<!-- Instantiate barometer plugin. -->
|
||||||
|
<xacro:barometer_plugin_macro
|
||||||
|
namespace="${namespace}"
|
||||||
|
pub_rate="10"
|
||||||
|
baro_topic="/baro"
|
||||||
|
>
|
||||||
|
</xacro:barometer_plugin_macro>
|
||||||
|
|
||||||
|
<xacro:if value="$(arg enable_mavlink_interface)">
|
||||||
|
<!-- Instantiate mavlink telemetry interface. -->
|
||||||
|
<xacro:mavlink_interface_macro
|
||||||
|
namespace="${namespace}"
|
||||||
|
imu_sub_topic="/imu"
|
||||||
|
gps_sub_topic="/gps"
|
||||||
|
mag_sub_topic="/mag"
|
||||||
|
baro_sub_topic="/baro"
|
||||||
|
mavlink_addr="$(arg mavlink_addr)"
|
||||||
|
mavlink_udp_port="$(arg mavlink_udp_port)"
|
||||||
|
mavlink_tcp_port="$(arg mavlink_tcp_port)"
|
||||||
|
serial_enabled="$(arg serial_enabled)"
|
||||||
|
serial_device="$(arg serial_device)"
|
||||||
|
baudrate="$(arg baudrate)"
|
||||||
|
qgc_addr="$(arg qgc_addr)"
|
||||||
|
qgc_udp_port="$(arg qgc_udp_port)"
|
||||||
|
sdk_addr="$(arg sdk_addr)"
|
||||||
|
sdk_udp_port="$(arg sdk_udp_port)"
|
||||||
|
hil_mode="$(arg hil_mode)"
|
||||||
|
hil_state_level="$(arg hil_state_level)"
|
||||||
|
vehicle_is_tailsitter="$(arg vehicle_is_tailsitter)"
|
||||||
|
send_vision_estimation="$(arg send_vision_estimation)"
|
||||||
|
send_odometry="$(arg send_odometry)"
|
||||||
|
enable_lockstep="$(arg enable_lockstep)"
|
||||||
|
use_tcp="$(arg use_tcp)"
|
||||||
|
>
|
||||||
|
</xacro:mavlink_interface_macro>
|
||||||
|
</xacro:if>
|
||||||
|
|
||||||
|
<!-- Mount an ADIS16448 IMU. -->
|
||||||
|
<xacro:imu_plugin_macro
|
||||||
|
namespace="${namespace}"
|
||||||
|
imu_suffix=""
|
||||||
|
parent_link="base_link"
|
||||||
|
imu_topic="/imu"
|
||||||
|
mass_imu_sensor="0.015"
|
||||||
|
gyroscope_noise_density="0.0003394"
|
||||||
|
gyroscopoe_random_walk="0.000038785"
|
||||||
|
gyroscope_bias_correlation_time="1000.0"
|
||||||
|
gyroscope_turn_on_bias_sigma="0.0087"
|
||||||
|
accelerometer_noise_density="0.004"
|
||||||
|
accelerometer_random_walk="0.006"
|
||||||
|
accelerometer_bias_correlation_time="300.0"
|
||||||
|
accelerometer_turn_on_bias_sigma="0.1960"
|
||||||
|
>
|
||||||
|
<inertia ixx="0.00001" ixy="0.0" ixz="0.0" iyy="0.00001" iyz="0.0" izz="0.00001" />
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
|
</xacro:imu_plugin_macro>
|
||||||
|
|
||||||
|
<xacro:if value="$(arg enable_ground_truth)">
|
||||||
|
<!-- Mount an IMU providing ground truth. -->
|
||||||
|
<xacro:imu_plugin_macro
|
||||||
|
namespace="${namespace}"
|
||||||
|
imu_suffix="gt"
|
||||||
|
parent_link="base_link"
|
||||||
|
imu_topic="ground_truth/imu"
|
||||||
|
mass_imu_sensor="0.00001"
|
||||||
|
gyroscope_noise_density="0.0"
|
||||||
|
gyroscopoe_random_walk="0.0"
|
||||||
|
gyroscope_bias_correlation_time="1000.0"
|
||||||
|
gyroscope_turn_on_bias_sigma="0.0"
|
||||||
|
accelerometer_noise_density="0.0"
|
||||||
|
accelerometer_random_walk="0.0"
|
||||||
|
accelerometer_bias_correlation_time="300.0"
|
||||||
|
accelerometer_turn_on_bias_sigma="0.0"
|
||||||
|
>
|
||||||
|
<inertia ixx="0.00001" ixy="0.0" ixz="0.0" iyy="0.00001" iyz="0.0" izz="0.00001" />
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
|
</xacro:imu_plugin_macro>
|
||||||
|
|
||||||
|
<!-- Mount a generic odometry sensor providing ground truth. -->
|
||||||
|
<xacro:odometry_plugin_macro
|
||||||
|
namespace="${namespace}/ground_truth"
|
||||||
|
odometry_sensor_suffix="gt"
|
||||||
|
parent_link="base_link"
|
||||||
|
pose_topic="pose"
|
||||||
|
pose_with_covariance_topic="pose_with_covariance"
|
||||||
|
position_topic="position"
|
||||||
|
transform_topic="transform"
|
||||||
|
odometry_topic="odometry"
|
||||||
|
parent_frame_id="world"
|
||||||
|
mass_odometry_sensor="0.00001"
|
||||||
|
measurement_divisor="1"
|
||||||
|
measurement_delay="0"
|
||||||
|
unknown_delay="0.0"
|
||||||
|
noise_normal_position="0 0 0"
|
||||||
|
noise_normal_quaternion="0 0 0"
|
||||||
|
noise_normal_linear_velocity="0 0 0"
|
||||||
|
noise_normal_angular_velocity="0 0 0"
|
||||||
|
noise_uniform_position="0 0 0"
|
||||||
|
noise_uniform_quaternion="0 0 0"
|
||||||
|
noise_uniform_linear_velocity="0 0 0"
|
||||||
|
noise_uniform_angular_velocity="0 0 0"
|
||||||
|
enable_odometry_map="false"
|
||||||
|
odometry_map=""
|
||||||
|
image_scale=""
|
||||||
|
>
|
||||||
|
<inertia ixx="0.00001" ixy="0.0" ixz="0.0" iyy="0.00001" iyz="0.0" izz="0.00001" /> <!-- [kg.m^2] [kg.m^2] [kg.m^2] [kg.m^2] [kg.m^2] [kg.m^2] -->
|
||||||
|
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
|
||||||
|
</xacro:odometry_plugin_macro>
|
||||||
|
</xacro:if>
|
||||||
|
|
||||||
<xacro:if value="$(arg enable_logging)">
|
<xacro:if value="$(arg enable_logging)">
|
||||||
<!-- Instantiate a logger -->
|
<!-- Instantiate a logger -->
|
||||||
|
|||||||
@@ -1,183 +0,0 @@
|
|||||||
<?xml version="1.0"?>
|
|
||||||
|
|
||||||
<!-- Reference: https://github.com/PX4/PX4-SITL_gazebo/blob/7505aee97d2d3112fb2bd95198946345c6fa0b07/models/iris/iris.sdf.jinja#L430 -->
|
|
||||||
|
|
||||||
<robot xmlns:xacro="http://ros.org/wiki/xacro">
|
|
||||||
|
|
||||||
<!-- IMU link -->
|
|
||||||
<link name="/imu_link">
|
|
||||||
<inertial>
|
|
||||||
<inertia ixx="0.00001" ixy="0.0" ixz="0.0" iyy="0.00001" iyz="0.0" izz="0.00001"/>
|
|
||||||
<mass value="0.015"/>
|
|
||||||
<!-- [kg] -->
|
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
||||||
</inertial>
|
|
||||||
</link>
|
|
||||||
|
|
||||||
<!-- IMU joint -->
|
|
||||||
<joint name="/imu_joint" type="fixed">
|
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
||||||
<parent link="base_link"/>
|
|
||||||
<child link="/imu_link"/>
|
|
||||||
<!-- <limit upper="0" lower="0" effort="0" velocity="0" /> -->
|
|
||||||
</joint>
|
|
||||||
|
|
||||||
<gazebo reference="/imu_joint">
|
|
||||||
<disableFixedJointLumping>true</disableFixedJointLumping>
|
|
||||||
<preserveFixedJoint>true</preserveFixedJoint>
|
|
||||||
</gazebo>
|
|
||||||
|
|
||||||
<gazebo>
|
|
||||||
<plugin name='groundtruth_plugin' filename='libgazebo_groundtruth_plugin.so'>
|
|
||||||
<robotNamespace/>
|
|
||||||
</plugin>
|
|
||||||
<plugin name='magnetometer_plugin' filename='libgazebo_magnetometer_plugin.so'>
|
|
||||||
<robotNamespace/>
|
|
||||||
<pubRate>100</pubRate>
|
|
||||||
<noiseDensity>0.0004</noiseDensity>
|
|
||||||
<randomWalk>6.4e-06</randomWalk>
|
|
||||||
<biasCorrelationTime>600</biasCorrelationTime>
|
|
||||||
<magTopic>/mag</magTopic>
|
|
||||||
</plugin>
|
|
||||||
<plugin name='barometer_plugin' filename='libgazebo_barometer_plugin.so'>
|
|
||||||
<robotNamespace/>
|
|
||||||
<pubRate>50</pubRate>
|
|
||||||
<baroTopic>/baro</baroTopic>
|
|
||||||
<baroDriftPaPerSec>0</baroDriftPaPerSec>
|
|
||||||
</plugin>
|
|
||||||
<plugin name='mavlink_interface' filename='libgazebo_mavlink_interface.so'>
|
|
||||||
<robotNamespace/>
|
|
||||||
<imuSubTopic>/imu</imuSubTopic>
|
|
||||||
<magSubTopic>/mag</magSubTopic>
|
|
||||||
<baroSubTopic>/baro</baroSubTopic>
|
|
||||||
<mavlink_addr>INADDR_ANY</mavlink_addr>
|
|
||||||
<mavlink_tcp_port>4560</mavlink_tcp_port>
|
|
||||||
<mavlink_udp_port>14560</mavlink_udp_port>
|
|
||||||
<serialEnabled>false</serialEnabled>
|
|
||||||
<serialDevice>/dev/ttyACM0</serialDevice>
|
|
||||||
<baudRate>921600</baudRate>
|
|
||||||
<qgc_addr>INADDR_ANY</qgc_addr>
|
|
||||||
<qgc_udp_port>14550</qgc_udp_port>
|
|
||||||
<sdk_addr>INADDR_ANY</sdk_addr>
|
|
||||||
<sdk_udp_port>14540</sdk_udp_port>
|
|
||||||
<hil_mode>false</hil_mode>
|
|
||||||
<hil_state_level>0</hil_state_level>
|
|
||||||
<send_vision_estimation>0</send_vision_estimation>
|
|
||||||
<send_odometry>1</send_odometry>
|
|
||||||
<enable_lockstep>1</enable_lockstep>
|
|
||||||
<use_tcp>1</use_tcp>
|
|
||||||
<motorSpeedCommandPubTopic>/gazebo/command/motor_speed</motorSpeedCommandPubTopic>
|
|
||||||
<control_channels>
|
|
||||||
<channel name='rotor1'>
|
|
||||||
<input_index>0</input_index>
|
|
||||||
<input_offset>0</input_offset>
|
|
||||||
<input_scaling>1000</input_scaling>
|
|
||||||
<zero_position_disarmed>0</zero_position_disarmed>
|
|
||||||
<zero_position_armed>100</zero_position_armed>
|
|
||||||
<joint_control_type>velocity</joint_control_type>
|
|
||||||
</channel>
|
|
||||||
<channel name='rotor2'>
|
|
||||||
<input_index>1</input_index>
|
|
||||||
<input_offset>0</input_offset>
|
|
||||||
<input_scaling>1000</input_scaling>
|
|
||||||
<zero_position_disarmed>0</zero_position_disarmed>
|
|
||||||
<zero_position_armed>100</zero_position_armed>
|
|
||||||
<joint_control_type>velocity</joint_control_type>
|
|
||||||
</channel>
|
|
||||||
<channel name='rotor3'>
|
|
||||||
<input_index>2</input_index>
|
|
||||||
<input_offset>0</input_offset>
|
|
||||||
<input_scaling>1000</input_scaling>
|
|
||||||
<zero_position_disarmed>0</zero_position_disarmed>
|
|
||||||
<zero_position_armed>100</zero_position_armed>
|
|
||||||
<joint_control_type>velocity</joint_control_type>
|
|
||||||
</channel>
|
|
||||||
<channel name='rotor4'>
|
|
||||||
<input_index>3</input_index>
|
|
||||||
<input_offset>0</input_offset>
|
|
||||||
<input_scaling>1000</input_scaling>
|
|
||||||
<zero_position_disarmed>0</zero_position_disarmed>
|
|
||||||
<zero_position_armed>100</zero_position_armed>
|
|
||||||
<joint_control_type>velocity</joint_control_type>
|
|
||||||
</channel>
|
|
||||||
<channel name='rotor5'>
|
|
||||||
<input_index>4</input_index>
|
|
||||||
<input_offset>1</input_offset>
|
|
||||||
<input_scaling>324.6</input_scaling>
|
|
||||||
<zero_position_disarmed>0</zero_position_disarmed>
|
|
||||||
<zero_position_armed>0</zero_position_armed>
|
|
||||||
<joint_control_type>velocity</joint_control_type>
|
|
||||||
<joint_control_pid>
|
|
||||||
<p>0.1</p>
|
|
||||||
<i>0</i>
|
|
||||||
<d>0</d>
|
|
||||||
<iMax>0.0</iMax>
|
|
||||||
<iMin>0.0</iMin>
|
|
||||||
<cmdMax>2</cmdMax>
|
|
||||||
<cmdMin>-2</cmdMin>
|
|
||||||
</joint_control_pid>
|
|
||||||
<joint_name>zephyr_delta_wing::propeller_joint</joint_name>
|
|
||||||
</channel>
|
|
||||||
<channel name='rotor6'>
|
|
||||||
<input_index>5</input_index>
|
|
||||||
<input_offset>0</input_offset>
|
|
||||||
<input_scaling>0.524</input_scaling>
|
|
||||||
<zero_position_disarmed>0</zero_position_disarmed>
|
|
||||||
<zero_position_armed>0</zero_position_armed>
|
|
||||||
<joint_control_type>position</joint_control_type>
|
|
||||||
<joint_name>zephyr_delta_wing::flap_left_joint</joint_name>
|
|
||||||
<joint_control_pid>
|
|
||||||
<p>10.0</p>
|
|
||||||
<i>0</i>
|
|
||||||
<d>0</d>
|
|
||||||
<iMax>0</iMax>
|
|
||||||
<iMin>0</iMin>
|
|
||||||
<cmdMax>20</cmdMax>
|
|
||||||
<cmdMin>-20</cmdMin>
|
|
||||||
</joint_control_pid>
|
|
||||||
</channel>
|
|
||||||
<channel name='rotor7'>
|
|
||||||
<input_index>6</input_index>
|
|
||||||
<input_offset>0</input_offset>
|
|
||||||
<input_scaling>0.524</input_scaling>
|
|
||||||
<zero_position_disarmed>0</zero_position_disarmed>
|
|
||||||
<zero_position_armed>0</zero_position_armed>
|
|
||||||
<joint_control_type>position</joint_control_type>
|
|
||||||
<joint_name>zephyr_delta_wing::flap_right_joint</joint_name>
|
|
||||||
<joint_control_pid>
|
|
||||||
<p>10.0</p>
|
|
||||||
<i>0</i>
|
|
||||||
<d>0</d>
|
|
||||||
<iMax>0</iMax>
|
|
||||||
<iMin>0</iMin>
|
|
||||||
<cmdMax>20</cmdMax>
|
|
||||||
<cmdMin>-20</cmdMin>
|
|
||||||
</joint_control_pid>
|
|
||||||
</channel>
|
|
||||||
<channel name='rotor8'>
|
|
||||||
<input_index>7</input_index>
|
|
||||||
<input_offset>0</input_offset>
|
|
||||||
<input_scaling>0.524</input_scaling>
|
|
||||||
<zero_position_disarmed>0</zero_position_disarmed>
|
|
||||||
<zero_position_armed>0</zero_position_armed>
|
|
||||||
<joint_control_type>position</joint_control_type>
|
|
||||||
</channel>
|
|
||||||
</control_channels>
|
|
||||||
</plugin>
|
|
||||||
<static>0</static>
|
|
||||||
<plugin name='rotors_gazebo_imu_plugin' filename='libgazebo_imu_plugin.so'>
|
|
||||||
<robotNamespace/>
|
|
||||||
<linkName>/imu_link</linkName>
|
|
||||||
<imuTopic>/imu</imuTopic>
|
|
||||||
<gyroscopeNoiseDensity>0.00018665</gyroscopeNoiseDensity>
|
|
||||||
<gyroscopeRandomWalk>3.8785e-05</gyroscopeRandomWalk>
|
|
||||||
<gyroscopeBiasCorrelationTime>1000.0</gyroscopeBiasCorrelationTime>
|
|
||||||
<gyroscopeTurnOnBiasSigma>0.0087</gyroscopeTurnOnBiasSigma>
|
|
||||||
<accelerometerNoiseDensity>0.00186</accelerometerNoiseDensity>
|
|
||||||
<accelerometerRandomWalk>0.006</accelerometerRandomWalk>
|
|
||||||
<accelerometerBiasCorrelationTime>300.0</accelerometerBiasCorrelationTime>
|
|
||||||
<accelerometerTurnOnBiasSigma>0.196</accelerometerTurnOnBiasSigma>
|
|
||||||
</plugin>
|
|
||||||
</gazebo>
|
|
||||||
|
|
||||||
</robot>
|
|
||||||
@@ -6,7 +6,7 @@
|
|||||||
|
|
||||||
-->
|
-->
|
||||||
|
|
||||||
<robot name="clover" xmlns:xacro="http://ros.org/wiki/xacro">
|
<robot name="iris" xmlns:xacro="http://ros.org/wiki/xacro">
|
||||||
<!-- Properties -->
|
<!-- Properties -->
|
||||||
<xacro:property name="namespace" value="" />
|
<xacro:property name="namespace" value="" />
|
||||||
<xacro:property name="rotor_velocity_slowdown_sim" value="10" />
|
<xacro:property name="rotor_velocity_slowdown_sim" value="10" />
|
||||||
@@ -35,7 +35,7 @@
|
|||||||
<xacro:property name="sqrt2" value="1.4142135623730951" />
|
<xacro:property name="sqrt2" value="1.4142135623730951" />
|
||||||
<xacro:property name="rotor_drag_coefficient" value="1.75e-04" />
|
<xacro:property name="rotor_drag_coefficient" value="1.75e-04" />
|
||||||
<xacro:property name="rolling_moment_coefficient" value="0.000001" />
|
<xacro:property name="rolling_moment_coefficient" value="0.000001" />
|
||||||
<xacro:property name="color" value="DarkGrey" />
|
<xacro:property name="color" value="$(arg visual_material)" />
|
||||||
|
|
||||||
<!-- Property Blocks -->
|
<!-- Property Blocks -->
|
||||||
<!-- Clover body inertia -->
|
<!-- Clover body inertia -->
|
||||||
@@ -84,7 +84,7 @@
|
|||||||
</xacro:unless>
|
</xacro:unless>
|
||||||
|
|
||||||
<!-- Included URDF Files -->
|
<!-- Included URDF Files -->
|
||||||
<xacro:include filename="clover4_macros.xacro" />
|
<xacro:include filename="$(find clover_description)/urdf/clover/clover4_macros.xacro" />
|
||||||
|
|
||||||
<!-- Instantiate multirotor_base_macro once -->
|
<!-- Instantiate multirotor_base_macro once -->
|
||||||
<xacro:clover4_base_macro
|
<xacro:clover4_base_macro
|
||||||
|
|||||||
@@ -64,12 +64,6 @@
|
|||||||
<!-- <gazebo>
|
<!-- <gazebo>
|
||||||
<static>true</static>
|
<static>true</static>
|
||||||
</gazebo> -->
|
</gazebo> -->
|
||||||
<gazebo>
|
|
||||||
<plugin name="${name}_ros_controller" filename="libsim_leds_controller.so">
|
|
||||||
<robotNamespace></robotNamespace>
|
|
||||||
<ledCount>${led_count}</ledCount>
|
|
||||||
</plugin>
|
|
||||||
</gazebo>
|
|
||||||
</xacro:macro>
|
</xacro:macro>
|
||||||
|
|
||||||
</robot>
|
</robot>
|
||||||
|
|||||||
@@ -1,6 +1,6 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
<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="$(find clover_description)/urdf/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">
|
<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">
|
||||||
|
|||||||
@@ -1,5 +1,5 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
<robot name="pinhole_camera" xmlns:xacro="http://ros.org/wiki/xacro">
|
<robot name="pinhole_camera" xmlns:xacro="http://ros.org/wiki/xacro">
|
||||||
<xacro:include filename="../camera_sensor.urdf.xacro"/>
|
<xacro:include filename="$(find clover_description)/urdf/camera_sensor.urdf.xacro"/>
|
||||||
<xacro:camera_sensor name="main_camera" width="640" height="480" rate="30" horizontal_fov="${120.0*pi/180.0}"/>
|
<xacro:camera_sensor name="main_camera" width="640" height="480" rate="30" horizontal_fov="${120.0*pi/180.0}"/>
|
||||||
</robot>
|
</robot>
|
||||||
|
|||||||
@@ -1,6 +1,6 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
<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="$(find clover_description)/urdf/camera_sensor.urdf.xacro"/>
|
||||||
|
|
||||||
<xacro:macro name="rpi_cam" params="name:=rpi_cam parent x:=0 y:=0 z:=0 roll:=0 pitch:=0 yaw:=0 width:=320 height:=240 rate:=40 do_throttling:=false">
|
<xacro:macro name="rpi_cam" params="name:=rpi_cam parent x:=0 y:=0 z:=0 roll:=0 pitch:=0 yaw:=0 width:=320 height:=240 rate:=40 do_throttling:=false">
|
||||||
<joint name="${name}_joint" type="fixed">
|
<joint name="${name}_joint" type="fixed">
|
||||||
|
|||||||
@@ -37,14 +37,6 @@ target_compile_options(sim_leds PRIVATE -std=c++11)
|
|||||||
|
|
||||||
add_dependencies(sim_leds ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
|
add_dependencies(sim_leds ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
|
||||||
|
|
||||||
add_library(sim_leds_controller src/sim_leds_controller.cpp)
|
|
||||||
|
|
||||||
target_include_directories(sim_leds_controller PRIVATE ${catkin_INCLUDE_DIRS} ${GAZEBO_INCLUDE_DIRS})
|
|
||||||
target_link_libraries(sim_leds_controller PRIVATE ${catkin_LIBRARIES} ${GAZEBO_LIBRARIES})
|
|
||||||
target_compile_options(sim_leds_controller PRIVATE -std=c++11)
|
|
||||||
|
|
||||||
add_dependencies(sim_leds_controller ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
|
|
||||||
|
|
||||||
# Gazebo throttling camera plugin
|
# Gazebo throttling camera plugin
|
||||||
# for some reason, CMake does not support per-target link directories, and Gazebo does not put
|
# for some reason, CMake does not support per-target link directories, and Gazebo does not put
|
||||||
# CameraPlugin into ${GAZEBO_LIBRARIES}
|
# CameraPlugin into ${GAZEBO_LIBRARIES}
|
||||||
|
|||||||
@@ -55,7 +55,7 @@ A visual Gazebo plugin is used for the LED strip. An example of the plugin usage
|
|||||||
The plugin accepts the following parameters during instantiation:
|
The plugin accepts the following parameters during instantiation:
|
||||||
|
|
||||||
* `robotNamespace` (*string*, default: "") - a ROS namespace for the plugin;
|
* `robotNamespace` (*string*, default: "") - a ROS namespace for the plugin;
|
||||||
* `ledCount` (*integer*, required) - total number of LEDs in a strip.
|
* `ledCount` (*integer*, required) - total numer of LEDs in a strip.
|
||||||
|
|
||||||
The plugin will provide the following service:
|
The plugin will provide the following service:
|
||||||
|
|
||||||
|
|||||||
@@ -1,36 +0,0 @@
|
|||||||
#!/bin/sh
|
|
||||||
#
|
|
||||||
# @name COEX Clover Simulator
|
|
||||||
#
|
|
||||||
# @type Quadrotor X
|
|
||||||
#
|
|
||||||
|
|
||||||
. ${R}etc/init.d-posix/airframes/10016_iris # base on iris
|
|
||||||
|
|
||||||
param set ATT_W_EXT_HDG 0.5
|
|
||||||
param set ATT_EXT_HDG_M 1
|
|
||||||
|
|
||||||
param set COM_DISARM_LAND 1.0
|
|
||||||
|
|
||||||
param set LPE_FLW_SCALE 1.0
|
|
||||||
param set LPE_FLW_R 0.2
|
|
||||||
param set LPE_FLW_RR 0.0
|
|
||||||
param set LPE_FLW_QMIN 10
|
|
||||||
param set LPE_VIS_DELAY 0.0
|
|
||||||
param set LPE_VIS_Z 0.1
|
|
||||||
param set LPE_FUSION 86
|
|
||||||
|
|
||||||
param set SENS_FLOW_ROT 0
|
|
||||||
param set SENS_FLOW_MINHGT 0.0
|
|
||||||
param set SENS_FLOW_MAXHGT 4.0
|
|
||||||
param set SENS_FLOW_MAXR 10.0
|
|
||||||
|
|
||||||
param set EKF2_AID_MASK 26 # flow + vis pos + vis yaw
|
|
||||||
param set EKF2_OF_DELAY 0
|
|
||||||
param set EKF2_OF_QMIN 10
|
|
||||||
param set EKF2_OF_N_MIN 0.05
|
|
||||||
param set EKF2_OF_N_MAX 0.2
|
|
||||||
param set EKF2_HGT_MODE 2
|
|
||||||
param set EKF2_EVA_NOISE 0.1
|
|
||||||
param set EKF2_EVP_NOISE 0.1
|
|
||||||
param set EKF2_EV_DELAY 0
|
|
||||||
@@ -4,18 +4,16 @@
|
|||||||
<arg name="est" default="ekf2"/> <!-- PX4 estimator: lpe, ekf2 -->
|
<arg name="est" default="ekf2"/> <!-- PX4 estimator: lpe, ekf2 -->
|
||||||
<arg name="vehicle" default="clover"/> <!-- PX4 vehicle configuration: clover, clover_vpe -->
|
<arg name="vehicle" default="clover"/> <!-- PX4 vehicle configuration: clover, clover_vpe -->
|
||||||
<arg name="main_camera" default="true"/> <!-- Simulated vision position estimation camera (optical flow, ArUco) -->
|
<arg name="main_camera" default="true"/> <!-- Simulated vision position estimation camera (optical flow, ArUco) -->
|
||||||
<arg name="maintain_camera_rate" default="false"/> <!-- Slow simulation down to maintain camera rate -->
|
|
||||||
<arg name="rangefinder" default="true"/> <!-- Simulated downward-facing rangefinder, vl53l1x-like -->
|
<arg name="rangefinder" default="true"/> <!-- Simulated downward-facing rangefinder, vl53l1x-like -->
|
||||||
<arg name="led" default="true"/> <!-- Simulated LED strip, ws281x-like -->
|
<arg name="led" default="true"/> <!-- Simulated LED strip, ws281x-like -->
|
||||||
<arg name="gps" default="false"/> <!--Simulated GPS module -->
|
<arg name="gps" default="false"/> <!--Simulated GPS module -->
|
||||||
<arg name="use_clover_physics" default="false"/> <!-- Use inertial parameters from CAD models -->
|
<arg name="use_clover_physics" default="false"/> <!-- Use inertial parameters from CAD models -->
|
||||||
<arg name="gui" default="true"/> <!-- Run Gazebo with GUI -->
|
|
||||||
|
|
||||||
<!-- Gazebo instance -->
|
<!-- Gazebo instance -->
|
||||||
<include file="$(find gazebo_ros)/launch/empty_world.launch" if="$(eval type == 'gazebo')">
|
<include file="$(find gazebo_ros)/launch/empty_world.launch" if="$(eval type == 'gazebo')">
|
||||||
<!-- Workaround for crashes in VMware -->
|
<!-- Workaround for crashes in VMware -->
|
||||||
<env name="SVGA_VGPU10" value="0"/>
|
<env name="SVGA_VGPU10" value="0"/>
|
||||||
<arg name="gui" value="$(arg gui)"/>
|
<arg name="gui" value="true"/>
|
||||||
<arg name="world_name" value="$(find clover_simulation)/resources/worlds/clover_aruco.world"/>
|
<arg name="world_name" value="$(find clover_simulation)/resources/worlds/clover_aruco.world"/>
|
||||||
<arg name="verbose" value="true"/>
|
<arg name="verbose" value="true"/>
|
||||||
</include>
|
</include>
|
||||||
@@ -29,16 +27,13 @@
|
|||||||
<!-- Clover model -->
|
<!-- Clover model -->
|
||||||
<include file="$(find clover_description)/launch/spawn_drone.launch" if="$(eval type == 'gazebo')">
|
<include file="$(find clover_description)/launch/spawn_drone.launch" if="$(eval type == 'gazebo')">
|
||||||
<arg name="main_camera" value="$(arg main_camera)"/>
|
<arg name="main_camera" value="$(arg main_camera)"/>
|
||||||
<arg name="maintain_camera_rate" value="$(arg maintain_camera_rate)"/>
|
|
||||||
<arg name="rangefinder" value="$(arg rangefinder)"/>
|
<arg name="rangefinder" value="$(arg rangefinder)"/>
|
||||||
<arg name="led" value="$(arg led)"/>
|
<arg name="led" value="$(arg led)"/>
|
||||||
<arg name="gps" value="$(arg gps)"/>
|
<arg name="gps" value="$(arg gps)"/>
|
||||||
<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" 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)"/>
|
|
||||||
</node>
|
|
||||||
|
|
||||||
<param name="use_sim_time" value="false" if="$(eval type == 'jmavsim')"/>
|
<param name="use_sim_time" value="false" if="$(eval type == 'jmavsim')"/>
|
||||||
|
|
||||||
@@ -48,10 +43,10 @@
|
|||||||
<arg name="fcu_conn" value="sitl"/>
|
<arg name="fcu_conn" value="sitl"/>
|
||||||
<arg name="fcu_ip" value="127.0.0.1"/>
|
<arg name="fcu_ip" value="127.0.0.1"/>
|
||||||
<arg name="gcs_bridge" value=""/>
|
<arg name="gcs_bridge" value=""/>
|
||||||
|
<arg name="rc" default="false"/>
|
||||||
<arg name="web_video_server" default="false" if="$(eval type == 'jmavsim')"/>
|
<arg name="web_video_server" default="false" if="$(eval type == 'jmavsim')"/>
|
||||||
<arg name="main_camera" default="false" if="$(eval type == 'jmavsim')"/>
|
<arg name="main_camera" default="false" if="$(eval type == 'jmavsim')"/>
|
||||||
<arg name="aruco" default="false" if="$(eval type == 'jmavsim')"/>
|
<arg name="aruco" default="false" if="$(eval type == 'jmavsim')"/>
|
||||||
<arg name="optical_flow" default="false" if="$(eval type == 'jmavsim')"/>
|
|
||||||
<arg name="led" default="false" if="$(eval type == 'jmavsim')"/>
|
<arg name="led" default="false" if="$(eval type == 'jmavsim')"/>
|
||||||
</include>
|
</include>
|
||||||
</launch>
|
</launch>
|
||||||
|
|||||||
@@ -1,24 +0,0 @@
|
|||||||
<?xml version="1.0"?>
|
|
||||||
<sdf version="1.5">
|
|
||||||
<model name="aruco_100">
|
|
||||||
<static>true</static>
|
|
||||||
<link name="marker_100_link">
|
|
||||||
<pose>0 0 1e-3 0 0 1.5707963267948966</pose>
|
|
||||||
<visual name="visual_marker_100">
|
|
||||||
<cast_shadows>false</cast_shadows>
|
|
||||||
<geometry>
|
|
||||||
<box>
|
|
||||||
<size>0.22 0.22 1e-3</size>
|
|
||||||
</box>
|
|
||||||
</geometry>
|
|
||||||
<material>
|
|
||||||
<script>
|
|
||||||
<uri>model://aruco_100/materials/scripts</uri>
|
|
||||||
<uri>model://aruco_100/materials/textures</uri>
|
|
||||||
<name>aruco/marker_100</name>
|
|
||||||
</script>
|
|
||||||
</material>
|
|
||||||
</visual>
|
|
||||||
</link>
|
|
||||||
</model>
|
|
||||||
</sdf>
|
|
||||||
@@ -1,15 +0,0 @@
|
|||||||
material aruco/marker_100
|
|
||||||
{
|
|
||||||
technique
|
|
||||||
{
|
|
||||||
pass
|
|
||||||
{
|
|
||||||
texture_unit
|
|
||||||
{
|
|
||||||
texture aruco_marker_100.png
|
|
||||||
filtering none
|
|
||||||
scale 1.0 1.0
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
Binary file not shown.
|
Before Width: | Height: | Size: 94 B |
@@ -1,13 +0,0 @@
|
|||||||
<?xml version="1.0"?>
|
|
||||||
<model>
|
|
||||||
<name>ArUco Marker 100</name>
|
|
||||||
<version>1.0</version>
|
|
||||||
<sdf version="1.5">marker_100.sdf</sdf>
|
|
||||||
<author>
|
|
||||||
<name>Marker Generator script</name>
|
|
||||||
<email>marker@generator.sh</email>
|
|
||||||
</author>
|
|
||||||
<description>
|
|
||||||
ArUco marker #100
|
|
||||||
</description>
|
|
||||||
</model>
|
|
||||||
@@ -1,24 +0,0 @@
|
|||||||
<?xml version="1.0"?>
|
|
||||||
<sdf version="1.5">
|
|
||||||
<model name="aruco_101">
|
|
||||||
<static>true</static>
|
|
||||||
<link name="marker_101_link">
|
|
||||||
<pose>0 0 1e-3 0 0 1.5707963267948966</pose>
|
|
||||||
<visual name="visual_marker_101">
|
|
||||||
<cast_shadows>false</cast_shadows>
|
|
||||||
<geometry>
|
|
||||||
<box>
|
|
||||||
<size>0.44 0.44 1e-3</size>
|
|
||||||
</box>
|
|
||||||
</geometry>
|
|
||||||
<material>
|
|
||||||
<script>
|
|
||||||
<uri>model://aruco_101/materials/scripts</uri>
|
|
||||||
<uri>model://aruco_101/materials/textures</uri>
|
|
||||||
<name>aruco/marker_101</name>
|
|
||||||
</script>
|
|
||||||
</material>
|
|
||||||
</visual>
|
|
||||||
</link>
|
|
||||||
</model>
|
|
||||||
</sdf>
|
|
||||||
@@ -1,15 +0,0 @@
|
|||||||
material aruco/marker_101
|
|
||||||
{
|
|
||||||
technique
|
|
||||||
{
|
|
||||||
pass
|
|
||||||
{
|
|
||||||
texture_unit
|
|
||||||
{
|
|
||||||
texture aruco_marker_101.png
|
|
||||||
filtering none
|
|
||||||
scale 1.0 1.0
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
Binary file not shown.
|
Before Width: | Height: | Size: 94 B |
@@ -1,13 +0,0 @@
|
|||||||
<?xml version="1.0"?>
|
|
||||||
<model>
|
|
||||||
<name>ArUco Marker 101</name>
|
|
||||||
<version>1.0</version>
|
|
||||||
<sdf version="1.5">marker_101.sdf</sdf>
|
|
||||||
<author>
|
|
||||||
<name>Marker Generator script</name>
|
|
||||||
<email>marker@generator.sh</email>
|
|
||||||
</author>
|
|
||||||
<description>
|
|
||||||
ArUco marker #101
|
|
||||||
</description>
|
|
||||||
</model>
|
|
||||||
@@ -1,24 +0,0 @@
|
|||||||
<?xml version="1.0"?>
|
|
||||||
<sdf version="1.5">
|
|
||||||
<model name="aruco_102">
|
|
||||||
<static>true</static>
|
|
||||||
<link name="marker_102_link">
|
|
||||||
<pose>0 0 1e-3 0 0 1.5707963267948966</pose>
|
|
||||||
<visual name="visual_marker_102">
|
|
||||||
<cast_shadows>false</cast_shadows>
|
|
||||||
<geometry>
|
|
||||||
<box>
|
|
||||||
<size>0.44 0.44 1e-3</size>
|
|
||||||
</box>
|
|
||||||
</geometry>
|
|
||||||
<material>
|
|
||||||
<script>
|
|
||||||
<uri>model://aruco_102/materials/scripts</uri>
|
|
||||||
<uri>model://aruco_102/materials/textures</uri>
|
|
||||||
<name>aruco/marker_102</name>
|
|
||||||
</script>
|
|
||||||
</material>
|
|
||||||
</visual>
|
|
||||||
</link>
|
|
||||||
</model>
|
|
||||||
</sdf>
|
|
||||||
@@ -1,15 +0,0 @@
|
|||||||
material aruco/marker_102
|
|
||||||
{
|
|
||||||
technique
|
|
||||||
{
|
|
||||||
pass
|
|
||||||
{
|
|
||||||
texture_unit
|
|
||||||
{
|
|
||||||
texture aruco_marker_102.png
|
|
||||||
filtering none
|
|
||||||
scale 1.0 1.0
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
Binary file not shown.
|
Before Width: | Height: | Size: 94 B |
@@ -1,13 +0,0 @@
|
|||||||
<?xml version="1.0"?>
|
|
||||||
<model>
|
|
||||||
<name>ArUco Marker 102</name>
|
|
||||||
<version>1.0</version>
|
|
||||||
<sdf version="1.5">marker_102.sdf</sdf>
|
|
||||||
<author>
|
|
||||||
<name>Marker Generator script</name>
|
|
||||||
<email>marker@generator.sh</email>
|
|
||||||
</author>
|
|
||||||
<description>
|
|
||||||
ArUco marker #102
|
|
||||||
</description>
|
|
||||||
</model>
|
|
||||||
@@ -1,33 +0,0 @@
|
|||||||
<?xml version="1.0"?>
|
|
||||||
<sdf version="1.5">
|
|
||||||
<model name="camera">
|
|
||||||
<static>true</static>
|
|
||||||
<link name='camera_link'>
|
|
||||||
<pose>0 0 0 0 0 0</pose>
|
|
||||||
<sensor name='camera' type='camera'>
|
|
||||||
<camera>
|
|
||||||
<horizontal_fov>1.8</horizontal_fov>
|
|
||||||
<image>
|
|
||||||
<format>B8G8R8</format>
|
|
||||||
<width>640</width>
|
|
||||||
<height>480</height>
|
|
||||||
</image>
|
|
||||||
<clip>
|
|
||||||
<near>0.02</near>
|
|
||||||
<far>300</far>
|
|
||||||
</clip>
|
|
||||||
</camera>
|
|
||||||
<always_on>1</always_on>
|
|
||||||
<update_rate>30</update_rate>
|
|
||||||
<visualize>1</visualize>
|
|
||||||
<plugin name='camera_plugin' filename='libgazebo_ros_camera.so'>
|
|
||||||
<alwaysOn>1</alwaysOn>
|
|
||||||
<imageTopicName>image_raw</imageTopicName>
|
|
||||||
<cameraTopicName>camera_info</cameraTopicName>
|
|
||||||
<cameraName>camera</cameraName>
|
|
||||||
<frameName>/camera</frameName>
|
|
||||||
</plugin>
|
|
||||||
</sensor>
|
|
||||||
</link>
|
|
||||||
</model>
|
|
||||||
</sdf>
|
|
||||||
@@ -1,13 +0,0 @@
|
|||||||
<?xml version="1.0"?>
|
|
||||||
<model>
|
|
||||||
<name>Camera</name>
|
|
||||||
<version>1.0</version>
|
|
||||||
<sdf version="1.5">camera.sdf</sdf>
|
|
||||||
<author>
|
|
||||||
<name>Oleg Kalachev</name>
|
|
||||||
<email>okalachev@gmail.com</email>
|
|
||||||
</author>
|
|
||||||
<description>
|
|
||||||
External camera
|
|
||||||
</description>
|
|
||||||
</model>
|
|
||||||
@@ -1,6 +1,6 @@
|
|||||||
<package format="2">
|
<package format="2">
|
||||||
<name>clover_simulation</name>
|
<name>clover_simulation</name>
|
||||||
<version>0.23.0</version>
|
<version>0.21.1</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>
|
||||||
|
|
||||||
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>
|
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>
|
||||||
|
|||||||
@@ -1,8 +0,0 @@
|
|||||||
#!/usr/bin/env bash
|
|
||||||
|
|
||||||
# script for running gzweb
|
|
||||||
# usage: ./gzweb [<port>]
|
|
||||||
|
|
||||||
export NVM_DIR=$HOME/.nvm
|
|
||||||
source $NVM_DIR/nvm.sh
|
|
||||||
npm start --prefix $HOME/gzweb -p ${1-8080}
|
|
||||||
@@ -41,4 +41,4 @@ def save_world(world, file):
|
|||||||
'''
|
'''
|
||||||
Save the world to file-like object
|
Save the world to file-like object
|
||||||
'''
|
'''
|
||||||
return world.write(file, encoding='unicode')
|
return world.write(file)
|
||||||
|
|||||||
@@ -49,9 +49,14 @@ private:
|
|||||||
|
|
||||||
std::unique_ptr<ros::NodeHandle> nh;
|
std::unique_ptr<ros::NodeHandle> nh;
|
||||||
|
|
||||||
|
ros::ServiceServer setLedsSrv;
|
||||||
|
// Note: LED state should only be published by the /gazebo node
|
||||||
|
led_msgs::LEDStateArray ledState;
|
||||||
|
ros::Publisher statePublisher;
|
||||||
// LED state will be read from the topic to avoid creating more services
|
// LED state will be read from the topic to avoid creating more services
|
||||||
ros::Subscriber stateSubscriber;
|
ros::Subscriber stateSubscriber;
|
||||||
|
|
||||||
|
bool setLeds(led_msgs::SetLEDs::Request& req, led_msgs::SetLEDs::Response& resp);
|
||||||
void handleLedsMsg(const led_msgs::LEDStateArrayConstPtr& leds);
|
void handleLedsMsg(const led_msgs::LEDStateArrayConstPtr& leds);
|
||||||
|
|
||||||
public:
|
public:
|
||||||
@@ -68,8 +73,16 @@ public:
|
|||||||
ROS_INFO_NAMED(("LedController_" + robotNamespace).c_str(), "LedController has started (as %s)", role == Role::Client ? "client" : "server");
|
ROS_INFO_NAMED(("LedController_" + robotNamespace).c_str(), "LedController has started (as %s)", role == Role::Client ? "client" : "server");
|
||||||
|
|
||||||
nh.reset(new ros::NodeHandle(robotNamespace));
|
nh.reset(new ros::NodeHandle(robotNamespace));
|
||||||
|
if (role == Role::Server)
|
||||||
|
{
|
||||||
|
setLedsSrv = nh->advertiseService("led/set_leds", &LedController::setLeds, this);
|
||||||
|
statePublisher = nh->advertise<led_msgs::LEDStateArray>("led/state", 1, true);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
// LED state should be published to the "led/state" topic, so we grab our data there
|
||||||
stateSubscriber = nh->subscribe<led_msgs::LEDStateArray>("led/state", 1, &LedController::handleLedsMsg, this);
|
stateSubscriber = nh->subscribe<led_msgs::LEDStateArray>("led/state", 1, &LedController::handleLedsMsg, this);
|
||||||
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
~LedController()
|
~LedController()
|
||||||
@@ -83,9 +96,13 @@ public:
|
|||||||
std::lock_guard<std::mutex> lock(registryMutex);
|
std::lock_guard<std::mutex> lock(registryMutex);
|
||||||
if (totalLeds > 0) {
|
if (totalLeds > 0) {
|
||||||
registeredLeds.resize(totalLeds);
|
registeredLeds.resize(totalLeds);
|
||||||
|
ledState.leds.resize(totalLeds);
|
||||||
}
|
}
|
||||||
ROS_DEBUG_NAMED(("LedController_" + robotNamespace).c_str(), "Registering LED visual plugin to %s (LED id=%d)", (role == Role::Client) ? "client" : "server", ledIdx);
|
ROS_DEBUG_NAMED(("LedController_" + robotNamespace).c_str(), "Registering LED visual plugin to %s (LED id=%d)", (role == Role::Client) ? "client" : "server", ledIdx);
|
||||||
registeredLeds[ledIdx] = plugin;
|
registeredLeds[ledIdx] = plugin;
|
||||||
|
ledState.leds[ledIdx].index = ledIdx;
|
||||||
|
if (role == Role::Server)
|
||||||
|
statePublisher.publish(ledState);
|
||||||
}
|
}
|
||||||
|
|
||||||
void unregisterPlugin(sim_led::LedVisualPlugin* plugin)
|
void unregisterPlugin(sim_led::LedVisualPlugin* plugin)
|
||||||
@@ -140,8 +157,7 @@ public:
|
|||||||
{
|
{
|
||||||
auto indexStr = parentName.substr(lastDashPos + 1);
|
auto indexStr = parentName.substr(lastDashPos + 1);
|
||||||
try {
|
try {
|
||||||
if (indexStr == "visual") myIndex = 0; // the first visual doesn't have index
|
myIndex = std::stoi(indexStr);
|
||||||
else myIndex = std::stoi(indexStr);
|
|
||||||
} catch(const std::exception &e) {
|
} catch(const std::exception &e) {
|
||||||
gzwarn << "Failed to convert " << indexStr << " to integer: " << e.what() << ", assuming 0\n";
|
gzwarn << "Failed to convert " << indexStr << " to integer: " << e.what() << ", assuming 0\n";
|
||||||
myIndex = 0;
|
myIndex = 0;
|
||||||
@@ -179,6 +195,26 @@ public:
|
|||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// FIXME: These two functions basically do the same thing, maybe they can be merged?
|
||||||
|
bool led_controller::LedController::setLeds(led_msgs::SetLEDs::Request &req, led_msgs::SetLEDs::Response &resp)
|
||||||
|
{
|
||||||
|
std::lock_guard<std::mutex> lock(registryMutex);
|
||||||
|
for(const auto& led : req.leds)
|
||||||
|
{
|
||||||
|
if (led.index < registeredLeds.size()) {
|
||||||
|
auto color = GazeboColor(led.r / 255.0f, led.g / 255.0f, led.b / 255.0f);
|
||||||
|
auto ledPlugin = registeredLeds[led.index];
|
||||||
|
if (ledPlugin) ledPlugin->SetColor(color);
|
||||||
|
ledState.leds[led.index].r = led.r;
|
||||||
|
ledState.leds[led.index].g = led.g;
|
||||||
|
ledState.leds[led.index].b = led.b;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
statePublisher.publish(ledState);
|
||||||
|
resp.success = true;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
void led_controller::LedController::handleLedsMsg(const led_msgs::LEDStateArrayConstPtr& leds)
|
void led_controller::LedController::handleLedsMsg(const led_msgs::LEDStateArrayConstPtr& leds)
|
||||||
{
|
{
|
||||||
std::lock_guard<std::mutex> lock(registryMutex);
|
std::lock_guard<std::mutex> lock(registryMutex);
|
||||||
|
|||||||
@@ -1,71 +0,0 @@
|
|||||||
#include <led_msgs/SetLEDs.h>
|
|
||||||
#include <led_msgs/LEDStateArray.h>
|
|
||||||
|
|
||||||
#include <ros/ros.h>
|
|
||||||
|
|
||||||
#include <gazebo/gazebo.hh>
|
|
||||||
#include <gazebo/physics/physics.hh>
|
|
||||||
#include <gazebo/common/common.hh>
|
|
||||||
|
|
||||||
class LedControllerPlugin : public gazebo::ModelPlugin {
|
|
||||||
private:
|
|
||||||
std::unique_ptr<ros::NodeHandle> nh;
|
|
||||||
std::string ns;
|
|
||||||
ros::ServiceServer setLedsSrv;
|
|
||||||
led_msgs::LEDStateArray ledState;
|
|
||||||
ros::Publisher statePublisher;
|
|
||||||
std::mutex handleMutex;
|
|
||||||
|
|
||||||
public:
|
|
||||||
bool setLeds(led_msgs::SetLEDs::Request &req, led_msgs::SetLEDs::Response &resp)
|
|
||||||
{
|
|
||||||
std::lock_guard<std::mutex> lock(handleMutex);
|
|
||||||
for(const auto& led : req.leds)
|
|
||||||
{
|
|
||||||
if (led.index < ledState.leds.size()) {
|
|
||||||
ledState.leds[led.index].r = led.r;
|
|
||||||
ledState.leds[led.index].g = led.g;
|
|
||||||
ledState.leds[led.index].b = led.b;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
statePublisher.publish(ledState);
|
|
||||||
resp.success = true;
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
virtual void Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) override
|
|
||||||
{
|
|
||||||
ROS_INFO("Initialize LED Controller");
|
|
||||||
|
|
||||||
// We need "libgazebo_ros_api.so" to be loaded
|
|
||||||
if (!ros::isInitialized())
|
|
||||||
{
|
|
||||||
ROS_FATAL_NAMED("LedController", "Tried to load ROS plugin when ROS Gazebo API is not loaded. Please use gazebo_ros node to"
|
|
||||||
"launch Gazebo.");
|
|
||||||
}
|
|
||||||
|
|
||||||
ns = "";
|
|
||||||
|
|
||||||
if (sdf->HasElement("robotNamespace")) {
|
|
||||||
ns = sdf->Get<std::string>("robotNamespace");
|
|
||||||
}
|
|
||||||
if (!sdf->HasElement("ledCount")) {
|
|
||||||
gzerr << "ledCount is not set, but is required for the plugin to function correctly\n";
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
int totalLeds = sdf->Get<int>("ledCount");
|
|
||||||
ledState.leds.resize(totalLeds);
|
|
||||||
for (int i = 0; i < totalLeds; i++) {
|
|
||||||
ledState.leds[i].index = i;
|
|
||||||
}
|
|
||||||
|
|
||||||
nh.reset(new ros::NodeHandle(ns));
|
|
||||||
|
|
||||||
setLedsSrv = nh->advertiseService("led/set_leds", &LedControllerPlugin::setLeds, this);
|
|
||||||
statePublisher = nh->advertise<led_msgs::LEDStateArray>("led/state", 1, true);
|
|
||||||
|
|
||||||
statePublisher.publish(ledState);
|
|
||||||
}
|
|
||||||
};
|
|
||||||
|
|
||||||
GZ_REGISTER_MODEL_PLUGIN(LedControllerPlugin);
|
|
||||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user