mirror of
https://github.com/CopterExpress/clover.git
synced 2026-06-03 08:29:32 +00:00
simulation: add type:=jmavsim to simulator.launch, remove sitl.launch, some adjustments
This commit is contained in:
@@ -44,16 +44,12 @@ Alternatively you may change the `fcu_url` property in `mavros.launch` file to p
|
||||
|
||||
## Running
|
||||
|
||||
To start connection to SITL, use:
|
||||
|
||||
```bash
|
||||
roslaunch clover sitl.launch
|
||||
```
|
||||
|
||||
To start connection to the flight controller, use:
|
||||
|
||||
```bash
|
||||
roslaunch clover clover.launch
|
||||
```
|
||||
|
||||
For the simulation information see the [corresponding article](https://clover.coex.tech/en/simulation.html).
|
||||
|
||||
> Note that the package is configured to connect to `/dev/px4fmu` by default (see [previous section](#manual-installation)). Install udev rules or specify path to your FCU device in `mavros.launch`.
|
||||
|
||||
@@ -1,19 +0,0 @@
|
||||
<launch>
|
||||
<!-- clover configuration for testing in sitl -->
|
||||
<arg name="ip" default="127.0.0.1"/>
|
||||
<arg name="rosbridge" default="false"/>
|
||||
|
||||
<include file="$(find clover)/launch/clover.launch">
|
||||
<arg name="fcu_conn" value="udp"/>
|
||||
<arg name="fcu_ip" value="$(arg ip)"/>
|
||||
<arg name="gcs_bridge" value="false"/>
|
||||
<arg name="optical_flow" value="false"/>
|
||||
<arg name="web_video_server" default="false"/>
|
||||
<arg name="main_camera" default="false"/>
|
||||
<arg name="rosbridge" value="$(arg rosbridge)"/>
|
||||
<arg name="aruco" default="false"/>
|
||||
<arg name="rangefinder_vl53l1x" default="false"/>
|
||||
<arg name="led" default="false"/>
|
||||
<arg name="rc" default="false"/>
|
||||
</include>
|
||||
</launch>
|
||||
@@ -1,4 +1,5 @@
|
||||
<launch>
|
||||
<arg name="type" default="gazebo"/> <!-- gazebo, jmavsim, none (only clover packages) -->
|
||||
<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 -->
|
||||
@@ -9,7 +10,7 @@
|
||||
<arg name="use_clover_physics" default="false"/> <!-- Use inertial parameters from CAD models -->
|
||||
|
||||
<!-- Gazebo instance -->
|
||||
<include file="$(find gazebo_ros)/launch/empty_world.launch">
|
||||
<include file="$(find gazebo_ros)/launch/empty_world.launch" if="$(eval type == 'gazebo')">
|
||||
<!-- Workaround for crashes in VMware -->
|
||||
<env name="SVGA_VGPU10" value="0"/>
|
||||
<arg name="gui" value="true"/>
|
||||
@@ -18,13 +19,13 @@
|
||||
</include>
|
||||
|
||||
<!-- PX4 instance -->
|
||||
<node name="sitl_$(arg mav_id)" pkg="px4" type="px4" output="screen" args="$(find px4)/ROMFS/px4fmu_common -s etc/init.d-posix/rcS -i $(arg mav_id)">
|
||||
<node name="sitl_$(arg mav_id)" pkg="px4" type="px4" output="screen" args="$(find px4)/ROMFS/px4fmu_common -s etc/init.d-posix/rcS -i $(arg mav_id)" unless="$(eval type == 'none')">
|
||||
<env name="PX4_SIM_MODEL" value="$(arg vehicle)"/>
|
||||
<env name="PX4_ESTIMATOR" value="$(arg est)"/>
|
||||
</node>
|
||||
|
||||
<!-- Clover model -->
|
||||
<include file="$(find clover_description)/launch/spawn_drone.launch">
|
||||
<include file="$(find clover_description)/launch/spawn_drone.launch" if="$(eval type == 'gazebo')">
|
||||
<arg name="main_camera" value="$(arg main_camera)"/>
|
||||
<arg name="rangefinder" value="$(arg rangefinder)"/>
|
||||
<arg name="led" value="$(arg led)"/>
|
||||
@@ -32,10 +33,20 @@
|
||||
<arg name="use_clover_physics" value="$(arg use_clover_physics)"/>
|
||||
</include>
|
||||
|
||||
<node name="jmavsim" pkg="px4" type="jmavsim_run.sh" output="screen" if="$(eval type == 'jmavsim')"/>
|
||||
|
||||
<param name="use_sim_time" value="false" if="$(eval type == 'jmavsim')"/>
|
||||
|
||||
<!-- Clover services -->
|
||||
<include file="$(find clover)/launch/clover.launch">
|
||||
<arg name="simulator" value="true"/>
|
||||
<arg name="fcu_conn" value="sitl"/>
|
||||
<arg name="fcu_ip" value="127.0.0.1"/>
|
||||
<arg name="gcs_bridge" value=""/>
|
||||
<arg name="rc" default="false"/>
|
||||
<arg name="web_video_server" default="false" if="$(eval type == 'jmavsim')"/>
|
||||
<arg name="main_camera" default="false" if="$(eval type == 'jmavsim')"/>
|
||||
<arg name="aruco" default="false" if="$(eval type == 'jmavsim')"/>
|
||||
<arg name="led" default="false" if="$(eval type == 'jmavsim')"/>
|
||||
</include>
|
||||
</launch>
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
PX4 Simulation
|
||||
===
|
||||
|
||||
> **Hint** This article is about running a standalone PX4 simulation with a generic quadcopter. Consider using [our configuration](simulation.md) for a more Clover-like experience.
|
||||
> **Warning** This article is about running a standalone PX4 simulation with a generic quadcopter and **is outdated**. Consider using [our configuration](simulation.md) for a more Clover-like experience.
|
||||
|
||||
Main article: https://dev.px4.io/en/simulation/
|
||||
|
||||
|
||||
@@ -198,7 +198,7 @@ catkin_make
|
||||
|
||||
```bash
|
||||
. devel/setup.bash
|
||||
roslaunch clover sitl.launch
|
||||
roslaunch clover_simulation simulator.launch type:=none
|
||||
```
|
||||
|
||||
Для того, чтобы воспользоваться функциями предоставляемыми нашим пакетом, в новом окне терминала подтяните зависимости из файла `setup`:
|
||||
@@ -207,4 +207,4 @@ roslaunch clover sitl.launch
|
||||
source ~/catkin_ws/devel/setup.bash
|
||||
```
|
||||
|
||||
Теперь вы можете воспользоваться всеми возможностями пакета `Clover` в вашем симуляторе.
|
||||
Теперь вы можете воспользоваться всеми возможностями пакета `clover` в вашем симуляторе.
|
||||
|
||||
Reference in New Issue
Block a user