mirror of
https://github.com/CopterExpress/clover.git
synced 2026-06-09 02:54:32 +00:00
Compare commits
21 Commits
v0.23-rc.5
...
test_resul
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
dc5ffc250b | ||
|
|
7460d6541d | ||
|
|
0f37f19b40 | ||
|
|
e9c3c6ff72 | ||
|
|
7909756046 | ||
|
|
1e8a4841af | ||
|
|
6ec574e193 | ||
|
|
8381aecd50 | ||
|
|
f5eb475660 | ||
|
|
928f4f135e | ||
|
|
8d15de0849 | ||
|
|
826f631b97 | ||
|
|
52b5d7b04e | ||
|
|
455d52007e | ||
|
|
e9e6cabbb9 | ||
|
|
8fcd6e9b9e | ||
|
|
24d3a1df8d | ||
|
|
9784e7bfa1 | ||
|
|
fbad85d87f | ||
|
|
c1ca40187e | ||
|
|
c1179869cd |
14
.github/workflows/build.yml
vendored
14
.github/workflows/build.yml
vendored
@@ -7,13 +7,13 @@ on:
|
|||||||
branches: [ master ]
|
branches: [ master ]
|
||||||
|
|
||||||
jobs:
|
jobs:
|
||||||
melodic:
|
# 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:
|
noetic:
|
||||||
runs-on: ubuntu-latest
|
runs-on: ubuntu-latest
|
||||||
steps:
|
steps:
|
||||||
|
|||||||
@@ -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.21.1</version>
|
<version>0.23.0</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>
|
||||||
|
|||||||
@@ -9,10 +9,10 @@ def node():
|
|||||||
return rospy.init_node('aruco_pose_opencv_crash', anonymous=True)
|
return rospy.init_node('aruco_pose_opencv_crash', anonymous=True)
|
||||||
|
|
||||||
def test_opencv_crashes_img01(node):
|
def test_opencv_crashes_img01(node):
|
||||||
rospy.wait_for_message('aruco_detect_01/visualization', VisMarkerArray, timeout=5)
|
rospy.wait_for_message('aruco_detect_01/visualization', VisMarkerArray, timeout=20)
|
||||||
|
|
||||||
def test_opencv_crashes_img02(node):
|
def test_opencv_crashes_img02(node):
|
||||||
rospy.wait_for_message('aruco_detect_02/visualization', VisMarkerArray, timeout=5)
|
rospy.wait_for_message('aruco_detect_02/visualization', VisMarkerArray, timeout=20)
|
||||||
|
|
||||||
def test_opencv_crashes_img03(node):
|
def test_opencv_crashes_img03(node):
|
||||||
rospy.wait_for_message('aruco_detect_03/visualization', VisMarkerArray, timeout=5)
|
rospy.wait_for_message('aruco_detect_03/visualization', VisMarkerArray, timeout=20)
|
||||||
|
|||||||
@@ -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.0-0buster \
|
ros-${ROS_DISTRO}-cv-camera=0.5.1-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 \
|
||||||
@@ -146,7 +146,7 @@ echo_stamp "Install GeographicLib datasets (needed for mavros)" \
|
|||||||
echo_stamp "Running tests"
|
echo_stamp "Running tests"
|
||||||
cd /home/pi/catkin_ws
|
cd /home/pi/catkin_ws
|
||||||
# FIXME: Investigate failing tests
|
# FIXME: Investigate failing tests
|
||||||
catkin_make run_tests #&& catkin_test_results
|
catkin_make run_tests && catkin_test_results
|
||||||
|
|
||||||
echo_stamp "Change permissions for catkin_ws"
|
echo_stamp "Change permissions for catkin_ws"
|
||||||
chown -Rf pi:pi /home/pi/catkin_ws
|
chown -Rf pi:pi /home/pi/catkin_ws
|
||||||
|
|||||||
@@ -58,5 +58,9 @@ 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/*) ]]
|
||||||
|
|||||||
@@ -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="rangefinder/range"/>
|
<remap from="mavros/distance_sensor/rangefinder_sub" to="$(arg distance_sensor_remap)" if="$(eval bool(distance_sensor_remap))"/>
|
||||||
|
|
||||||
<rosparam param="plugin_whitelist">
|
<rosparam param="plugin_whitelist">
|
||||||
- altitude
|
- altitude
|
||||||
|
|||||||
@@ -78,6 +78,9 @@ 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.21.1</version>
|
<version>0.23.0</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>
|
||||||
|
|||||||
@@ -740,6 +740,14 @@ 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?
|
||||||
|
|||||||
@@ -61,6 +61,7 @@ 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;
|
||||||
@@ -861,8 +862,9 @@ 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.param<string>("mavros/local_position/tf/frame_id", local_frame, "map");
|
nh_priv.param("mavros", mavros, string("mavros")); // for case of using multiple connections
|
||||||
nh.param<string>("mavros/local_position/tf/child_frame_id", fcu_frame, "base_link");
|
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_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);
|
||||||
@@ -894,25 +896,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);
|
||||||
|
|||||||
@@ -33,3 +33,29 @@ 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,10 +23,7 @@
|
|||||||
|
|
||||||
<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"/>
|
||||||
|
|
||||||
@@ -38,6 +35,8 @@
|
|||||||
<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,5 +1,6 @@
|
|||||||
const url = 'ws://' + location.hostname + ':9090';
|
const url = 'ws://' + location.hostname + ':9090';
|
||||||
const ros = new ROSLIB.Ros({ url: url });
|
const ros = new ROSLIB.Ros({ url: url });
|
||||||
|
const params = Object.fromEntries(new URLSearchParams(window.location.search).entries());
|
||||||
|
|
||||||
ros.on('connection', function () {
|
ros.on('connection', function () {
|
||||||
document.body.classList.add('connected');
|
document.body.classList.add('connected');
|
||||||
@@ -52,6 +53,15 @@ function viewTopic(topic) {
|
|||||||
new ROSLIB.Topic({ ros: ros, name: topic }).subscribe(function(msg) {
|
new ROSLIB.Topic({ ros: ros, name: topic }).subscribe(function(msg) {
|
||||||
document.title = topic;
|
document.title = topic;
|
||||||
if (mouseDown) return;
|
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);
|
topicMessage.innerHTML = yamlStringify(msg); // JSON.stringify(msg, null, 4);
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
@@ -62,8 +72,6 @@ topicMessage.addEventListener('mousedown', function() { mouseDown = true; });
|
|||||||
topicMessage.addEventListener('mouseup', function() { mouseDown = false; });
|
topicMessage.addEventListener('mouseup', function() { mouseDown = false; });
|
||||||
|
|
||||||
function init() {
|
function init() {
|
||||||
const params = Object.fromEntries(new URLSearchParams(window.location.search).entries());
|
|
||||||
|
|
||||||
if (!params.topic) {
|
if (!params.topic) {
|
||||||
viewTopicsList();
|
viewTopicsList();
|
||||||
} else {
|
} else {
|
||||||
|
|||||||
@@ -23,6 +23,6 @@
|
|||||||
<body>
|
<body>
|
||||||
<h1> </h1>
|
<h1> </h1>
|
||||||
<ul id="topics"></ul>
|
<ul id="topics"></ul>
|
||||||
<code id="topic-message" title="Hold mouse button to pause">No messages received</code>
|
<code id="topic-message">No messages received</code>
|
||||||
</body>
|
</body>
|
||||||
</html>
|
</html>
|
||||||
|
|||||||
@@ -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.21.1</version>
|
<version>0.23.0</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>
|
||||||
|
|||||||
@@ -1,6 +1,6 @@
|
|||||||
<package format="2">
|
<package format="2">
|
||||||
<name>clover_description</name>
|
<name>clover_description</name>
|
||||||
<version>0.21.1</version>
|
<version>0.23.0</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>
|
||||||
|
|||||||
@@ -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="$(arg visual_material)" />
|
<xacro:property name="color" value="DarkGrey" />
|
||||||
|
|
||||||
<!-- Property Blocks -->
|
<!-- Property Blocks -->
|
||||||
<!-- Clover body inertia -->
|
<!-- Clover body inertia -->
|
||||||
|
|||||||
@@ -1,6 +1,6 @@
|
|||||||
<package format="2">
|
<package format="2">
|
||||||
<name>clover_simulation</name>
|
<name>clover_simulation</name>
|
||||||
<version>0.21.1</version>
|
<version>0.23.0</version>
|
||||||
<description>The clover_simulation package provides worlds and launch files for Gazebo.</description>
|
<description>The clover_simulation package provides worlds and launch files for Gazebo.</description>
|
||||||
|
|
||||||
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>
|
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>
|
||||||
|
|||||||
@@ -6,7 +6,7 @@ Software autorun
|
|||||||
systemd
|
systemd
|
||||||
---
|
---
|
||||||
|
|
||||||
Main documentation: [https://wiki.archlinux.org/title/Systemd](https://wiki.archlinux.org/title/Systemd).
|
Main documentation: https://wiki.archlinux.org/title/Systemd.
|
||||||
|
|
||||||
All automatically started Clover software is launched as a `clover.service` systemd service.
|
All automatically started Clover software is launched as a `clover.service` systemd service.
|
||||||
|
|
||||||
@@ -54,8 +54,8 @@ The started file must have *permission* to run:
|
|||||||
chmod +x my_program.py
|
chmod +x my_program.py
|
||||||
```
|
```
|
||||||
|
|
||||||
When scripting languages are used, a [shebang](https://en.wikipedia.org/wiki/Shebang_(Unix)) should be placed at the beginning of the file, for example:
|
When scripting languages are used, a <a href="https://en.wikipedia.org/wiki/Shebang_(Unix)">shebang</a> should be placed at the beginning of the file, for example:
|
||||||
|
|
||||||
```bash
|
```bash
|
||||||
#!/usr/bin/env python
|
#!/usr/bin/env python3
|
||||||
```
|
```
|
||||||
|
|||||||
@@ -9,7 +9,8 @@ Main frames in the `clover` package:
|
|||||||
* `base_link` is rigidly bound to the drone. It is shown by the simplified drone model on the image above;
|
* `base_link` is rigidly bound to the drone. It is shown by the simplified drone model on the image above;
|
||||||
* `body` is bound to the drone, but its Z axis points up regardless of the drone's pitch and roll. It is shown by the red, blue and green lines in the illustration;
|
* `body` is bound to the drone, but its Z axis points up regardless of the drone's pitch and roll. It is shown by the red, blue and green lines in the illustration;
|
||||||
* <a name="navigate_target"></a>`navigate_target` is bound to the current navigation target (as set by the [navigate](simple_offboard.md#navigate) service);
|
* <a name="navigate_target"></a>`navigate_target` is bound to the current navigation target (as set by the [navigate](simple_offboard.md#navigate) service);
|
||||||
* `setpoint` is current position setpoint.
|
* `setpoint` is current position setpoint;
|
||||||
|
* `main_camera_optical` is the coordinate system, [linked to the main camera](camera_setup.md#frame);
|
||||||
|
|
||||||
Additional frames become available when [ArUco positioning system](aruco.md) is active:
|
Additional frames become available when [ArUco positioning system](aruco.md) is active:
|
||||||
|
|
||||||
|
|||||||
@@ -101,6 +101,7 @@
|
|||||||
* [Светодиодная лента (legacy)](leds_old.md)
|
* [Светодиодная лента (legacy)](leds_old.md)
|
||||||
* [Вклад в Клевер](contributing.md)
|
* [Вклад в Клевер](contributing.md)
|
||||||
* [Репозиторий пакетов COEX](packages.md)
|
* [Репозиторий пакетов COEX](packages.md)
|
||||||
|
* [Тестирование Клевера](testing.md)
|
||||||
* [Переход на версию 0.20](migrate20.md)
|
* [Переход на версию 0.20](migrate20.md)
|
||||||
* [Переход на версию 0.22](migrate22.md)
|
* [Переход на версию 0.22](migrate22.md)
|
||||||
* [COEX DuoCam](duocam.md)
|
* [COEX DuoCam](duocam.md)
|
||||||
|
|||||||
@@ -6,7 +6,7 @@
|
|||||||
systemd
|
systemd
|
||||||
---
|
---
|
||||||
|
|
||||||
Основная документация: [https://wiki.archlinux.org/index.php/Systemd_(Русский)](https://wiki.archlinux.org/index.php/Systemd_(Русский)).
|
Основная документация: https://wiki.archlinux.org/index.php/Systemd_(Русский).
|
||||||
|
|
||||||
Все автоматически стартуемое ПО Клевера запускается в виде systemd-сервиса `clover.service`.
|
Все автоматически стартуемое ПО Клевера запускается в виде systemd-сервиса `clover.service`.
|
||||||
|
|
||||||
@@ -54,8 +54,8 @@ roslaunch
|
|||||||
chmod +x my_program.py
|
chmod +x my_program.py
|
||||||
```
|
```
|
||||||
|
|
||||||
При использовании скриптовых языков вначале файла должен стоять [shebang](https://ru.wikipedia.org/wiki/Шебанг_(Unix)), например:
|
При использовании скриптовых языков вначале файла должен стоять <a href="https://ru.wikipedia.org/wiki/Шебанг_(Unix)">shebang</a>, например:
|
||||||
|
|
||||||
```bash
|
```bash
|
||||||
#!/usr/bin/env python
|
#!/usr/bin/env python3
|
||||||
```
|
```
|
||||||
|
|||||||
@@ -11,7 +11,8 @@
|
|||||||
* `base_link` — координаты относительно квадрокоптера: схематичное изображение квадрокоптера на иллюстрации;
|
* `base_link` — координаты относительно квадрокоптера: схематичное изображение квадрокоптера на иллюстрации;
|
||||||
* `body` — координаты относительно квадрокоптера без учета наклонов по тангажу и крену: красная, синяя и зеленая линии на иллюстрации;
|
* `body` — координаты относительно квадрокоптера без учета наклонов по тангажу и крену: красная, синяя и зеленая линии на иллюстрации;
|
||||||
* <a name="navigate_target"></a>`navigate_target` – координаты точки, в которую сейчас летит дрон (с использованием [navigate](simple_offboard.md#navigate));
|
* <a name="navigate_target"></a>`navigate_target` – координаты точки, в которую сейчас летит дрон (с использованием [navigate](simple_offboard.md#navigate));
|
||||||
* `setpoint` – текущий setpoint по позиции.
|
* `setpoint` – текущий setpoint по позиции;
|
||||||
|
* `main_camera_optical` – система координат, [связанная с основной камерой](camera_setup.md#frame).
|
||||||
|
|
||||||
При использовании [системы позиционирования по ArUco-маркерам](aruco.md) появляются дополнительные фреймы:
|
При использовании [системы позиционирования по ArUco-маркерам](aruco.md) появляются дополнительные фреймы:
|
||||||
|
|
||||||
|
|||||||
100
docs/ru/testing.md
Normal file
100
docs/ru/testing.md
Normal file
@@ -0,0 +1,100 @@
|
|||||||
|
# Список тестирования
|
||||||
|
|
||||||
|
Актуальный список для ручного тестирования релизов Клевера.
|
||||||
|
|
||||||
|
Критичность: **критично**, средняя критичность, *не критично*.
|
||||||
|
|
||||||
|
## [Образ Клевера](image.md)
|
||||||
|
|
||||||
|
### Общие тесты
|
||||||
|
|
||||||
|
* **Раздача [Wi-Fi](wifi.md)**
|
||||||
|
* **Возможность подключения по [SSH](ssh.md) по IP и Hostname**
|
||||||
|
* **Успешное подключение COEX Pix по USB (по умолчанию)**
|
||||||
|
* Успешное подключение COEX Pix по UART (с настройкой)
|
||||||
|
* **Бридж для QGC – корректное подключение по TCP**
|
||||||
|
* Бридж для QGC – корректное подключение по UDP-b
|
||||||
|
* **Раздача главной страницы**
|
||||||
|
* **Раздача пользовательской документации (RU/EN), отсутствие битых изображений и т. д.**
|
||||||
|
* **Работа веб-терминала Butterfly**
|
||||||
|
* **Работа web_video_server**
|
||||||
|
* **Корректная работа драйвера камеры, корректные изображения и данные в топиках**
|
||||||
|
* **Корректная работа драйвера vl53l1x (i2c к Raspberry), в том числе топика `~data`**
|
||||||
|
* **Корректная работа optical flow и всех его топиков, полет по optical flow**
|
||||||
|
* **Полет по полю маркеров**
|
||||||
|
* **Корректная установка OpenCV – возможность использования из Python и C++**
|
||||||
|
* **Отсутствие неожиданного жора памяти и CPU (можно контролировать с помощью `selfcheck.py` или `htop`)**
|
||||||
|
* Автоматическая перекалибровка камеры при изменении разрешения
|
||||||
|
|
||||||
|
### Тесты веб-части
|
||||||
|
|
||||||
|
* Работа веб-просмотрщика топиков
|
||||||
|
* Работа веб-консоли
|
||||||
|
* Работа веб 3D-визуализации ArUco (map, detect)
|
||||||
|
* Работа веб 3D-визуализации web_rviz
|
||||||
|
* Работа веб 3D-визуализации web_visualization_aruco_map
|
||||||
|
* Работает отображение карты ArUco `/aruco_map/image` и в snapshot, и в debug
|
||||||
|
* Визуализация расположения камеры в web rviz
|
||||||
|
* Правильное отображение осей в `/aruco_map/image`
|
||||||
|
|
||||||
|
### Тесты selfcheck.py
|
||||||
|
|
||||||
|
* **Корректная работа `rosrun clover selfcheck.py`, отсутствие варнингов, анализ вывода**
|
||||||
|
* **Выводит ориентацию камеры текстом**
|
||||||
|
* **Делает `commander check`**
|
||||||
|
* **Показывается, что используется наш форк прошивки и версию образа**
|
||||||
|
* **Показывает возникающие ошибки и опечатки, допущенные в .launch файлах**
|
||||||
|
* **Проверка на throttling**
|
||||||
|
|
||||||
|
### Тесты simple_offboard
|
||||||
|
|
||||||
|
* **Корректная работа simple_offboard – взлет, полет в точку в любом фрейме, отсутствие проблем с `yaw` и `yaw_rate`**
|
||||||
|
* **В фрейме `body`**
|
||||||
|
* **В фрейме `aruco_map`**
|
||||||
|
* **В фрейме `map`**
|
||||||
|
* **В фрейме `navigate_target`**
|
||||||
|
* Корректное выполнения флипа
|
||||||
|
* **Возможность лететь к отдельным маркерам в карте, которые вне кадра и в кадре**
|
||||||
|
* **Корректное детектирование статуса kill switch при выполнение команды с флагом `auto_arm`**
|
||||||
|
* *Корректная работа outdoor по GPS-координатам*
|
||||||
|
* Работают программы из папки `~/examples`
|
||||||
|
|
||||||
|
### Тесты [ArUco](aruco.md)
|
||||||
|
|
||||||
|
* **Распознавание ArUco-маркеров, корректная работа всех топиков пакета `aruco_detect` и `aruco_map`**
|
||||||
|
* **VPE-полеты по маркерам на полу**
|
||||||
|
* *VPE-полеты по маркерам на потолке*
|
||||||
|
* Корректное распознавание ArUco-маркеров и ArUco-карты (проверка с помощью rviz или debug)
|
||||||
|
* *Работает в случае если используется слишком большой ID*
|
||||||
|
* Работают комментарии в файле карты, а также в карте используется от 4 до 8 параметров
|
||||||
|
* Полет по Optical Flow над 1 маркером
|
||||||
|
* `aruco_map` не падает в случае маленьких размеров карты и маркеров
|
||||||
|
|
||||||
|
### Тесты [pigpiod](gpio.md)
|
||||||
|
|
||||||
|
* Корректная работа pigpiod, возможность работы с сонаром, сервой и электромагнитом по мануалу
|
||||||
|
* Одновременная работа pigpiod и rpi_ws281x (правильная работа светодиодной ленты и сервы)
|
||||||
|
|
||||||
|
### Тесты [LED-ленты](leds.md)
|
||||||
|
|
||||||
|
* **Работает нода LED ленты на RPi 4**
|
||||||
|
* Дополнительная проверка на RPi 3, RPi 4 Rev. 1.4
|
||||||
|
* **Корректная работа всех notify эффектов заданных в `led.launch`**
|
||||||
|
* **Низкоуровневое управление отдельными диодами**
|
||||||
|
* **Высокоуровневое управление эффектами**
|
||||||
|
|
||||||
|
### [Блочное программирование](blocks.md)
|
||||||
|
|
||||||
|
* Корректная работа функционала блочного программирования
|
||||||
|
* Работа функций сохранение/загрузка/удаление
|
||||||
|
* Работа с pigpiod
|
||||||
|
* Работа всех примеров
|
||||||
|
|
||||||
|
### Дополнительно
|
||||||
|
|
||||||
|
* ROS ноды не падают в случае потери всех соединений (удобно проверять с экраном)
|
||||||
|
* Работает `rosshow`
|
||||||
|
* Работает `espeak`
|
||||||
|
* *Работает LIRC*
|
||||||
|
* *Работа iOS-пульта из коробки*
|
||||||
|
* *Работа Android-пульта из коробки*
|
||||||
@@ -1,7 +1,7 @@
|
|||||||
<?xml version="1.0"?>
|
<?xml version="1.0"?>
|
||||||
<package format="2">
|
<package format="2">
|
||||||
<name>roswww_static</name>
|
<name>roswww_static</name>
|
||||||
<version>0.21.1</version>
|
<version>0.23.0</version>
|
||||||
<description>Static web pages for ROS packages</description>
|
<description>Static web pages for ROS packages</description>
|
||||||
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>
|
<maintainer email="okalachev@gmail.com">Oleg Kalachev</maintainer>
|
||||||
<license>MIT</license>
|
<license>MIT</license>
|
||||||
|
|||||||
Reference in New Issue
Block a user