Skip to content

Commit

Permalink
param config for robot_localization
Browse files Browse the repository at this point in the history
  • Loading branch information
AnielAlexa committed Feb 16, 2024
1 parent e20518b commit 281945c
Show file tree
Hide file tree
Showing 4 changed files with 28 additions and 31 deletions.
11 changes: 4 additions & 7 deletions rae_camera/config/camera.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -8,22 +8,19 @@

i_calibration_dump: false
i_pipeline_dump: false
imu:
i_acc_cov: 0.1
i_gyro_cov: 0.001
i_batch_report_threshold: 5
i_max_batch_reports: 5
i_gyro_freq: 400
i_acc_freq: 65
nn:
i_nn_config_path: /workspaces/rae_ws/src/rae-ros/rae_camera/config/yolo.json
i_disable_resize: true
i_enable_passthrough: true
imu:
i_acc_cov: 0.1
i_gyro_cov: 0.001
i_rot_cov: 0.000001
i_batch_report_threshold: 5
i_max_batch_reports: 5
i_enable_rotation: true
i_message_type: IMU_WITH_MAG_SPLIT
i_rotation_vector_type: GAME_ROTATION_VECTOR
i_sync_method: COPY
i_gyro_freq: 100
i_acc_freq: 100
Expand Down
2 changes: 1 addition & 1 deletion rae_hw/config/controller.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ diff_controller:
velocity_rolling_window_size: 1

open_loop: false
enable_odom_tf: true
enable_odom_tf: false

cmd_vel_timeout: 0.5
use_stamped_vel: false
Expand Down
10 changes: 5 additions & 5 deletions rae_hw/config/ekf.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ ekf_filter_node:
# The frequency, in Hz, at which the filter will output a position estimate. Note that the filter will not begin
# computation until it receives at least one message from one of the inputs. It will then run continuously at the
# frequency specified here, regardless of whether it receives more measurements. Defaults to 30 if unspecified.
frequency: 50.0
frequency: 10.0

# The period, in seconds, after which we consider a sensor to have timed out. In this event, we carry out a predict
# cycle on the EKF without correcting it. This parameter can be thought of as the minimum frequency with which the
Expand All @@ -20,7 +20,7 @@ ekf_filter_node:
# Use this parameter to provide an offset to the transform generated by ekf_localization_node. This can be used for
# future dating the transform, which is required for interaction with some other packages. Defaults to 0.0 if
# unspecified.
transform_time_offset: 0.0
transform_time_offset: 0.3

# Use this parameter to provide specify how long the tf listener should wait for a transform to become available.
# Defaults to 0.0 if unspecified.
Expand All @@ -45,7 +45,7 @@ ekf_filter_node:
publish_acceleration: false

# Whether to broadcast the transformation over the /tf topic. Defaults to true if unspecified.
publish_tf: false
publish_tf: true

# REP-105 (http://www.ros.org/reps/rep-0105.html) specifies four principal coordinate frames: base_link, odom, map, and
# earth. base_link is the coordinate frame that is affixed to the robot. Both odom and map are world-fixed frames.
Expand Down Expand Up @@ -129,15 +129,15 @@ ekf_filter_node:

# Further input parameter examples

imu0: imu/data
imu0: rae/imu/data
imu0_config: [false, false, false,
false, false, true,
false, false, false,
false, false, false,
false, false, false]
imu0_differential: false
imu0_relative: false
imu0_queue_size: 1
imu0_queue_size: 10
imu0_pose_rejection_threshold: 0.8 # Note the difference in parameter names
imu0_twist_rejection_threshold: 0.8 #
imu0_linear_acceleration_rejection_threshold: 0.8 #
Expand Down
36 changes: 18 additions & 18 deletions rae_hw/launch/control.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -43,24 +43,24 @@ def launch_setup(context, *args, **kwargs):
'rae_hw'), 'config', 'ekf.yaml')],
)

imu_comp_filt = Node(
package='imu_complementary_filter',
executable='complementary_filter_node',
name='complementary_filter_gain_node',
namespace=LaunchConfiguration('namespace'),
output='screen',
parameters=[
{'do_bias_estimation': True},
{'do_adaptive_gain': True},
{'orientation_stddev': 0.001},
{'use_mag': False},
{'gain_acc': 0.04},
{'gain_mag': 0.01},
],
remappings=[
('imu/data_raw', '/rae/imu/data'),
]
)
# imu_comp_filt = Node(
# package='imu_complementary_filter',
# executable='complementary_filter_node',
# name='complementary_filter_gain_node',
# namespace=LaunchConfiguration('namespace'),
# output='screen',
# parameters=[
# {'do_bias_estimation': True},
# {'do_adaptive_gain': True},
# {'orientation_stddev': 0.001},
# {'use_mag': False},
# {'gain_acc': 0.04},
# {'gain_mag': 0.01},
# ],
# remappings=[
# ('imu/data_raw', '/rae/imu/data'),
# ]
# )

controller_manager = Node(
package='controller_manager',
Expand Down

0 comments on commit 281945c

Please sign in to comment.