Compare commits

..

1 Commits

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

View File

@@ -21,25 +21,3 @@ jobs:
- 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
noetic-raw:
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 pip
run: apt-get update && apt-get -y install python3-pip
- name: Install dependencies
run: rosdep update && rosdep install --from-paths src --ignore-src -y
- 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: Install
run: source devel/setup.bash && catkin_make install

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

@@ -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')"/>