diff --git a/config/diffbot/base.yaml b/config/diffbot/base.yaml index 3715543..37782b0 100644 --- a/config/diffbot/base.yaml +++ b/config/diffbot/base.yaml @@ -1,6 +1,7 @@ base: - mass: 2.5 # Base mass in Kg + mass: 0.8 # Base mass in Kg x_size: 0.195 # Dimension in x axis - y_size: 0.198 # Dimension in y axis - z_size: 0.182 # Dimension in z axis + y_size: 0.08 # Dimension in y axis + z_size: 0.005 # Dimension in z axis mesh: 'chassis.stl' # Name of the mesh files. Leave it empty ('') to have a white base. + #mesh: '' \ No newline at end of file diff --git a/config/diffbot/front_wheel.yaml b/config/diffbot/front_wheel.yaml index dc39c86..94a8c8c 100644 --- a/config/diffbot/front_wheel.yaml +++ b/config/diffbot/front_wheel.yaml @@ -1,8 +1,9 @@ wheel: mass: 0.01 # Wheel mass in Kg - radius: 0.011 # Wheel radius in m - length: 0.006 # Wheel length in m, considering is as a cylinder + radius: 0.0331 # Wheel radius in m + length: 0.025 # Wheel length in m, considering is as a cylinder mesh: 'wheel.stl' # Name of the mesh files. Leave it empty ('') to have a red wheel - x_offset: 0.035 - y_offset: -0.056 - z_offset: 0.008 + #mesh: '' + x_offset: 0.079 + y_offset: 0.015 + z_offset: -0.017 diff --git a/config/diffbot/motor.yaml b/config/diffbot/motor.yaml new file mode 100644 index 0000000..7c86229 --- /dev/null +++ b/config/diffbot/motor.yaml @@ -0,0 +1,9 @@ +mass: 0.1 # Motor mass in Kg +x_size: 0.07 # Motor dimension in x axis +y_size: 0.0225 # Motor dimension in y axis +z_size: 0.0188 # Motor dimension in z axis +mesh: 'motor.stl' # Name of the mesh files. Leave it empty ('') to have a red wheel +#mesh: '' +x_offset: 0.096 +y_offset: -0.0135 +z_offset: -0.017 diff --git a/meshes/diffbot/motor.stl b/meshes/diffbot/motor.stl index 69aed8c..a1a003b 100644 Binary files a/meshes/diffbot/motor.stl and b/meshes/diffbot/motor.stl differ diff --git a/meshes/diffbot/wheel.stl b/meshes/diffbot/wheel.stl index 000fe33..8f7865c 100644 Binary files a/meshes/diffbot/wheel.stl and b/meshes/diffbot/wheel.stl differ diff --git a/urdf/diffbot.gazebo.xacro b/urdf/diffbot.gazebo.xacro new file mode 100644 index 0000000..02718d7 --- /dev/null +++ b/urdf/diffbot.gazebo.xacro @@ -0,0 +1,35 @@ + + + + + + + /diffbot + + gazebo_ros_control/DefaultRobotHWSim + + + + + + + + + + + 0.01 + + + + + + + + + + + \ No newline at end of file diff --git a/urdf/diffbot.urdf.xacro b/urdf/diffbot.urdf.xacro index 8313903..781feaf 100644 --- a/urdf/diffbot.urdf.xacro +++ b/urdf/diffbot.urdf.xacro @@ -1,12 +1,12 @@ - + - + - - + + @@ -14,17 +14,23 @@ + + + + + + - @@ -40,8 +46,23 @@ base_props="${base_props}" mesh="${front_wheel_props['wheel']['mesh']}"> + + + + + + + + - + + \ No newline at end of file diff --git a/urdf/include/common_macros.urdf.xacro b/urdf/include/common_macros.urdf.xacro index 4a5d605..189a0dd 100644 --- a/urdf/include/common_macros.urdf.xacro +++ b/urdf/include/common_macros.urdf.xacro @@ -17,7 +17,7 @@ - wheel_props [dictionary]: wheel properties; - base_props [dictionary]: base link properties; - mesh [string]: file name of the wheel mesh; - - DEFAULT Value -> Empty string + - DEFAULT Value -> Empty string --> @@ -32,9 +32,10 @@ - - + + + @@ -52,9 +53,11 @@ - + @@ -86,14 +89,12 @@ params="prefix reflect wheel_props locationright:=${0} "> - - - - - + @@ -135,14 +136,12 @@ - - - - - + @@ -170,7 +169,7 @@ - @@ -184,9 +183,9 @@ - + @@ -196,7 +195,7 @@ - + @@ -227,6 +226,75 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -286,11 +381,12 @@ - r [float]: cylinder radius; - l [float]: cylinder lenght (height); --> - + + iyy="${m*(3*r*r+l*l)/12}" iyz = "0" izz="${m*r*r/2}"/> + @@ -305,12 +401,13 @@ - y [float]: link dimension on the Y-axis; - z [float]: link dimension on the Z-axis; --> - + + @@ -366,7 +463,7 @@ - +