Skip to content

Commit 3d1ecfc

Browse files
authored
Fix GPS/IMU update rates. (#723)
Signed-off-by: Carlos Agüero <[email protected]>
1 parent 7aeb71d commit 3d1ecfc

File tree

2 files changed

+3
-3
lines changed

2 files changed

+3
-3
lines changed

vrx_urdf/wamv_gazebo/urdf/components/wamv_gps.xacro

+2-2
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
<?xml version="1.0" encoding="UTF-8"?>
22
<robot xmlns:xacro="http://ros.org/wiki/xacro">
33
<xacro:macro name="wamv_gps" params="name:=gps x:=0.3 y:=0 z:=1.3
4-
R:=0 P:=0 Y:=0 update_rate:=15">
4+
R:=0 P:=0 Y:=0 update_rate:=20">
55
<link name="${namespace}/${name}_link">
66
<visual name="${name}_visual">
77
<geometry>
@@ -38,7 +38,7 @@
3838
<gazebo reference="${namespace}/${name}_link">
3939
<sensor name="navsat" type="navsat">
4040
<always_on>1</always_on>
41-
<update_rate>15</update_rate>
41+
<update_rate>${update_rate}</update_rate>
4242
<!--<topic>${namespace}/${sensor_namespace}gps/gps/fix</topic>-->
4343
</sensor>
4444
</gazebo>

vrx_urdf/wamv_gazebo/urdf/components/wamv_imu.xacro

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
<?xml version="1.0"?>
22
<robot xmlns:xacro="http://ros.org/wiki/xacro">
3-
<xacro:macro name="wamv_imu" params="name:=imu x:=0.3 y:=0.5 z:=1.3 R:=0 P:=0 Y:=0 update_rate:=15">
3+
<xacro:macro name="wamv_imu" params="name:=imu x:=0.3 y:=0.5 z:=1.3 R:=0 P:=0 Y:=0 update_rate:=100">
44
<link name="${namespace}/${name}_link">
55
<visual name="${name}_visual">>
66
<geometry>

0 commit comments

Comments
 (0)