Skip to content

Commit

Permalink
launch: PX4: use node.launch in PX4 scripts.
Browse files Browse the repository at this point in the history
Also remove px4_local_gcs.launch: please use
`roslaunch mavros px4.launch gcs_url:=udp://@localhost` instead.

Issue #144.
  • Loading branch information
vooon committed Sep 8, 2014
1 parent 8baa1fb commit 826be38
Show file tree
Hide file tree
Showing 9 changed files with 150 additions and 64 deletions.
2 changes: 1 addition & 1 deletion mavros/launch/apm2.launch
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<launch>
<!-- vim: ft=roslaunch -->
<!-- vim: ft=xml -->
<!-- example launch script for ArduPilotMega based FCU's -->

<arg name="fcu_url" default="/dev/ttyACM0:57600" />
Expand Down
2 changes: 1 addition & 1 deletion mavros/launch/apm2_radio.launch
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<launch>
<!-- vim: ft=roslaunch -->
<!-- vim: ft=xml -->
<!-- This file almost same as apm2.launch but defaults set for connections via 3DR Radio modem -->

<arg name="fcu_url" default="/dev/ttyUSB0:57600" />
Expand Down
2 changes: 1 addition & 1 deletion mavros/launch/node.launch
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<launch>
<!-- vim: ft=roslaunch -->
<!-- vim: ft=xml -->
<!-- base node launch file-->

<arg name="fcu_url" />
Expand Down
26 changes: 10 additions & 16 deletions mavros/launch/px4.launch
Original file line number Diff line number Diff line change
@@ -1,25 +1,19 @@
<launch>
<!-- vim: ft=roslaunch -->
<!-- vim: ft=xml -->
<!-- example launch script for PX4 based FCU's -->

<arg name="fcu_url" default="serial:///dev/ttyACM0:57600" />
<arg name="fcu_url" default="/dev/ttyACM0:57600" />
<arg name="gcs_url" default="" />
<arg name="tgt_system" default="1" />
<arg name="tgt_component" default="50" />

<node pkg="mavros" type="mavros_node" name="mavros" required="true" clear_params="true" output="screen">
<param name="fcu_url" value="$(arg fcu_url)" />
<param name="gcs_url" value="$(arg gcs_url)" />
<param name="target_system_id" value="$(arg tgt_system)" />
<param name="target_component_id" value="$(arg tgt_component)" />
<include file="$(find mavros)/launch/node.launch">
<arg name="blacklist_yaml" value="$(find mavros)/launch/px4_blacklist.yaml" />
<arg name="config_yaml" value="$(find mavros)/launch/px4_config.yaml" />

<!-- px4 blacklist -->
<rosparam command="load" file="$(find mavros)/launch/px4_blacklist.yaml" />

<!-- enable heartbeat send and reduce timeout -->
<param name="conn_heartbeat" value="5.0" />
<param name="conn_timeout" value="10.0" />
<!-- enable mavlink autostart on USB port -->
<param name="startup_px4_usb_quirk" value="true" />
</node>
<arg name="fcu_url" value="$(arg fcu_url)" />
<arg name="gcs_url" value="$(arg gcs_url)" />
<arg name="tgt_system" value="$(arg tgt_system)" />
<arg name="tgt_component" value="$(arg tgt_component)" />
</include>
</launch>
3 changes: 2 additions & 1 deletion mavros/launch/px4_blacklist.yaml
Original file line number Diff line number Diff line change
@@ -1 +1,2 @@
plugin_blacklist: []
plugin_blacklist:
- '3dr_radio'
123 changes: 123 additions & 0 deletions mavros/launch/px4_config.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,123 @@
# Common configuration for PX4 autopilot
#
# node:
startup_px4_usb_quirk: true

# sys_status
conn_heartbeat: 5.0 # send hertbeat every n secs
conn_timeout: 10.0 # hertbeat timeout n secs
sys:
min_voltage: 10.0 # diagnostics min voltage

# imu_pub
imu:
frame_id: "fcu"
# need find actual values
linear_acceleration_stdev: 0.0003
angular_velocity_stdev: !degrees 0.02
orientation_stdev: 1.0
magnetic_stdev: 0.0

# gps
gps:
frame_id: "gps"
#time_ref_source: "gps"

# param
# None

# waypoint
mission:
pull_after_gcs: true # update mission if gcs updates

# pc_io
# None

# command
# None

# *_position
#position:
# # local_position
# local:
# send_tf: false
# frame_id: "local_origin"
# child_frame_id: "fcu"
#
# # vision_pose_estimate [extra]
# vision:
# pose_with_covariance: false
# listen_tf: false
# frame_id: "local_origin"
# child_frame_id: "vision"
# tf_rate_limit: 10.0

