Add 'launch/klausen_dampen.launch'

This commit is contained in:
cesar.alejandro 2022-03-01 18:06:18 +00:00
parent 23a33625eb
commit 5ef1fa2ecf
1 changed files with 63 additions and 0 deletions

View File

@ -0,0 +1,63 @@
<?xml version="1.0"?>
<!--
Launch file to use klausen oscillaton damping ctrl in Gazebo
/-->
<launch>
<arg name="mav_name" default="spiri"/>
<arg name="command_input" default="1" />
<arg name="log_output" default="screen" />
<arg name="fcu_protocol" default="v2.0" />
<arg name="respawn_mavros" default="false" />
<arg name="gazebo_gui" default="false" />
<arg name="test_type" default="step.py" />
<group ns="sim">
<rosparam file="$(find oscillation_ctrl)/config/Ctrl_param.yaml" />
</group>
<node
pkg="oscillation_ctrl"
type="LinkState.py"
name="linkStates_node"
launch-prefix="xterm -e"
/>
<node
pkg="oscillation_ctrl"
type="ref_signalGen.py"
name="refSignal_node"
/>
<node
pkg="oscillation_ctrl"
type="klausen_control.py"
name="klausenCtrl_node"
output="screen"
/>
<node
pkg="oscillation_ctrl"
type="pathFollow_node"
name="pathFollow_node"
launch-prefix="xterm -e"
/>
<node
pkg="oscillation_ctrl"
type="$(arg test_type)"
name="test_node"
launch-prefix="xterm -e"
/>
<node pkg="geometric_controller" type="geometric_controller_node" name="geometric_controller" output="screen">
<param name="mav_name" type="string" value="$(arg mav_name)" />
<!--remap from="command/bodyrate_command" to="/mavros/setpoint_raw/attitude"/-->
<param name="ctrl_mode" value="$(arg command_input)" />
<param name="max_acc" value="8.0" />
<param name="Kp_x" value="8.0" />
<param name="Kp_y" value="8.0" />
<param name="Kp_z" value="10.0" />
<param name="Kv_x" value="3.0" />
<param name="Kv_y" value="3.0" />
<param name="Kv_z" value="6.0" />
</node>
<!-- PX4 LAUNCH -->
<include file="$(find px4)/launch/spiri_with_tether.launch"/>
</launch>