ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
The problem was with gazebo's /clock
publishing frequency which is, by default, set to 10Hz. There is a corresponding issue topic on this problem here.
The issue can be addressed by creating a gazebo.yaml
params file including
gazebo:
ros__parameters:
publish_rate: 100.0
and changing the launch file to
gazebo = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(get_package_share_directory("gazebo_ros"), "launch", "gazebo.launch.py")
),
launch_arguments={
"world": world,
"extra_gazebo_args": ["--ros-args --params-file ", gazebo_params],
}.items(),
Where gazebo_params
is a LaunchConfiguration
corresponding to the full path to the gazebo.yaml
config file.
2 | No.2 Revision |
The problem was with gazebo's /clock
publishing frequency which is, by default, set to 10Hz. There is a corresponding issue topic on this problem here.
The issue can be addressed by creating a gazebo.yaml
params file including
gazebo:
ros__parameters:
publish_rate: 100.0
and changing the launch file to
gazebo = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(get_package_share_directory("gazebo_ros"), "launch", "gazebo.launch.py")
),
launch_arguments={
"world": world,
"extra_gazebo_args": ["--ros-args --params-file ", gazebo_params],
}.items(),
Where gazebo_params
is a LaunchConfiguration
corresponding to the full path to the gazebo.yaml
config file.
$ ros2 topic hz /odometry/filtered/odom
average rate: 29.787
min: 0.030s max: 0.044s std dev: 0.00379s window: 31
average rate: 29.811
min: 0.030s max: 0.044s std dev: 0.00393s window: 62
average rate: 29.856
min: 0.030s max: 0.044s std dev: 0.00385s window: 93
3 | No.3 Revision |
Credit to @ljaniec for referring me to the relevant issue.
The problem was with gazebo's /clock
publishing frequency which is, by default, set to 10Hz. There is a corresponding issue topic on this problem here.
The issue can be addressed by creating a gazebo.yaml
params file including
gazebo:
ros__parameters:
publish_rate: 100.0
and changing the launch file to
gazebo = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(get_package_share_directory("gazebo_ros"), "launch", "gazebo.launch.py")
),
launch_arguments={
"world": world,
"extra_gazebo_args": ["--ros-args --params-file ", gazebo_params],
}.items(),
Where gazebo_params
is a LaunchConfiguration
corresponding to the full path to the gazebo.yaml
config file. Doing so enables the ekf node to run at the commanded frequency (30Hz):
$ ros2 topic hz /odometry/filtered/odom
average rate: 29.787
min: 0.030s max: 0.044s std dev: 0.00379s window: 31
average rate: 29.811
min: 0.030s max: 0.044s std dev: 0.00393s window: 62
average rate: 29.856
min: 0.030s max: 0.044s std dev: 0.00385s window: 93