6 changed files with 187 additions and 2 deletions
@ -0,0 +1,13 @@
@@ -0,0 +1,13 @@
|
||||
#!/bin/sh |
||||
# |
||||
# @name 3DR Iris Quadrotor SITL (Obstacle Avoidance) |
||||
# |
||||
# @type Quadrotor Wide |
||||
# |
||||
|
||||
sh /etc/init.d-posix/10016_iris |
||||
|
||||
if [ $AUTOCNF = yes ] |
||||
then |
||||
param set COM_OBS_AVOID 1 |
||||
fi |
@ -0,0 +1,88 @@
@@ -0,0 +1,88 @@
|
||||
{ |
||||
"fileType": "Plan", |
||||
"geoFence": { |
||||
"circles": [ |
||||
], |
||||
"polygons": [ |
||||
], |
||||
"version": 2 |
||||
}, |
||||
"groundStation": "QGroundControl", |
||||
"mission": { |
||||
"cruiseSpeed": 15, |
||||
"firmwareType": 12, |
||||
"hoverSpeed": 5, |
||||
"items": [ |
||||
{ |
||||
"AMSLAltAboveTerrain": null, |
||||
"Altitude": 4, |
||||
"AltitudeMode": 0, |
||||
"autoContinue": true, |
||||
"command": 22, |
||||
"doJumpId": 1, |
||||
"frame": 3, |
||||
"params": [ |
||||
15, |
||||
0, |
||||
0, |
||||
null, |
||||
47.3977432, |
||||
8.5456085, |
||||
4 |
||||
], |
||||
"type": "SimpleItem" |
||||
}, |
||||
{ |
||||
"AMSLAltAboveTerrain": null, |
||||
"Altitude": 4, |
||||
"AltitudeMode": 0, |
||||
"autoContinue": true, |
||||
"command": 16, |
||||
"doJumpId": 2, |
||||
"frame": 3, |
||||
"params": [ |
||||
0, |
||||
0, |
||||
0, |
||||
null, |
||||
47.3977432, |
||||
8.5458765, |
||||
4 |
||||
], |
||||
"type": "SimpleItem" |
||||
}, |
||||
{ |
||||
"AMSLAltAboveTerrain": null, |
||||
"Altitude": -1, |
||||
"AltitudeMode": 0, |
||||
"autoContinue": true, |
||||
"command": 21, |
||||
"doJumpId": 3, |
||||
"frame": 3, |
||||
"params": [ |
||||
0, |
||||
0, |
||||
0, |
||||
null, |
||||
47.3977432, |
||||
8.5458812, |
||||
-1 |
||||
], |
||||
"type": "SimpleItem" |
||||
} |
||||
], |
||||
"plannedHomePosition": [ |
||||
47.3977419, |
||||
8.5458854, |
||||
487.923 |
||||
], |
||||
"vehicleType": 2, |
||||
"version": 2 |
||||
}, |
||||
"rallyPoints": { |
||||
"points": [ |
||||
], |
||||
"version": 2 |
||||
}, |
||||
"version": 1 |
||||
} |
@ -0,0 +1,52 @@
@@ -0,0 +1,52 @@
|
||||
<?xml version="1.0"?> |
||||
<launch> |
||||
<!-- Posix SITL MAVROS integration tests --> |
||||
<!-- Test a mission --> |
||||
<arg name="est" default="ekf2"/> |
||||
<arg name="gui" default="false"/> |
||||
<arg name="interactive" default="false"/> |
||||
<arg name="mission" default="avoidance"/> |
||||
<arg name="sdf" default="$(find local_planner)/../sim/models/iris_depth_camera_3/iris_depth_camera.sdf"/> |
||||
<arg name="vehicle" default="iris_obs_avoid"/> |
||||
<arg name="world" default="$(find local_planner)/../sim/worlds/boxes1.world"/> |
||||
<!-- PX4 SITL and Gazebo --> |
||||
<include file="$(find px4)/launch/posix_sitl.launch"> |
||||
<arg name="est" value="$(arg est)"/> |
||||
<arg name="gui" value="$(arg gui)"/> |
||||
<arg name="interactive" value="$(arg interactive)"/> |
||||
<arg name="respawn_gazebo" value="true"/> |
||||
<arg name="sdf" value="$(arg sdf)"/> |
||||
<arg name="vehicle" value="$(arg vehicle)"/> |
||||
<arg name="verbose" value="true"/> |
||||
<arg name="world" value="$(arg world)"/> |
||||
</include> |
||||
<!-- MAVROS --> |
||||
<include file="$(find mavros)/launch/node.launch"> |
||||
<arg name="pluginlists_yaml" value="$(find mavros)/launch/px4_pluginlists.yaml"/> |
||||
<arg name="config_yaml" value="$(find local_planner)/resource/px4_config.yaml"/> |
||||
<arg name="gcs_url" value=""/> |
||||
<arg name="fcu_url" value="udp://:14540@localhost:14557"/> |
||||
<arg name="tgt_system" value="1"/> |
||||
<arg name="tgt_component" value="1"/> |
||||
<arg name="respawn_mavros" value="true"/> |
||||
</include> |
||||
<!-- Transformation Publishers --> |
||||
<node pkg="tf" type="static_transform_publisher" name="tf_front_camera" |
||||
args="0 0 0 -1.57 0 -1.57 fcu front_camera_link 10"/> |
||||
<node pkg="tf" type="static_transform_publisher" name="tf_right_camera" |
||||
args="0 0 0 -3.14 0 -1.57 fcu right_camera_link 10"/> |
||||
<node pkg="tf" type="static_transform_publisher" name="tf_left_camera" |
||||
args="0 0 0 0 0 -1.57 fcu left_camera_link 10"/> |
||||
<!-- Suppress console outputs --> |
||||
<env name="ROSCONSOLE_CONFIG_FILE" value="$(find local_planner)/resource/custom_rosconsole.conf"/> |
||||
<!-- Launch Local Planner --> |
||||
<arg name="pointcloud_topics" default="[/camera_front/depth/points,/camera_left/depth/points,/camera_right/depth/points]"/> |
||||
<node name="local_planner_node" pkg="local_planner" type="local_planner_node" output="screen"> |
||||
<param name="goal_x_param" value="17" /> |
||||
<param name="goal_y_param" value="15"/> |
||||
<param name="goal_z_param" value="3" /> |
||||
<rosparam param="pointcloud_topics" subst_value="True">$(arg pointcloud_topics)</rosparam> |
||||
</node> |
||||
<!-- ROStest --> |
||||
<test test-name="$(arg mission)" pkg="px4" type="mission_test.py" time-limit="300.0" args="$(arg mission).plan"/> |
||||
</launch> |
@ -0,0 +1,20 @@
@@ -0,0 +1,20 @@
|
||||
#! /bin/bash |
||||
|
||||
DIR=$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd ) |
||||
PX4_SRC_DIR=${DIR}/.. |
||||
|
||||
source /opt/ros/${ROS_DISTRO:-kinetic}/setup.bash |
||||
mkdir -p ${PX4_SRC_DIR}/catkin_ws/src |
||||
cd ${PX4_SRC_DIR}/catkin_ws/ |
||||
git clone -b '0.1.0' --single-branch --depth 1 https://github.com/PX4/avoidance.git src/avoidance |
||||
|
||||
catkin init |
||||
catkin build local_planner --cmake-args -DCMAKE_BUILD_TYPE=Release |
||||
|
||||
source ${PX4_SRC_DIR}/catkin_ws/devel/setup.bash |
||||
source /usr/share/gazebo/setup.sh |
||||
|
||||
export CATKIN_SETUP_UTIL_ARGS=--extend |
||||
export GAZEBO_MODEL_PATH=$GAZEBO_MODEL_PATH:${PX4_SRC_DIR}/catkin_ws/src/avoidance/sim/models |
||||
|
||||
source $DIR/rostest_px4_run.sh "$@" |
Loading…
Reference in new issue