Compare commits

..

1 Commits

Author SHA1 Message Date
Oleg Kalachev
add7f0d55f simulation: hitl support 2022-09-08 09:24:04 +03:00
25 changed files with 30 additions and 259 deletions

View File

@@ -16,36 +16,8 @@ jobs:
# docker run --rm -v $(pwd):/root/catkin_ws/src/clover ros:melodic-ros-base /root/catkin_ws/src/clover/builder/standalone-install.sh
noetic:
runs-on: ubuntu-latest
container: ros:noetic-ros-base
defaults:
run:
working-directory: catkin_ws
shell: bash
steps:
- 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
- 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

View File

@@ -251,5 +251,4 @@ 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,8 +187,6 @@ 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;
@@ -206,33 +204,20 @@ 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()) {
// 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);
}
transform.transform.rotation = marker.pose.orientation;
fillTranslation(transform.transform.translation, tvecs[i]);
br_->sendTransform(transform);
}
}
}
array_.markers.push_back(marker);
}
if (send_tf_) {
br_->sendTransform(transforms);
}
}
markers_pub_.publish(array_);

Binary file not shown.

Before

Width:  |  Height:  |  Size: 62 KiB

View File

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

View File

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

View File

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

View File

@@ -4,8 +4,6 @@
<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"/>
@@ -45,8 +43,4 @@
<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

