Compare commits

..

30 Commits

Author SHA1 Message Date
Oleg Kalachev
aa89077c23 Merge branch 'master' into terrain-frame 2022-10-13 00:08:46 +06:00
Oleg Kalachev
4e9d8a64d0 simple_offboard: test for simple_offboard/release service presence 2022-10-13 00:08:35 +06:00
Oleg Kalachev
94171d51ac simple_offboard: implement simple_offboard/release service 2022-10-13 00:07:27 +06:00
Oleg Kalachev
0d45b6cb7f Allow setting Z with yaw=0 2022-10-12 23:07:25 +06:00
Oleg Kalachev
eb448ae0e7 main_camera.launch: run image_raw_throttled topic by default (#248) 2022-10-12 00:25:12 +06:00
Oleg Kalachev
c0707e066a actions: build Debian packages and upload to artifacts (#458) 2022-10-05 16:10:17 +06:00
Oleg Kalachev
91c6998633 docs: add snippet to subscribe and decode incoming mavlink messages 2022-09-29 13:58:02 +05:00
Sergey Stetsky
7b431fa021 docs: add command for updating markers map in the sim (#456)
Co-authored-by: Oleg Kalachev <okalachev@gmail.com>
2022-09-23 20:15:57 +03:00
Oleg Kalachev
d61760a718 simple_offboard: add terrain frame 2022-09-23 00:30:42 +03:00
Oleg Kalachev
1e12498cb2 Install GeographicLib datasets in build workflow 2022-09-14 14:19:06 +03:00
Oleg Kalachev
43037f515d aruco_detect: check for duplicates in marker transforms, send all transforms in one message 2022-09-14 12:55:27 +03:00
Oleg Kalachev
2ea848721c aruco_pose: add duplicate test to CMakeLists.txt 2022-09-14 12:46:04 +03:00
Oleg Kalachev
d06b0a0cd2 aruco_pose: implement test for TF_REPEATED_DATA when multiple markers with the same ID 2022-09-14 12:35:16 +03:00
Oleg Kalachev
1efe10c9dd Simplify script for testing native Noetic build 2022-09-10 15:26:34 +03:00
Oleg Kalachev
24cd1f6fac Show number of messages received in topic viewer 2022-09-10 08:08:09 +03:00
Oleg Kalachev
5223bef5e7 Fix error when viewing messages without header in topic viewer 2022-09-10 01:31:38 +03:00
Oleg Kalachev
105eac7e1d clover.launch: make force_init argument overridable externally 2022-09-08 14:42:45 +03:00
Oleg Kalachev
c1d6ed27aa mavros.launch: fix fcu_url for hitl connection 2022-09-08 01:32:51 +03:00
Oleg Kalachev
614784e949 mavros.launch: add hitl option for fcu_conn argument 2022-09-07 00:55:13 +03:00
Oleg Kalachev
9376c017b4 selfcheck.py: skip boot duration check on not Clover image 2022-09-03 22:53:38 +03:00
Oleg Kalachev
b5d300e218 optical_flow: timeout for previous frame
For cases when optical flow is dynamically disabled and enabled back
2022-09-03 07:26:25 +03:00
Oleg Kalachev
efb44484b0 Remove obsolete note from readme 2022-08-26 22:51:08 +03:00
Oleg Kalachev
0a2ad3d64f docs: remove some obsolete notes about renaming 2022-08-26 22:50:55 +03:00
oponfil
ffe2d3d5e4 docs: update connection article (en) (#363)
* Add instructions on how to connect FMU to Raspberry Pi by UART

* Remove sitl connection section

Co-authored-by: Oleg Kalachev <okalachev@gmail.com>
2022-08-26 22:36:11 +03:00
oponfil
81f4795aec docs: update connection article (#362)
* Add instructions on how to connect FMU to Raspberry Pi by UART

* Remove inactual sitl connection

Co-authored-by: Oleg Kalachev <okalachev@gmail.com>
2022-08-26 22:35:40 +03:00
oponfil
596ed3dcf2 docs: docs: correction in mavros article on global setpoints (en) (#358)
Co-authored-by: Oleg Kalachev <okalachev@gmail.com>
2022-08-26 22:09:56 +03:00
oponfil
63c71fc331 docs: correction in mavros article on global setpoints (#357)
Co-authored-by: Oleg Kalachev <okalachev@gmail.com>
2022-08-26 22:08:22 +03:00
Oleg Kalachev
0efb249d9b docs: update PX4 to v1.12.3 in native simulation installation article 2022-08-26 16:05:28 +03:00
Oleg Kalachev
47c6e5aa9b docs: comment out link to install_software.sh in simulation installation manual
The link confuses users so they often try to run it
2022-08-25 18:28:52 +03:00
Oleg Kalachev
687a4f50fd Fix python-pymavlink installation adding some lxml dependencies
Otherwise installation falls with:
Error: Please make sure the libxml2 and libxslt development packages are installed
2022-08-24 22:42:18 +03:00
34 changed files with 284 additions and 125 deletions

View File

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

View File

@@ -1,23 +0,0 @@
name: Build docs Docker image
on:
workflow_dispatch:
push:
branches: [ '*' ]
jobs:
docs-docker:
runs-on: ubuntu-22.04
steps:
- uses: actions/checkout@v2
- name: Build Docker image
run: docker build -t clover-docs:latest docs
- name: Test Docker image
run: docker run -t --rm -v `pwd`:/clover clover-docs:latest
- name: Show results
run: |
ls -lh _book
ls -lh *.pdf

View File

@@ -251,4 +251,5 @@ if (CATKIN_ENABLE_TESTING)
add_rostest(test/test_node_failure.test)
add_rostest(test/largemap.test)
add_rostest(test/crash_opencv.test)
add_rostest(test/duplicate.test)
endif()

View File

@@ -187,6 +187,8 @@ private:
array_.markers.reserve(ids.size());
aruco_pose::Marker marker;
vector<geometry_msgs::TransformStamped> transforms;
transforms.reserve(ids.size());
geometry_msgs::TransformStamped transform;
transform.header.stamp = msg->header.stamp;
transform.header.frame_id = msg->header.frame_id;
@@ -204,20 +206,33 @@ private:
snapOrientation(marker.pose.orientation, snap_to.transform.rotation, auto_flip_);
}
// TODO: check IDs are unique
if (send_tf_) {
transform.child_frame_id = getChildFrameId(ids[i]);
// check if such static transform is in the map
if (map_markers_ids_.find(ids[i]) == map_markers_ids_.end()) {
transform.transform.rotation = marker.pose.orientation;
fillTranslation(transform.transform.translation, tvecs[i]);
br_->sendTransform(transform);
// check if a markers with that id is already added
bool send = true;
for (auto &t : transforms) {
if (t.child_frame_id == transform.child_frame_id) {
send = false;
break;
}
}
if (send) {
transform.transform.rotation = marker.pose.orientation;
fillTranslation(transform.transform.translation, tvecs[i]);
transforms.push_back(transform);
}
}
}
}
array_.markers.push_back(marker);
}
if (send_tf_) {
br_->sendTransform(transforms);
}
}
markers_pub_.publish(array_);

Binary file not shown.

After

Width:  |  Height:  |  Size: 62 KiB

View File

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

View File

@@ -0,0 +1,21 @@
<launch>
<node pkg="image_publisher" type="image_publisher" name="main_camera" args="$(find aruco_pose)/test/duplicate.png">
<param name="frame_id" value="main_camera_optical"/>
<param name="publish_rate" value="10"/>
<param name="camera_info_url" value="file://$(find aruco_pose)/test/camera_info.yaml" />
</node>
<node pkg="nodelet" type="nodelet" name="nodelet_manager" args="manager" required="true"/>
<node pkg="nodelet" clear_params="true" type="nodelet" name="aruco_detect" args="load aruco_pose/aruco_detect nodelet_manager" required="true">
<remap from="image_raw" to="main_camera/image_raw"/>
<remap from="camera_info" to="main_camera/camera_info"/>
<param name="length" value="0.33"/>
<param name="estimate_poses" value="true"/>
<param name="send_tf" value="true"/>
<param name="cornerRefinementMethod" value="1"/>
</node>
<param name="test_module" value="$(find aruco_pose)/test/duplicate.py"/>
<test test-name="aruco_pose_test" pkg="ros_pytest" type="ros_pytest_runner"/>
</launch>

View File

@@ -12,7 +12,7 @@
<arg name="led" default="true"/>
<arg name="blocks" default="false"/>
<arg name="rc" default="false"/>
<arg name="force_init" value="true"/> <!-- force estimator to init by publishing zero pose -->
<arg name="force_init" default="true"/> <!-- force estimator to init by publishing zero pose -->
<arg name="simulator" default="false"/> <!-- flag that we are operating on a simulated drone -->

View File

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

View File

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

View File

@@ -37,6 +37,8 @@
<depend>rosbridge_server</depend>
<depend>web_video_server</depend>
<depend>tf2_web_republisher</depend>
<depend>libxml2</depend>
<depend>libxslt</depend>
<depend condition="$ROS_PYTHON_VERSION == 2">python-lxml</depend>
<depend condition="$ROS_PYTHON_VERSION == 3">python3-lxml</depend>
<depend>dynamic_reconfigure</depend>

View File

@@ -154,7 +154,7 @@ private:
img.convertTo(curr_, CV_32F);
if (prev_.empty()) {
if (prev_.empty() || (msg->header.stamp - prev_stamp_).toSec() > 0.1) { // outdated previous frame
prev_ = curr_.clone();
prev_stamp_ = msg->header.stamp;
cv::createHanningWindow(hann_, curr_.size(), CV_32F);

View File

@@ -625,6 +625,10 @@ def check_rangefinder():
@check('Boot duration')
def check_boot_duration():
if not os.path.exists('/etc/clover_version'):
info('skip check')
return # Don't check not on Clover's image
output = subprocess.check_output('systemd-analyze').decode()
r = re.compile(r'([\d\.]+)s\s*$', flags=re.MULTILINE)
duration = float(r.search(output).groups()[0])

View File

@@ -37,6 +37,7 @@
#include <mavros_msgs/State.h>
#include <mavros_msgs/StatusText.h>
#include <mavros_msgs/ManualControl.h>
#include <mavros_msgs/Altitude.h>
#include <clover/GetTelemetry.h>
#include <clover/Navigate.h>
@@ -54,6 +55,7 @@ using namespace clover;
using mavros_msgs::PositionTarget;
using mavros_msgs::AttitudeTarget;
using mavros_msgs::Thrust;
using mavros_msgs::Altitude;
// tf2
tf2_ros::Buffer tf_buffer;
@@ -96,10 +98,12 @@ Thrust thrust_msg;
TwistStamped rates_msg;
TransformStamped target, setpoint;
geometry_msgs::TransformStamped body;
geometry_msgs::TransformStamped terrain;
// State
PoseStamped nav_start;
PoseStamped setpoint_position, setpoint_position_transformed;
Vector3Stamped setpoint_z, setpoint_z_transformed; // for z-only commands
Vector3Stamped setpoint_velocity, setpoint_velocity_transformed;
QuaternionStamped setpoint_attitude, setpoint_attitude_transformed;
float setpoint_yaw_rate;
@@ -122,6 +126,8 @@ enum setpoint_type_t setpoint_type = NONE;
enum { YAW, YAW_RATE, TOWARDS } setpoint_yaw_type;
bool setpoint_z_valid = false;
// Last received telemetry messages
mavros_msgs::State state;
mavros_msgs::StatusText statustext;
@@ -173,6 +179,15 @@ void handleLocalPosition(const PoseStamped& pose)
// TODO: terrain?, home?
}
void handleAltitude(const Altitude& alt)
{
// publish terrain frame
if (!std::isfinite(alt.bottom_clearance)) return;
terrain.header.stamp = alt.header.stamp;
terrain.transform.translation.z = -alt.bottom_clearance;
transform_broadcaster->sendTransform(terrain);
}
// wait for transform without interrupting publishing setpoints
inline bool waitTransform(const string& target, const string& source,
const ros::Time& stamp, const ros::Duration& timeout) // editorconfig-checker-disable-line
@@ -421,6 +436,18 @@ void publish(const ros::Time stamp)
}
}
if (setpoint_z_valid && setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL || setpoint_type == POSITION) {
setpoint_z.header.stamp = stamp;
try {
tf_buffer.transform(setpoint_z, setpoint_z_transformed, local_frame, ros::Duration(0.05));
setpoint_position_transformed.pose.position.z = setpoint_z_transformed.vector.z;
} catch (const tf2::TransformException& e) {
ROS_WARN_THROTTLE(10, "can't transform z coordinate from %s to %s, ignoring z coordinate",
setpoint_z.header.frame_id.c_str(), local_frame.c_str());
}
}
if (setpoint_type == POSITION) {
position_msg = setpoint_position_transformed;
}
@@ -556,7 +583,7 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
// look up for reference frame
auto search = reference_frames.find(frame_id);
const string& reference_frame = search == reference_frames.end() ? frame_id : search->second;
const string& reference_frame = search == reference_frames.end() ? frame_id : search->second; // when not found it's the same frame
// Serve "partial" commands
@@ -583,22 +610,33 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
}
}
if (!auto_arm && std::isfinite(yaw_rate) &&
isnan(x) && isnan(y) && isnan(z) && isnan(vx) && isnan(vy) && isnan(vz) &&
isnan(pitch) && isnan(roll) && isnan(yaw) && isnan(thrust) &&
if (!auto_arm && std::isfinite(z) &&
isnan(x) && isnan(y) && isnan(vx) && isnan(vy) && isnan(vz) &&
isnan(pitch) && isnan(roll) && isnan(thrust) &&
isnan(lat) && isnan(lon)) {
// change only the yaw rate
if (setpoint_type == POSITION || setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL || setpoint_type == VELOCITY) {
message = "Changing yaw rate only";
// set only the z
if (setpoint_type == POSITION || setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL) {
if (!waitTransform(setpoint_position.header.frame_id, frame_id, stamp, transform_timeout))
throw std::runtime_error("Can't transform from " + frame_id + " to " + setpoint_position.header.frame_id);
setpoint_yaw_type = YAW_RATE;
setpoint_yaw_rate = yaw_rate;
message = "Changing z only";
setpoint_z.header.frame_id = frame_id;
setpoint_z.header.stamp = stamp;
setpoint_z.vector.z = z;
setpoint_z_valid = true;
goto publish_setpoint;
} else {
throw std::runtime_error("Setting yaw rate is possible only when position or velocity setpoints active");
throw std::runtime_error("Setting z is possible only when position setpoint active");
}
}
// commands without z
if (isnan(z) && setpoint_z_valid && (sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL || sp_type == POSITION)) {
z = 0;
}
// Serve normal commands
if (sp_type == NAVIGATE || sp_type == POSITION) {
@@ -860,6 +898,13 @@ bool land(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
return false;
}
bool release(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
{
setpoint_timer.stop();
res.success = true;
return true;
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "simple_offboard");
@@ -881,6 +926,7 @@ int main(int argc, char **argv)
nh_priv.param("check_kill_switch", check_kill_switch, true);
nh_priv.param("default_speed", default_speed, 0.5f);
nh_priv.param<string>("body_frame", body.child_frame_id, "body");
nh_priv.param<string>("terrain_frame", terrain.child_frame_id, "terrain");
nh_priv.getParam("reference_frames", reference_frames);
// Default reference frames
@@ -916,6 +962,13 @@ int main(int argc, char **argv)
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);
ros::Subscriber altitude_sub;
if (!body.child_frame_id.empty() && !terrain.child_frame_id.empty()) {
terrain.header.frame_id = body.child_frame_id;
terrain.transform.rotation = tf::createQuaternionMsgFromRollPitchYaw(0, 0, 0);
altitude_sub = nh.subscribe(mavros + "/altitude", 1, &handleAltitude);
}
// Setpoint publishers
position_pub = nh.advertise<PoseStamped>(mavros + "/setpoint_position/local", 1);
position_raw_pub = nh.advertise<PositionTarget>(mavros + "/setpoint_raw/local", 1);
@@ -933,6 +986,7 @@ int main(int argc, char **argv)
auto sa_serv = nh.advertiseService("set_attitude", &setAttitude);
auto sr_serv = nh.advertiseService("set_rates", &setRates);
auto ld_serv = nh.advertiseService("land", &land);
auto rl_serv = nh_priv.advertiseService("release", &release);
// Setpoint timer
setpoint_timer = nh.createTimer(ros::Duration(1 / nh_priv.param("setpoint_rate", 30.0)), &publishSetpoint, false, false);

View File

@@ -24,6 +24,7 @@ def test_simple_offboard_services_available():
rospy.wait_for_service('set_attitude', timeout=5)
rospy.wait_for_service('set_rates', timeout=5)
rospy.wait_for_service('land', timeout=5)
rospy.wait_for_service('simple_offboard/release', timeout=5)
def test_web_video_server(node):
try:

View File

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

View File

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

View File

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

View File

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

View File

@@ -1,36 +0,0 @@
# Build: sudo docker build -t clover-docs:latest .
# Run: docker run -it --rm -v ~/clover:/clover clover-docs:latest
# Save image: sudo docker save clover-docs:latest | gzip > clover-docs.tar.gz
FROM ubuntu:22.04
ENV DEBIAN_FRONTEND=noninteractive
RUN apt-get update && apt-get install -y curl git
RUN curl https://raw.githubusercontent.com/creationix/nvm/master/install.sh | bash
RUN . $HOME/.nvm/nvm.sh && nvm install 10.15 && nvm use 10.15 && npm --version
RUN echo ttf-mscorefonts-installer msttcorefonts/accepted-mscorefonts-eula select true | debconf-set-selections \
&& apt-get update \
&& apt-get install -y calibre msttcorefonts ghostscript
RUN . $HOME/.nvm/nvm.sh && curl https://raw.githubusercontent.com/CopterExpress/clover/master/builder/assets/install_gitbook.sh | bash
# RUN . $HOME/.nvm/nvm.sh && npm install markdownlint-cli@0.28.1 -g && PUPPETEER_SKIP_DOWNLOAD=1 npm install svgexport -g
RUN . $HOME/.nvm/nvm.sh && npm install markdownlint-cli@0.28.1 -g && npm install svgexport -g --unsafe-perm
RUN . $HOME/.nvm/nvm.sh && node -v && gitbook -V && markdownlint -V
RUN curl https://raw.githubusercontent.com/CopterExpress/clover/master/book.json > book.json
RUN . $HOME/.nvm/nvm.sh && gitbook install
CMD . $HOME/.nvm/nvm.sh && export QTWEBENGINE_DISABLE_SANDBOX=1 && cp -r node_modules /clover && cd /clover && gitbook build \
&& gitbook pdf ./ _book/clover.pdf && \
gs -sDEVICE=pdfwrite -dCompatibilityLevel=1.4 -dPDFSETTINGS=/default -dNOPAUSE -dQUIET -dBATCH -dDetectDuplicateImages -dCompressFonts=true -r150 -sOutputFile=_book/clover_ru_compressed.pdf _book/clover_ru.pdf && \
gs -sDEVICE=pdfwrite -dCompatibilityLevel=1.4 -dPDFSETTINGS=/default -dNOPAUSE -dQUIET -dBATCH -dDetectDuplicateImages -dCompressFonts=true -r150 -sOutputFile=_book/clover_en_compressed.pdf _book/clover_en.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

View File

@@ -1,7 +1,5 @@
# Working with the camera
> **Note** In the image version **0.20** `clever` package was renamed to `clover`. See [previous version of the article](https://github.com/CopterExpress/clover/blob/v0.19/docs/en/camera.md) for older images.
Make sure the camera is enabled in the `~/catkin_ws/src/clover/clover/launch/clover.launch` file:
```xml
@@ -147,6 +145,8 @@ rospy.spin()
The script will take up to 100% CPU capacity. To slow down the script artificially, you can use [throttling](http://wiki.ros.org/topic_tools/throttle) of frames from the camera, for example, at 5 Hz (`main_camera.launch`):
> **Note** Starting from [image](image.md) version **0.24** `image_raw_throttled` topic is available without addition configuration.
```xml
<node pkg="topic_tools" name="cam_throttle" type="throttle"
args="messages main_camera/image_raw 5.0 main_camera/image_raw_throttled"/>

View File

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

View File

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

View File

@@ -305,6 +305,16 @@ rosservice call /land "{}"
> **Caution** In recent PX4 versions, the vehicle will be switched out of LAND mode to manual mode, if the remote control sticks are moved significantly.
### release
If it's necessary to pause sending setpoint messages, use the `simple_offboard/release` service:
```python
release = rospy.ServiceProxy('simple_offboard/release', Trigger)
release()
```
## Additional materials
* [ArUco-based position estimation and navigation](aruco.md).

View File

@@ -2,7 +2,7 @@
Setting up the simulation environment from scratch requires some effort, but results in the most performant setup, with less chance of driver issues.
> **Hint** See up-to-date commands set for installation Clover simulation software in the script, that builds the virtual machine image with the simulator: [`install_software.sh`](https://github.com/CopterExpress/clover_vm/blob/master/scripts/install_software.sh).
<!-- > **Hint** See up-to-date commands set for installation Clover simulation software in the script, that builds the virtual machine image with the simulator: [`install_software.sh`](https://github.com/CopterExpress/clover_vm/blob/master/scripts/install_software.sh). -->
Prerequisites: **Ubuntu 20.04**.
@@ -66,7 +66,7 @@ PX4 will be built along with the other packages in our workspace. You may clone
Clone PX4 sources and make the required symlinks:
```bash
git clone --recursive --depth 1 --branch v1.12.0 https://github.com/PX4/PX4-Autopilot.git ~/PX4-Autopilot
git clone --recursive --depth 1 --branch v1.12.3 https://github.com/PX4/PX4-Autopilot.git ~/PX4-Autopilot
ln -s ~/PX4-Autopilot ~/catkin_ws/src/
ln -s ~/PX4-Autopilot/Tools/sitl_gazebo ~/catkin_ws/src/
ln -s ~/PX4-Autopilot/mavlink ~/catkin_ws/src/

View File

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

View File

@@ -240,6 +240,30 @@ ros_msg = mavlink.convert_to_rosmsg(msg)
mavlink_pub.publish(ros_msg)
```
<!-- markdownlint-disable MD044 -->
### # {#mavlink-receive}
<!-- markdownlint-enable MD044 -->
Subscribe to all MAVLink messages from the flight controller and decode them:
```python
from mavros_msgs.msg import Mavlink
from mavros import mavlink
from pymavlink import mavutil
link = mavutil.mavlink.MAVLink('', 255, 1)
def mavlink_cb(msg):
mav_msg = link.decode(mavlink.convert_to_bytes(msg))
print('msgid =', msg.msgid, mav_msg) # print message id and parsed message
mavlink_sub = rospy.Subscriber('mavlink/from', Mavlink, mavlink_cb)
rospy.spin()
```
### # {#rc-sub}
React to the drone's mode switching (may be used for starting an autonomous flight, see [example](https://gist.github.com/okalachev/b709f04522d2f9af97e835baedeb806b)):

View File

@@ -1,7 +1,5 @@
# Работа с камерой
> **Note** В версии образа **0.20** пакет и сервис `clever` был переименован в `clover`. Для более ранних версий см. документацию для версии [**0.19**](https://github.com/CopterExpress/clover/blob/v0.19/docs/ru/camera.md).
<!-- TODO: физическое подключение -->
Для работы с основной камерой необходимо убедиться что она включена в файле `~/catkin_ws/src/clover/clover/launch/clover.launch`:
@@ -149,6 +147,8 @@ rospy.spin()
Скрипт будет занимать 100% процессора. Для искусственного замедления работы скрипта можно запустить [throttling](http://wiki.ros.org/topic_tools/throttle) кадров с камеры, например, в 5 Гц (`main_camera.launch`):
> **Note** Начиная с версии [образа](image.md) **0.24** топик `image_raw_throttled` доступен без дополнительной конфигурации.
```xml
<node pkg="topic_tools" name="cam_throttle" type="throttle"
args="messages main_camera/image_raw 5.0 main_camera/image_raw_throttled"/>

View File

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

View File

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

View File

@@ -305,6 +305,16 @@ rosservice call /land "{}"
> **Caution** В более новых версиях PX4 коптер выйдет из режима LAND в ручной режим, если сильно перемещать стики.
### release
В случае необходимости приостановки отправки setpoint-сообщений, используйте сервис `simple_offboard/release`:
```python
release = rospy.ServiceProxy('simple_offboard/release', Trigger)
release()
```
## Дополнительные материалы
* [Полеты в поле ArUco-маркеров](aruco.md).

View File

@@ -2,7 +2,7 @@
Настройка среды для симуляции с нуля требует некоторых усилий, однако это приведет к улучшению производительности и к уменьшению вероятности появления проблем с драйверами.
> **Hint** Смотрите актуальный набор команд установки необходимого ПО для запуска симулятора Клевера в скрипте сборки виртуальной машины с симулятором: [`install_software.sh`](https://github.com/CopterExpress/clover_vm/blob/master/scripts/install_software.sh).
<!-- > **Hint** Смотрите актуальный набор команд установки необходимого ПО для запуска симулятора Клевера в скрипте сборки виртуальной машины с симулятором: [`install_software.sh`](https://github.com/CopterExpress/clover_vm/blob/master/scripts/install_software.sh). -->
Требования для сборки: **Ubuntu 20.04**.
@@ -66,7 +66,7 @@ sudo /usr/bin/python3 -m pip install -r ~/catkin_ws/src/clover/clover/requiremen
Склонируйте исходный код PX4 и создайте необходимые симлинки:
```bash
git clone --recursive --depth 1 --branch v1.12.0 https://github.com/PX4/PX4-Autopilot.git ~/PX4-Autopilot
git clone --recursive --depth 1 --branch v1.12.3 https://github.com/PX4/PX4-Autopilot.git ~/PX4-Autopilot
ln -s ~/PX4-Autopilot ~/catkin_ws/src/
ln -s ~/PX4-Autopilot/Tools/sitl_gazebo ~/catkin_ws/src/
ln -s ~/PX4-Autopilot/mavlink ~/catkin_ws/src/

View File

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

View File

@@ -251,6 +251,30 @@ ros_msg = mavlink.convert_to_rosmsg(msg)
mavlink_pub.publish(ros_msg)
```
<!-- markdownlint-disable MD044 -->
### # {#mavlink-receive}
<!-- markdownlint-enable MD044 -->
Подписка на все MAVLink-сообщения от полетного контроллера и их декодирование:
```python
from mavros_msgs.msg import Mavlink
from mavros import mavlink
from pymavlink import mavutil
link = mavutil.mavlink.MAVLink('', 255, 1)
def mavlink_cb(msg):
mav_msg = link.decode(mavlink.convert_to_bytes(msg))
print('msgid =', msg.msgid, mav_msg) # print message id and parsed message
mavlink_sub = rospy.Subscriber('mavlink/from', Mavlink, mavlink_cb)
rospy.spin()
```
### # {#rc-sub}
Реакция на переключение режима на пульте радиоуправления (может быть использовано для запуска автономного полета, см. [пример](https://gist.github.com/okalachev/b709f04522d2f9af97e835baedeb806b)):