Skip to content

Commit

Permalink
added new launcher files
Browse files Browse the repository at this point in the history
  • Loading branch information
marcelinomalmeidan committed Jun 15, 2017
1 parent 498fdc0 commit 1c4a9e5
Show file tree
Hide file tree
Showing 4 changed files with 89 additions and 2 deletions.
44 changes: 44 additions & 0 deletions launch/360dragonfly.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
<launch>
<node pkg="px4_control"
type="px4_control_node"
name="px4_control_node"
output="screen">

<!-- Joystick Attitude Reference parameters -->
<param name="RollMax" value="30.0"/> <!-- degrees -->
<param name="PitchMax" value="30.0"/> <!-- degrees -->
<param name="YawRateMax" value="45.0"/> <!-- deg/sec -->
<param name="maxThrust" value="0.7"/> <!-- From 0 to 1 -->

<!-- Joystick Position Reference parameters -->
<param name="xRate" value="1.0"/> <!-- meters/sec -->
<param name="yRate" value="1.0"/> <!-- meters/sec -->
<param name="zRate" value="0.5"/> <!-- meters/sec -->
<param name="PosRefTimeConstant" value="0.2"/> <!-- seconds -->

<!-- Topic with odometry information for the vehicle -->
<param name="odomTopic" value="/Dragonfly/odom"/>

<!-- Type of joystick being used. Admitted types are:
joyXboxOne / joyXbox360 / joyXbox360Wired -->
<param name="joyDriver" value="joyXbox360Wired"/>

<!-- Position Control parameters -->
<param name="mass" value="0.407"/> <!-- kg -->
<param name="gz" value="9.81"/> <!-- m/s^2 -->
<param name="thrustRatio" value="2.3"/> <!-- maxThrust/Weight -->
<param name="kpx" value="1.7"/>
<param name="kpy" value="1.7"/>
<param name="kpz" value="1.2"/>
<param name="kvx" value="0.8"/>
<param name="kvy" value="0.8"/>
<param name="kvz" value="0.7"/>
<param name="kix" value="0"/>
<param name="kiy" value="0"/>
<param name="kiz" value="0"/>
<param name="maxInteg_x" value="0"/>
<param name="maxInteg_y" value="0"/>
<param name="maxInteg_z" value="0"/>
</node>
</launch>

43 changes: 43 additions & 0 deletions launch/360gazebo.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
<launch>
<node pkg="px4_control"
type="px4_control_node"
name="px4_control_node"
output="screen">

<!-- Joystick Attitude Reference parameters -->
<param name="RollMax" value="30.0"/> <!-- degrees -->
<param name="PitchMax" value="30.0"/> <!-- degrees -->
<param name="YawRateMax" value="45.0"/> <!-- deg/sec -->
<param name="maxThrust" value="0.7"/> <!-- From 0 to 1 -->

<!-- Joystick Position Reference parameters -->
<param name="xRate" value="1.0"/> <!-- meters/sec -->
<param name="yRate" value="1.0"/> <!-- meters/sec -->
<param name="zRate" value="0.5"/> <!-- meters/sec -->

<!-- Topic with odometry information for the vehicle -->
<param name="odomTopic" value="/mavros/local_position/odom"/>

<!-- Type of joystick being used. Admitted types are:
joyXboxOne / joyXbox360 / joyXbox360Wired -->
<param name="joyDriver" value="joyXbox360Wired"/>

<!-- Position Control parameters -->
<param name="mass" value="1.535"/> <!-- kg -->
<param name="gz" value="9.81"/> <!-- m/s^2 -->
<param name="thrustRatio" value="1.7"/> <!-- maxThrust/Weight -->
<param name="kpx" value="10"/>
<param name="kpy" value="10"/>
<param name="kpz" value="10"/>
<param name="kvx" value="5"/>
<param name="kvy" value="5"/>
<param name="kvz" value="7.5"/>
<param name="kix" value="0"/>
<param name="kiy" value="0"/>
<param name="kiz" value="0"/>
<param name="maxInteg_x" value="0"/>
<param name="maxInteg_y" value="0"/>
<param name="maxInteg_z" value="0"/>
</node>
</launch>

2 changes: 1 addition & 1 deletion launch/dragonfly.launch
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
<param name="xRate" value="1.0"/> <!-- meters/sec -->
<param name="yRate" value="1.0"/> <!-- meters/sec -->
<param name="zRate" value="0.5"/> <!-- meters/sec -->
<param name="PosRefTimeConstant" values="0.2"/> <!-- seconds -->
<param name="PosRefTimeConstant" value="0.2"/> <!-- seconds -->

<!-- Topic with odometry information for the vehicle -->
<param name="odomTopic" value="/mavros/local_position/odom"/>
Expand Down
2 changes: 1 addition & 1 deletion launch/px4.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<!-- vim: set ft=xml noet : -->
<!-- example launch script for PX4 based FCU's -->

<arg name="fcu_url" default="udp://:14540@192.168.1.36:14557"/>
<arg name="fcu_url" default="udp://:14550@192.168.1.43:14556"/>
<arg name="gcs_url" default="" />
<arg name="tgt_system" default="1" />
<arg name="tgt_component" default="1" />
Expand Down

0 comments on commit 1c4a9e5

Please sign in to comment.