Skip to content

Commit

Permalink
Remove hardcoded namespace from px4_config
Browse files Browse the repository at this point in the history
  • Loading branch information
mgiurato authored and vooon committed Oct 26, 2023
1 parent 1a0bfc6 commit d7e71dd
Showing 1 changed file with 29 additions and 29 deletions.
58 changes: 29 additions & 29 deletions mavros/launch/px4_config.yaml
Original file line number Diff line number Diff line change
@@ -1,25 +1,25 @@
# Common configuration for PX4 autopilot
#
/mavros/**:
/**:
ros__parameters:
startup_px4_usb_quirk: false

# sys_status & sys_time connection options
/mavros/**/conn:
/**/conn:
ros__parameters:
heartbeat_rate: 1.0 # send heartbeat rate in Hertz
timeout: 10.0 # heartbeat timeout in seconds
timesync_rate: 10.0 # TIMESYNC rate in Hertz (feature disabled if 0.0)
system_time_rate: 1.0 # send system time to FCU rate in Hertz (disabled if 0.0)

# sys_status
/mavros/**/sys:
/**/sys:
ros__parameters:
min_voltage: [10.0] # diagnostics min voltage, use a vector i.e. [16.2, 16.0] for multiple batteries, up-to 10 are supported to achieve the same on a ROS launch file do: <rosparam param="sys/min_voltage">[16.2, 16.0]</rosparam>
disable_diag: false # disable all sys_status diagnostics, except heartbeat

# sys_time
/mavros/**/time:
/**/time:
ros__parameters:
time_ref_source: fcu # time_reference source
timesync_mode: MAVLINK
Expand All @@ -28,15 +28,15 @@
# --- mavros plugins (alphabetical order) ---

# 3dr_radio
/mavros/**/tdr_radio:
/**/tdr_radio:
ros__parameters:
low_rssi: 40 # raw rssi lower level for diagnostics

# actuator_control
# None

# command
/mavros/**/cmd:
/**/cmd:
ros__parameters:
use_comp_id_system_control: false # quirk for some old FCUs

Expand All @@ -47,7 +47,7 @@
# None

# global_position
/mavros/**/global_position:
/**/global_position:
ros__parameters:
frame_id: "map" # origin frame
child_frame_id: "base_link" # body-fixed frame
Expand All @@ -60,7 +60,7 @@
tf.child_frame_id: "base_link" # TF child_frame_id

# imu_pub
/mavros/**/imu:
/**/imu:
ros__parameters:
frame_id: base_link
# need find actual values
Expand All @@ -70,7 +70,7 @@
magnetic_stdev: 0.0

# local_position
/mavros/**/local_position:
/**/local_position:
ros__parameters:
frame_id: "map"
tf.send: false
Expand All @@ -85,12 +85,12 @@
# None

# setpoint_accel
/mavros/**/setpoint_accel:
/**/setpoint_accel:
ros__parameters:
send_force: false

# setpoint_attitude
/mavros/**/setpoint_attitude:
/**/setpoint_attitude:
ros__parameters:
reverse_thrust: false # allow reversed thrust
use_quaternion: false # enable PoseStamped topic subscriber
Expand All @@ -99,14 +99,14 @@
tf.child_frame_id: "target_attitude"
tf.rate_limit: 50.0

/mavros/**/setpoint_raw:
/**/setpoint_raw:
ros__parameters:
thrust_scaling: 1.0 # used in setpoint_raw attitude callback.
# Note: PX4 expects normalized thrust values between 0 and 1, which means that
# the scaling needs to be unitary and the inputs should be 0..1 as well.

# setpoint_position
/mavros/**/setpoint_position:
/**/setpoint_position:
ros__parameters:
tf.listen: false # enable tf listener (disable topic subscribers)
tf.frame_id: "map"
Expand All @@ -115,15 +115,15 @@
mav_frame: LOCAL_NED

# setpoint_velocity
/mavros/**/setpoint_velocity:
/**/setpoint_velocity:
ros__parameters:
mav_frame: LOCAL_NED

# vfr_hud
# None

# waypoint
/mavros/**/mission:
/**/mission:
ros__parameters:
pull_after_gcs: true # update mission if gcs updates
use_mission_item_int: true # use the MISSION_ITEM_INT message instead of MISSION_ITEM
Expand All @@ -140,9 +140,9 @@

# distance_sensor
## Currently available orientations:
# Check http://wiki.ros.org/mavros/**/Enumerations
# Check http://wiki.ros.org/**/Enumerations
##
/mavros/**/distance_sensor:
/**/distance_sensor:
ros__parameters:
config: |
hrlv_ez4_pub:
Expand Down Expand Up @@ -175,13 +175,13 @@
orientation: PITCH_270
# image_pub
/mavros/**/image:
/**/image:
ros__parameters:
frame_id: "px4flow"


# fake_gps
/mavros/**/fake_gps:
/**/fake_gps:
ros__parameters:
# select data source
use_mocap: true # ~mocap/pose
Expand All @@ -204,7 +204,7 @@


# landing_target
/mavros/**/landing_target:
/**/landing_target:
ros__parameters:
listen_lt: false
mav_frame: "LOCAL_NED"
Expand All @@ -222,14 +222,14 @@


# mocap_pose_estimate
/mavros/**/mocap:
/**/mocap:
ros__parameters:
# select mocap source
use_tf: false # ~mocap/tf
use_pose: true # ~mocap/pose

# mount_control
/mavros/**/mount:
/**/mount:
ros__parameters:
debounce_s: 4.0
err_threshold_deg: 10.0
Expand All @@ -238,41 +238,41 @@
negate_measured_yaw: false

# odom
/mavros/**/odometry:
/**/odometry:
ros__parameters:
fcu.odom_parent_id_des: "map" # desired parent frame rotation of the FCU's odometry
fcu.odom_child_id_des: "base_link" # desired child frame rotation of the FCU's odometry

# px4flow
/mavros/**/px4flow:
/**/px4flow:
ros__parameters:
frame_id: "px4flow"
ranger_fov: 0.118682 # 6.8 degrees at 5 meters, 31 degrees at 1 meter
ranger_min_range: 0.3 # meters
ranger_max_range: 5.0 # meters

# vision_pose_estimate
/mavros/**/vision_pose:
/**/vision_pose:
ros__parameters:
tf.listen: false # enable tf listener (disable topic subscribers)
tf.frame_id: "odom"
tf.child_frame_id: "vision_estimate"
tf.rate_limit: 10.0

# vision_speed_estimate
/mavros/**/vision_speed:
/**/vision_speed:
ros__parameters:
listen_twist: true # enable listen to twist topic, else listen to vec3d topic
twist_cov: true # enable listen to twist with covariance topic

# vibration
/mavros/**/vibration:
/**/vibration:
ros__parameters:
frame_id: "base_link"


# wheel_odometry
/mavros/**/wheel_odometry:
/**/wheel_odometry:
ros__parameters:
count: 2 # number of wheels to compute odometry
use_rpm: false # use wheel's RPM instead of cumulative distance to compute odometry
Expand All @@ -288,7 +288,7 @@
tf.child_frame_id: "base_link"

# camera
/mavros/**/camera:
/**/camera:
ros__parameters:
frame_id: "base_link"

0 comments on commit d7e71dd

Please sign in to comment.