# *_setpoint
#setpoint:
# # setpoint_accel
# accel:
# send_force: false
#
# # setpoint_attitude
# attitude:
# listen_tf: false
# listen_twist: false
# pose_with_covariance: false
# frame_id: "local_origin"
# child_frame_id: "attitude"
# tf_rate_limit: 10.0
#
# # setpoint_position
# position:
# listen_tf: false
# frame_id: "local_origin"
# child_frame_id: "setpoint"
# tf_rate_limit: 10.0
#
# # setpoint_velocity
# # None

# safety_area
#safety_area:
# p1:
# x: 1.0
# y: 1.0
# z: 1.0
# p2:
# x: -1.0
# y: -1.0
# z: -1.0

# 3dr_radio
# None

# global_position
#global_position:
# send_tf: false
# frame_id: "local_origin"
# child_frame_id: "fcu"
# rot_covariance: 99999.0

# vfr_hud
# None

# ftp
# None

# vision_speed_estimates [extras]
#vision_speed:
# listen_twist: false

# px4flow [extras]
#optical_flow_tx: false # publish mode (rx from FCU)

# image_pub [extras]
# None

# mocap_pose_estimate [extras]
#mocap:
# # select mocap source
# use_tf: false # ~mocap/tf
# use_pose: true # ~mocap/pose

# vim:ts=2 sw=2 et:
26 changes: 0 additions & 26 deletions mavros/launch/px4_local_gcs.launch

This file was deleted.

29 changes: 11 additions & 18 deletions mavros/launch/px4_radio.launch
Original file line number Diff line number Diff line change
@@ -1,26 +1,19 @@
<launch>
<!-- vim: ft=roslaunch -->
<!-- example launch script for PX4 based FCU's -->
<!-- vim: ft=xml -->
<!-- This file almost same as px4.launch but defaults set for connections via 3DR Radio modem -->

<arg name="fcu_url" default="serial:///dev/ttyUSB0:57600" /> <!-- Radio link: /dev/ttyUSB0 @57600 -->
<arg name="fcu_url" default="/dev/ttyUSB0:57600" />
<arg name="gcs_url" default="" />
<arg name="tgt_system" default="1" />
<arg name="tgt_component" default="50" />

<node pkg="mavros" type="mavros_node" name="mavros" required="true" clear_params="true" output="screen">
<param name="fcu_url" value="$(arg fcu_url)" />
<param name="gcs_url" value="$(arg gcs_url)" />
<param name="target_system_id" value="$(arg tgt_system)" />
<param name="target_component_id" value="$(arg tgt_component)" />
<include file="$(find mavros)/launch/node.launch">
<arg name="blacklist_yaml" value="$(find mavros)/launch/px4_radio_blacklist.yaml" />
<arg name="config_yaml" value="$(find mavros)/launch/px4_config.yaml" />

<!-- px4 blacklist -->
<rosparam command="load" file="$(find mavros)/launch/px4_blacklist.yaml" />

<!-- enable heartbeat send and reduce timeout -->
<param name="conn_heartbeat" value="5.0" />
<param name="conn_timeout" value="10.0" />
<!-- enable mavlink autostart on USB port -->
<param name="startup_px4_usb_quirk" value="true" />
</node>
</launch>
<arg name="fcu_url" value="$(arg fcu_url)" />
<arg name="gcs_url" value="$(arg gcs_url)" />
<arg name="tgt_system" value="$(arg tgt_system)" />
<arg name="tgt_component" value="$(arg tgt_component)" />
</include>
</launch>
1 change: 1 addition & 0 deletions mavros/launch/px4_radio_blacklist.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
plugin_blacklist: []

1 comment on commit 826be38

@TSC21
Copy link
Member

@TSC21 TSC21 commented on 826be38 Sep 9, 2014

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@vooon I already tried to set a launch using px4.launch. In px4_config.yaml I have:

# *_position
position:
#  # local_position
  local:
    send_tf: false
#    frame_id: "local_origin"
#    child_frame_id: "fcu"
#
#  # vision_pose_estimate [extra]
  vision:
#    pose_with_covariance: false
    listen_tf: true
#    frame_id: "local_origin"
#    child_frame_id: "vision"
#    tf_rate_limit: 10.0

I already checked using rosparam get /mavros/position/vision/listen_tf that the value of listen_tf is true but still the param value is not loaded when I issue roslaunch mavros px4.launch.

What am I doing wrong or if this is ok, what's wrong with it?

Thanks in advance!

Please sign in to comment.