@@ -37,7 +37,6 @@
#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>
@@ -55,7 +54,6 @@ 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;
@@ -98,12 +96,10 @@ 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;
@@ -126,8 +122,6 @@ 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;
@@ -179,15 +173,6 @@ 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
@@ -436,18 +421,6 @@ 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;
}
@@ -583,7 +556,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; // when not found it's the same frame
const string& reference_frame = search == reference_frames.end() ? frame_id : search->second;
// Serve "partial" commands
@@ -610,33 +583,22 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
}
}
if (!auto_arm && std::isfinite(z) &&
isnan(x) && isnan(y) && isnan(vx) && isnan(vy) && isnan(vz) &&
isnan(pitch) && isnan(roll) && isnan(thrust) &&
if (!auto_arm && std::isfinite(yaw_rate) &&
isnan(x) && isnan(y) && isnan(z) && isnan(vx) && isnan(vy) && isnan(vz) &&
isnan(pitch) && isnan(roll) && isnan(yaw) && isnan(thrust) &&
isnan(lat) && isnan(lon)) {
// 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);
// change only the yaw rate
if (setpoint_type == POSITION || setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL || setpoint_type == VELOCITY) {
message = "Changing yaw rate only";
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;
setpoint_yaw_type = YAW_RATE;
setpoint_yaw_rate = yaw_rate;
goto publish_setpoint;
} else {
throw std::runtime_error("Setting z is possible only when position setpoint active");
throw std::runtime_error("Setting yaw rate is possible only when position or velocity setpoints 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) {
@@ -898,13 +860,6 @@ 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");
@@ -926,7 +881,6 @@ 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
@@ -962,13 +916,6 @@ int main(int argc, char **argv)
auto manual_control_sub = nh.subscribe(mavros + "/manual_control/control", 1, &handleMessage<mavros_msgs::ManualControl, manual_control>);
auto 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);
@@ -986,7 +933,6 @@ 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,7 +24,6 @@ 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,9 +37,6 @@
<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,7 +40,6 @@ 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';
@@ -52,11 +51,10 @@ function viewTopic(topic) {
});
new ROSLIB.Topic({ ros: ros, name: topic }).subscribe(function(msg) {
counter++;
document.title = topic;
if (mouseDown) return;
if (msg.header && msg.header.stamp) {
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();
@@ -64,8 +62,7 @@ function viewTopic(topic) {
}
}
let txt = `<div class=counter>${counter} received</div>${yamlStringify(msg)}`; // JSON.stringify(msg, null, 4);
topicMessage.innerHTML = txt;
topicMessage.innerHTML = yamlStringify(msg); // JSON.stringify(msg, null, 4);
});
}

View File

@@ -15,7 +15,6 @@
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,8 +10,9 @@
<arg name="gps" default="true"/>
<!-- Use physics parameters from CAD programs -->
<arg name="use_clover_physics" default="false"/>
<arg name="hitl" default="false"/>
<arg name="cmd" default="$(find xacro)/xacro $(find clover_description)/urdf/clover/clover4.xacro main_camera:=$(arg main_camera) rangefinder:=$(arg rangefinder) led:=$(arg led) gps:=$(arg gps) maintain_camera_rate:=$(arg maintain_camera_rate) use_clover_physics:=$(arg use_clover_physics)"/>
<arg name="cmd" default="$(find xacro)/xacro $(find clover_description)/urdf/clover/clover4.xacro main_camera:=$(arg main_camera) rangefinder:=$(arg rangefinder) led:=$(arg led) gps:=$(arg gps) maintain_camera_rate:=$(arg maintain_camera_rate) use_clover_physics:=$(arg use_clover_physics) hitl:=$(arg hitl)"/>
<param command="$(arg cmd)" name="drone_description"/>
<!-- Note: -package_to_model replaces all mentions of "package://" with "model://" in urdf URIs -->
<node name="$(anon spawn)" output="screen" pkg="gazebo_ros" type="spawn_model" args="-urdf -param drone_description -model clover -z 0.3"/>

View File

@@ -7,6 +7,7 @@
<xacro:arg name="gps" default="true"/>
<xacro:arg name="maintain_camera_rate" default="false"/>
<xacro:arg name="use_clover_physics" default="false"/>
<xacro:arg name="hitl" default="false"/>
<xacro:include filename="clover4_base.xacro" />
<xacro:include filename="../sensors/rpi_cam.urdf.xacro"/>

View File

@@ -53,14 +53,14 @@
<mavlink_addr>INADDR_ANY</mavlink_addr>
<mavlink_tcp_port>4560</mavlink_tcp_port>
<mavlink_udp_port>14560</mavlink_udp_port>
<serialEnabled>false</serialEnabled>
<serialEnabled>$(arg hitl)</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_mode>$(arg hitl)</hil_mode>
<hil_state_level>0</hil_state_level>
<send_vision_estimation>0</send_vision_estimation>
<send_odometry>1</send_odometry>

View File

@@ -1,5 +1,6 @@
<launch>
<arg name="type" default="gazebo"/> <!-- gazebo, jmavsim, none (only clover packages) -->
<arg name="mode" default="sitl"/> <!-- sitl or hitl -->
<arg name="mav_id" default="0"/>
<arg name="est" default="ekf2"/> <!-- PX4 estimator: lpe, ekf2 -->
<arg name="vehicle" default="clover"/> <!-- PX4 vehicle configuration: clover, clover_vpe -->
@@ -21,7 +22,7 @@
</include>
<!-- PX4 instance -->
<node name="sitl_$(arg mav_id)" pkg="px4" type="px4" output="screen" required="true" args="$(find px4)/ROMFS/px4fmu_common -s etc/init.d-posix/rcS -i $(arg mav_id)" unless="$(eval type == 'none')">
<node name="sitl_$(arg mav_id)" pkg="px4" type="px4" output="screen" required="true" args="$(find px4)/ROMFS/px4fmu_common -s etc/init.d-posix/rcS -i $(arg mav_id)" unless="$(eval type == 'none' or mode == 'hitl')">
<env name="PX4_SIM_MODEL" value="$(arg vehicle)"/>
<env name="PX4_ESTIMATOR" value="$(arg est)"/>
</node>
@@ -34,6 +35,7 @@
<arg name="led" value="$(arg led)"/>
<arg name="gps" value="$(arg gps)"/>
<arg name="use_clover_physics" value="$(arg use_clover_physics)"/>
<arg name="hitl" value="$(eval mode == 'hitl')"/>
</include>
<node name="jmavsim" pkg="px4" required="true" type="jmavsim_run.sh" output="screen" if="$(eval type == 'jmavsim')">
@@ -45,7 +47,7 @@
<!-- Clover services -->
<include file="$(find clover)/launch/clover.launch">
<arg name="simulator" value="true"/>
<arg name="fcu_conn" value="sitl"/>
<arg name="fcu_conn" value="$(arg mode)"/>
<arg name="fcu_ip" value="127.0.0.1"/>
<arg name="gcs_bridge" value=""/>
<arg name="web_video_server" default="false" if="$(eval type == 'jmavsim')"/>

View File

@@ -145,8 +145,6 @@ 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

@@ -305,16 +305,6 @@ rosservice call /land "{}"
> **Caution** In recent PX4 versions, the vehicle will be switched out of LAND mode to manual mode, if the remote control sticks are moved significantly.
### 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

@@ -97,13 +97,3 @@ PX4_SIM_SPEED_FACTOR=0.42 roslaunch clover_simulation simulator.launch
The virtual machine may benefit from several CPU cores, especially if the cores are not very performant. In our tests, a four-core machine with only a single core allocated to the VM was unable to run the simulation, with constant interface freezes and dropped ROS messages. The same machine with all four cores available to the VM was able to run the simulation at 0.25 real-time speed.
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,30 +240,6 @@ 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

@@ -147,8 +147,6 @@ 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

@@ -305,16 +305,6 @@ 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

@@ -99,13 +99,3 @@ 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,30 +251,6 @@ 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)):