mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-21 01:12:11 +00:00
ros: move params to type/frame launch files
This commit is contained in:
@@ -2,4 +2,18 @@
|
||||
|
||||
<include file="$(find px4)/launch/multicopter_x.launch" />
|
||||
|
||||
<group ns="px4_multicopter">
|
||||
<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_ROLLRATE_D" type="double" value="0.0" />
|
||||
<param name="MC_PITCHRATE_P" type="double" value="0.05" />
|
||||
<param name="MC_PITCHRATE_D" type="double" value="0.0" />
|
||||
<param name="MC_YAW_FF" type="double" value="0" />
|
||||
<param name="MC_YAW_P" type="double" value="5.0" />
|
||||
<param name="MC_YAWRATE_P" type="double" value="0.5" />
|
||||
<param name="MC_MAN_R_MAX" type="double" value="10.0" />
|
||||
<param name="MC_MAN_P_MAX" type="double" value="10.0" />
|
||||
</group>
|
||||
|
||||
</launch>
|
||||
|
||||
@@ -2,4 +2,18 @@
|
||||
|
||||
<include file="$(find px4)/launch/multicopter_w.launch" />
|
||||
|
||||
<group ns="px4_multicopter">
|
||||
<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_ROLLRATE_D" type="double" value="0.0" />
|
||||
<param name="MC_PITCHRATE_P" type="double" value="0.05" />
|
||||
<param name="MC_PITCHRATE_D" type="double" value="0.0" />
|
||||
<param name="MC_YAW_FF" type="double" value="0" />
|
||||
<param name="MC_YAW_P" type="double" value="3.0" />
|
||||
<param name="MC_YAWRATE_P" type="double" value="0.5" />
|
||||
<param name="MC_MAN_R_MAX" type="double" value="10.0" />
|
||||
<param name="MC_MAN_P_MAX" type="double" value="10.0" />
|
||||
</group>
|
||||
|
||||
</launch>
|
||||
|
||||
@@ -7,19 +7,6 @@
|
||||
<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_ROLLRATE_D" type="double" value="0.0" />
|
||||
<param name="MC_PITCHRATE_P" type="double" value="0.05" />
|
||||
<param name="MC_PITCHRATE_D" type="double" value="0.0" />
|
||||
<param name="MC_YAW_FF" type="double" value="0" />
|
||||
<param name="MC_YAW_P" type="double" value="5.0" />
|
||||
<param name="MC_YAWRATE_P" type="double" value="0.5" />
|
||||
<param name="MC_MAN_R_MAX" type="double" value="10.0" />
|
||||
<param name="MC_MAN_P_MAX" type="double" value="10.0" />
|
||||
<param name="mixer" type="string" value="x" />
|
||||
</group>
|
||||
|
||||
</launch>
|
||||
|
||||
Reference in New Issue
Block a user