diff --git a/urdf/hokuyo_laser2d.xacro b/urdf/hokuyo_laser2d.xacro
index 70c213a8137cd8d556ed9fc687744c71741678ab..6efd1cb7d68d18188ef6959203ac001577197de5 100644
--- a/urdf/hokuyo_laser2d.xacro
+++ b/urdf/hokuyo_laser2d.xacro
@@ -10,7 +10,7 @@
                params="name:=main 
                        prefix:=robot
                        parent:=base
-                       mesh_resolution:=low
+                       mesh_resolution:=low_res
                        config_file:=${default_config}
                        model:=utm30lx
                        *origin">
diff --git a/urdf/hokuyo_laser2d_example.xacro b/urdf/hokuyo_laser2d_example.xacro
index fc0682f429163a6309350262b869ac41558e1d94..6b2d2198f2c4eb2c613fd8b86b4790b26b54d0e3 100644
--- a/urdf/hokuyo_laser2d_example.xacro
+++ b/urdf/hokuyo_laser2d_example.xacro
@@ -27,7 +27,7 @@
     </collision>
   </link>
 
-  <xacro:hokuyo_laser2d name="top" prefix="robot" parent="hokuyo_base" resolution="low_res" model="utm30lx">
+  <xacro:hokuyo_laser2d name="top" prefix="robot" parent="hokuyo_base" mesh_resolution="low" model="utm30lx">
     <origin xyz="0.0 0.0 0.5" rpy="0 0 0" />
   </xacro:hokuyo_laser2d>