diff --git a/launch/description.launch b/launch/description.launch index a2965e86535f2da78bb53f7e4d49f275aab5680d..cba50b576c8f70815e2cbbb278eca2bef36a7804 100644 --- a/launch/description.launch +++ b/launch/description.launch @@ -3,10 +3,11 @@ <arg name="name" default="model_car"/> <arg name="sim_config_path" default="$(find iri_model_car_gazebo)/config"/> + <arg name="model" default="$(find iri_model_car_description)/urdf/car.xacro"/> <group ns="$(arg name)"> <param name="robot_description" - command="$(find xacro)/xacro '$(find iri_model_car_description)/urdf/car.xacro' name:=$(arg name) sim_config_path:=$(arg sim_config_path)" /> + command="$(find xacro)/xacro '$(arg model)' name:=$(arg name) sim_config_path:=$(arg sim_config_path)" /> <node pkg="robot_state_publisher" type="robot_state_publisher" name="tf_broadcaster_$(arg name)"> <param name="publish_frequency" type="double" value="50.0"/> diff --git a/launch/description_test.launch b/launch/description_test.launch index be2afc48e8347fca0f39a04b017f85e9d83b90e6..fd0a5caf56802f53095211f7555e6dc365be05ce 100644 --- a/launch/description_test.launch +++ b/launch/description_test.launch @@ -3,10 +3,12 @@ <arg name="name" default="model_car"/> <arg name="sim_config_path" default="$(find iri_model_car_gazebo)/config"/> + <arg name="model" default="$(find iri_model_car_description)/urdf/car.xacro"/> <include file="$(find iri_model_car_description)/launch/description.launch"> <arg name="name" value="$(arg name)"/> <arg name="sim_config_path" value="$(arg sim_config_path)"/> + <arg name="model" value="$(arg model)"/> </include> <group ns="$(arg name)"> diff --git a/meshes/base.stl b/meshes/base.stl index 24c364807a2b92e7f80b2d6e8b53d7a1183b2cdc..51d2f91220759570ae8ea5facd231c9b8d8d8005 100644 Binary files a/meshes/base.stl and b/meshes/base.stl differ diff --git a/urdf/include/platform.xacro b/urdf/include/platform.xacro index 6da00be73bebdf9e02f8404bb64e37f4bdfc1023..d4a06297cf5d89c92d440f0a1c80e70d47055679 100644 --- a/urdf/include/platform.xacro +++ b/urdf/include/platform.xacro @@ -32,11 +32,11 @@ <link name="body"> <inertial> - <mass value="5.66119736" /> - <origin xyz="0.18422506 0.00000000 0.0504506" /> - <inertia ixx="0.02201830" ixy="0.00000000" ixz="-0.00092111" - iyy="0.06244486" iyz="0.00000000" - izz="0.06627095" /> + <mass value="5.55765386" /> + <origin xyz="0.17733236 -0.00000114 0.05669225" /> + <inertia ixx="0.02310947" ixy="0.00000076" ixz="0.00005282" + iyy="0.03978133" iyz="0.00000036" + izz="0.04842272" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> @@ -62,12 +62,12 @@ <!-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ WHEELS ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ --> <!-- ======= REAR LEFT ======= --> <xacro:wheel name="rear_left" parent="base_link" direction="1.0"> - <origin xyz="0 0.108 0" rpy="${PI/2.0} 0 ${PI}" /> + <origin xyz="0 0.1335 0.012" rpy="${PI/2.0} 0 ${PI}" /> </xacro:wheel> <!-- ======= REAR RIGHT ======= --> <xacro:wheel name="rear_right" parent="base_link" direction="-1.0"> - <origin xyz="0 -0.108 0" rpy="${PI/2.0} 0 0" /> + <origin xyz="0 -0.1335 0.012" rpy="${PI/2.0} 0 0" /> </xacro:wheel> <link name="steer_left"> @@ -81,7 +81,7 @@ </link> <joint name="base_link_2_steer_left_joint" type="revolute"> - <origin xyz="0.3666 0.108 0" rpy="0 0 0" /> + <origin xyz="0.360 0.1335 0.012" rpy="0 0 0" /> <axis xyz="0 0 1" /> <anchor xyz="0 0 0" /> <parent link="base_link" /> @@ -117,7 +117,7 @@ </link> <joint name="base_link_2_steer_right_joint" type="revolute"> - <origin xyz="0.3666 -0.108 0" rpy="0 0 0" /> + <origin xyz="0.360 -0.1335 0.012" rpy="0 0 0" /> <axis xyz="0 0 1" /> <anchor xyz="0 0 0" /> <parent link="base_link" /> diff --git a/urdf/include/sensors.xacro b/urdf/include/sensors.xacro index c9cc76600af0b33aeb23f393921edfcf0f30fdbe..08048ee5260e4f3ac40654bd1f13d06928cb02e4 100644 --- a/urdf/include/sensors.xacro +++ b/urdf/include/sensors.xacro @@ -13,27 +13,27 @@ <xacro:macro name="sensors" params="name sim_config_path"> <xacro:rplidar_laser2d name="front_lidar" prefix="model_car" parent="base_link" config_file="${sim_config_path}/rp_lidar_config.yaml"> - <origin xyz="0.439 0.0 0.05" rpy="0 ${PI} 0" /> + <origin xyz="0.439 0.0 0.039" rpy="0 ${PI} 0" /> </xacro:rplidar_laser2d> <xacro:hcsr04_sonar name="side_left" parent="base_link" sim_config="${sim_config_path}/side_left_sonar_config.yaml"> - <origin xyz="0.2585 0.1107 0.0" rpy="-${PI/2.0} ${PI/2.0} 0" /> + <origin xyz="0.2585 0.1362 0.012" rpy="-${PI/2.0} ${PI/2.0} 0" /> </xacro:hcsr04_sonar> <xacro:hcsr04_sonar name="side_right" parent="base_link" sim_config="${sim_config_path}/side_right_sonar_config.yaml"> - <origin xyz="0.2585 -0.1107 0.0" rpy="${PI/2.0} ${PI/2.0} 0" /> + <origin xyz="0.2585 -0.1362 0.012" rpy="${PI/2.0} ${PI/2.0} 0" /> </xacro:hcsr04_sonar> <xacro:hcsr04_sonar name="rear_center" parent="base_link" sim_config="${sim_config_path}/rear_center_sonar_config.yaml"> - <origin xyz="-0.0882 0.0 0.0" rpy="${PI} ${PI/2.0} 0" /> + <origin xyz="-0.095 0.0 0.012" rpy="${PI} ${PI/2.0} 0" /> </xacro:hcsr04_sonar> <xacro:hcsr04_sonar name="rear_left" parent="base_link" sim_config="${sim_config_path}/rear_left_sonar_config.yaml"> - <origin xyz="-0.07912 0.09898 0.0" rpy="${PI+PI/6.0} ${PI/2.0} 0" /> + <origin xyz="-0.07912 0.12448 0.012" rpy="${PI+PI/6.0} ${PI/2.0} 0" /> </xacro:hcsr04_sonar> <xacro:hcsr04_sonar name="rear_right" parent="base_link" sim_config="${sim_config_path}/rear_right_sonar_config.yaml"> - <origin xyz="-0.07912 -0.09898 0.0" rpy="${PI-PI/6.0} ${PI/2.0} 0" /> + <origin xyz="-0.07912 -0.12448 0.012" rpy="${PI-PI/6.0} ${PI/2.0} 0" /> </xacro:hcsr04_sonar> <xacro:mpu9250_imu name="imu" parent="base_link" sim_config="${sim_config_path}/mpu9250_imu_config.yaml"> @@ -41,11 +41,11 @@ </xacro:mpu9250_imu> <xacro:uvc_camera name="front_camera" parent="base_link" resolution="low_res" model="basler" sim_config="${sim_config_path}/basler_camera_sim_config.yaml"> - <origin xyz="0.273 0.0 0.180" rpy="0 0 0" /> + <origin xyz="0.305 0.0 0.166" rpy="0 0.14 0" /> </xacro:uvc_camera> <xacro:uvc_camera name="rear_camera" parent="base_link" resolution="low_res" model="delock" sim_config="${sim_config_path}/delock_camera_sim_config.yaml"> - <origin xyz="-0.0882 0.0 0.0325" rpy="${PI} 0 ${PI}" /> + <origin xyz="-0.102 -0.003 0.032" rpy="${PI} 0 ${PI}" /> </xacro:uvc_camera> </xacro:macro>