Skip to content

Commit

Permalink
Update configuration files in launch directory
Browse files Browse the repository at this point in the history
- Removed '/**' in namespace/node_name of parameters in configuration
  files that located under ./mavros/launch/ directory

This commit modifies the configuration files in the launch directory of the MAVROS package.
The '/**' in namespace/node_name of parameters were removed to ensure proper configuration.
The specific changes were made in thes files:
    ./mavros/launch/apm_config.yaml
    ./mavros/launch/apm_pluginlists.yaml
    ./mavros/launch/px4_config.yaml
    ./mavros/launch/px4_pluginlists.yaml
  • Loading branch information
hasanosman601 committed Oct 25, 2023
1 parent 67caa4d commit b577ccf
Show file tree
Hide file tree
Showing 4 changed files with 58 additions and 58 deletions.
56 changes: 28 additions & 28 deletions mavros/launch/apm_config.yaml
Original file line number Diff line number Diff line change
@@ -1,14 +1,14 @@
# Common configuration for APM2 autopilot
#
# node:
/mavros/**:
/mavros:
ros__parameters:
startup_px4_usb_quirk: false

# --- system plugins ---

# sys_status & sys_time connection options
/mavros/**/conn:
/mavros/conn:
ros__parameters:
heartbeat_rate: 1.0 # send heartbeat rate in Hertz
heartbeat_mav_type: "ONBOARD_CONTROLLER"
Expand All @@ -17,14 +17,14 @@
system_time_rate: 1.0 # send system time to FCU rate in Hertz (disabled if 0.0)

# sys_status
/mavros/**/sys:
/mavros/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:
/mavros/time:
ros__parameters:
time_ref_source: "fcu" # time_reference source
timesync_mode: MAVLINK
Expand All @@ -33,15 +33,15 @@
# --- mavros plugins (alphabetical order) ---

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

# actuator_control
# None

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

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

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

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

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

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

# setpoint_attitude
/mavros/**/setpoint_attitude:
/mavros/setpoint_attitude:
ros__parameters:
reverse_thrust: false # allow reversed thrust
use_quaternion: false # enable PoseStamped topic subscriber
Expand All @@ -105,12 +105,12 @@
tf.rate_limit: 50.0

# setpoint_raw
/mavros/**/setpoint_raw:
/mavros/setpoint_raw:
ros__parameters:
thrust_scaling: 1.0 # specify thrust scaling (normalized, 0 to 1) for thrust (like PX4)

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

# guided_target
/mavros/**/guided_target:
/mavros/guided_target:
ros__parameters:
tf.listen: false # enable tf listener (disable topic subscribers)
tf.frame_id: "map"
tf.child_frame_id: "target_position"
tf.rate_limit: 50.0

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

# vfr_hud
# None

# waypoint
/mavros/**/mission:
/mavros/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 @@ -153,7 +153,7 @@
## Currently available orientations:
# Check http://wiki.ros.org/mavros/**/Enumerations
##
/mavros/**/distance_sensor:
/mavros/distance_sensor:
ros__parameters:
config: |
rangefinder_pub:
Expand All @@ -169,12 +169,12 @@
orientation: PITCH_270 # only that orientation are supported by APM 3.4+
# image_pub
/mavros/**/image:
/mavros/image:
ros__parameters:
frame_id: "px4flow"

# fake_gps
/mavros/**/fake_gps:
/mavros/fake_gps:
ros__parameters:
# select data source
use_mocap: true # ~mocap/pose
Expand Down Expand Up @@ -202,7 +202,7 @@
gps_rate: 5.0 # GPS data publishing rate

# landing_target
/mavros/**/landing_target:
/mavros/landing_target:
ros__parameters:
listen_lt: false
mav_frame: "LOCAL_NED"
Expand All @@ -219,14 +219,14 @@
target_size: {x: 0.3, y: 0.3}

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

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

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

# px4flow
/mavros/**/px4flow:
/mavros/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:
/mavros/vision_pose:
ros__parameters:
tf.listen: false # enable tf listener (disable topic subscribers)
tf.frame_id: "map"
tf.child_frame_id: "vision_estimate"
tf.rate_limit: 10.0

# vision_speed_estimate
/mavros/**/vision_speed:
/mavros/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:
/mavros/vibration:
ros__parameters:
frame_id: "base_link"

# wheel_odometry
/mavros/**/wheel_odometry:
/mavros/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 Down
2 changes: 1 addition & 1 deletion mavros/launch/apm_pluginlists.yaml
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
/mavros/**:
/mavros:
ros__parameters:
plugin_denylist:
# common
Expand Down
Loading

0 comments on commit b577ccf

Please sign in to comment.