diff options
-rw-r--r-- | launch/ardrone.launch | 19 | ||||
-rw-r--r-- | launch/iris.launch | 17 |
2 files changed, 14 insertions, 22 deletions
diff --git a/launch/ardrone.launch b/launch/ardrone.launch index 495388be5..faf3bf6da 100644 --- a/launch/ardrone.launch +++ b/launch/ardrone.launch @@ -3,17 +3,14 @@ <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" /> + <param name="MPC_XY_P" type="double" value="1.0" /> + <param name="MPC_XY_FF" type="double" value="0.0" /> + <param name="MPC_XY_VEL_P" type="double" value="0.01" /> + <param name="MPC_XY_VEL_I" type="double" value="0.0" /> + <param name="MPC_XY_VEL_D" type="double" value="0.01" /> + <param name="MPC_XY_VEL_MAX" type="double" value="2.0" /> </group> + <node pkg="rosbag" type="record" name="record" output="screen" args="-a -O multicopter"/> + </launch> diff --git a/launch/iris.launch b/launch/iris.launch index 44a0ae034..7b5b13250 100644 --- a/launch/iris.launch +++ b/launch/iris.launch @@ -3,18 +3,13 @@ <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" /> <param name="mixer" type="string" value="i" /> + <param name="MPC_XY_P" type="double" value="1.0" /> + <param name="MPC_XY_FF" type="double" value="0.0" /> + <param name="MPC_XY_VEL_P" type="double" value="0.01" /> + <param name="MPC_XY_VEL_I" type="double" value="0.0" /> + <param name="MPC_XY_VEL_D" type="double" value="0.01" /> + <param name="MPC_XY_VEL_MAX" type="double" value="2.0" /> </group> </launch> |