oscillation_ctrl/launch/mocap_sim.launch

72 lines
1.7 KiB
XML

<?xml version="1.0"?>
<!--
Launch file to use klausen oscillaton damping ctrl in Gazebo
/-->
<launch>
<arg name="model" default="headless_spiri_mocap"/>
<arg name="ctrl" default="yes"/>
<group ns="sim"> <!--> should be mocap but will use gazebo since it is still sim <-->
<rosparam file="$(find oscillation_ctrl)/config/gazebo_config.yaml"/>
</group>
<node
pkg="oscillation_ctrl"
type="MoCap_Localization_fake.py"
name="fakeMocap_node"
launch-prefix="xterm -e"
/>
<!-- DETERMINES DESIRED POSITION -->
<node
pkg="oscillation_ctrl"
type="wpoint_tracker.py"
name="waypoints_server"
/>
<group if="$(eval ctrl == 'no')">
<group ns="status">
<rosparam file="$(find oscillation_ctrl)/config/noCtrl_param.yaml" />
</group>
<node
pkg="oscillation_ctrl"
type="offb_node"
name="offb_node"
launch-prefix="xterm -e"
/>
</group>
<!-- RUNS WITH CRTL -->
<group if="$(eval ctrl =='yes')">
<group ns="status">
<rosparam file="$(find oscillation_ctrl)/config/Ctrl_param.yaml" />
</group>
<!-- CREATES DESIRED TRAJECTORY/ REFERENCE SIGNAL -->
<node
pkg="oscillation_ctrl"
type="ref_signalGen.py"
name="refSignal_node"
/>
<!-- DETERMINES DESIRED ATTITUDE AND THRUST BASED ON REF. SIG. -->
<node
pkg="oscillation_ctrl"
type="klausen_control.py"
name="klausenCtrl_node"
launch-prefix="xterm -e"
/>
<!-- PUBLISHES DESIRED COMMANDS -->
<node
pkg="oscillation_ctrl"
type="mocap_pathFollow_node"
name="mocap_pathFollow_node"
launch-prefix="xterm -e"
/>
<!-- RUNS TEST -->
<node
pkg="oscillation_ctrl"
type="mocap_runTest.py"
name="mocap_Test"
launch-prefix="xterm -e"
/>
</group>
<!-- PX4 LAUNCH -->
<include file="$(find px4)/launch/$(arg model).launch"/>
</launch>