diff options
author | Thomas Gubler <thomasgubler@gmail.com> | 2014-12-31 15:23:28 +0100 |
---|---|---|
committer | Thomas Gubler <thomasgubler@gmail.com> | 2014-12-31 15:23:28 +0100 |
commit | 1b0446ed41eb6db676106debeef2f895edc30d01 (patch) | |
tree | a5568624f0f9e4476f4edfbc308e8df6fc0c2ed6 /launch | |
parent | 134f41c7077ea8592a55c07b1635bac6e23fe3bd (diff) | |
download | px4-firmware-1b0446ed41eb6db676106debeef2f895edc30d01.tar.gz px4-firmware-1b0446ed41eb6db676106debeef2f895edc30d01.tar.bz2 px4-firmware-1b0446ed41eb6db676106debeef2f895edc30d01.zip |
improve launch files
Diffstat (limited to 'launch')
-rw-r--r-- | launch/gazebo_multicopter.launch | 11 | ||||
-rw-r--r-- | launch/multicopter.launch | 5 |
2 files changed, 7 insertions, 9 deletions
diff --git a/launch/gazebo_multicopter.launch b/launch/gazebo_multicopter.launch index 9c0e96e04..febf7bdc0 100644 --- a/launch/gazebo_multicopter.launch +++ b/launch/gazebo_multicopter.launch @@ -1,13 +1,6 @@ <launch> -<include file="$(find mav_gazebo)/launch/vtol_empty_world_with_joy.launch" /> -<group ns="px4_multicopter"> - <node pkg="joy" name="joy_node" type="joy_node"/> - <node pkg="px4" name="manual_input" type="manual_input"/> - <node pkg="px4" name="commander" type="commander"/> - <node pkg="px4" name="mc_mixer" type="mc_mixer"/> - <node pkg="px4" name="attitude_estimator" type="attitude_estimator"/> - <node pkg="px4" name="mc_att_control" type="mc_att_control"/> -</group> +<include file="$(find mav_gazebo)/launch/vtol_empty_world_with_joy.launch" /> +<include file="$(find px4)/launch/multicopter.launch" /> </launch> diff --git a/launch/multicopter.launch b/launch/multicopter.launch index 96ff3ad99..2ccd1338b 100644 --- a/launch/multicopter.launch +++ b/launch/multicopter.launch @@ -7,6 +7,11 @@ <node pkg="px4" name="mc_mixer" type="mc_mixer"/> <node pkg="px4" name="attitude_estimator" type="attitude_estimator"/> <node pkg="px4" name="mc_att_control" type="mc_att_control"/> + + <param name="MC_ROLL_P" type="double" value="6.0" /> + <param name="MC_PITCH_P" type="double" value="6.0" /> + <param name="MC_ROLLRATE_P" type="double" value="0.05" /> + <param name="MC_PITCHRATE_P" type="double" value="0.05" /> </group> </launch> |