diff --git a/rosbot_xl_description/urdf/rosbot_xl.urdf.xacro b/rosbot_xl_description/urdf/rosbot_xl.urdf.xacro index a994bc3..46b0776 100644 --- a/rosbot_xl_description/urdf/rosbot_xl.urdf.xacro +++ b/rosbot_xl_description/urdf/rosbot_xl.urdf.xacro @@ -20,10 +20,10 @@ + parent_link="body_link" + xyz="-0.155 -0.055 0.065" + rpy="0.0 0.0 0.0" + antenna_angle="0.0" /> @@ -31,9 +31,6 @@ - - @@ -54,8 +49,6 @@ parent_link="${lidar_parent_link}" xyz="${lidar_xyz}" rpy="${lidar_rpy}" - use_gpu="${lidar_use_gpu}" - simulation_engine="$(arg simulation_engine)" namespace="$(arg namespace)" /> @@ -66,8 +59,6 @@ parent_link="${lidar_parent_link}" xyz="${lidar_xyz}" rpy="${lidar_rpy}" - use_gpu="${lidar_use_gpu}" - simulation_engine="$(arg simulation_engine)" namespace="$(arg namespace)" /> @@ -78,8 +69,6 @@ parent_link="${lidar_parent_link}" xyz="${lidar_xyz}" rpy="${lidar_rpy}" - use_gpu="${lidar_use_gpu}" - simulation_engine="$(arg simulation_engine)" namespace="$(arg namespace)" /> @@ -90,8 +79,6 @@ parent_link="${lidar_parent_link}" xyz="${lidar_xyz}" rpy="${lidar_rpy}" - use_gpu="${lidar_use_gpu}" - simulation_engine="$(arg simulation_engine)" namespace="$(arg namespace)" /> @@ -102,9 +89,6 @@ parent_link="${lidar_parent_link}" xyz="${lidar_xyz}" rpy="${lidar_rpy}" - use_gpu="${lidar_use_gpu}" - simulation_engine="$(arg simulation_engine)" - topic="velodyne_points" namespace="$(arg namespace)" /> @@ -126,7 +110,6 @@ xyz="${camera_xyz}" rpy="${camera_rpy}" use_nominal_extrinsics="$(arg use_sim)" - simulation_engine="$(arg simulation_engine)" namespace="$(arg namespace)" /> @@ -138,7 +121,6 @@ parent_link="${camera_parent_link}" xyz="${camera_xyz}" rpy="${camera_rpy}" - simulation_engine="$(arg simulation_engine)" namespace="$(arg namespace)" /> @@ -170,7 +152,6 @@ xyz="${camera_xyz}" rpy="${camera_rpy}" model="${camera_model_type}" - simulation_engine="$(arg simulation_engine)" namespace="$(arg namespace)" />