Skip to content

Commit

Permalink
GAZEBO RUNNING (#249)
Browse files Browse the repository at this point in the history
Nafis and Nico:
* loaded into gazebo
  • Loading branch information
NafisMolla authored Jul 9, 2023
1 parent a3a9896 commit 8016946
Show file tree
Hide file tree
Showing 4 changed files with 86 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@ chassis:
length: 1.17
width: 0.807
height: 0.2
mass: 20 #assuming 20kg

wheels:
# Should match values defined in uwrt_mars_rover_drivetrain_hw/config/drivetrain_controllers.yaml
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource


from launch_ros.actions import Node
import xacro


def generate_launch_description():

# Specify the name of the package and path to xacro file within the package
pkg_name = 'uwrt_mars_rover_drivetrain_description'
file_subpath = 'urdf/drivetrain.urdf.xacro'


# Use xacro to process the file
xacro_file = os.path.join(get_package_share_directory(pkg_name),file_subpath)
robot_description_raw = xacro.process_file(xacro_file).toxml()


# Configure the node
node_robot_state_publisher = Node(
package='robot_state_publisher',
executable='robot_state_publisher',
output='screen',
parameters=[{'robot_description': robot_description_raw,
'use_sim_time': True}] # add other parameters here if required
)



gazebo = IncludeLaunchDescription(
PythonLaunchDescriptionSource([os.path.join(
get_package_share_directory('gazebo_ros'), 'launch'), '/gazebo.launch.py']),
)


spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py',
arguments=['-topic', 'robot_description',
'-entity', 'my_bot'],
output='screen')






# Run the node
return LaunchDescription([
gazebo,
node_robot_state_publisher,
spawn_entity
])
Original file line number Diff line number Diff line change
Expand Up @@ -13,11 +13,18 @@
<xacro:property name="chassis_length" value="${chassis_parameters['length']}" scope="parent"/>
<xacro:property name="chassis_width" value="${chassis_parameters['width']}" scope="parent"/>
<xacro:property name="chassis_height" value="${chassis_parameters['height']}" scope="parent"/>
<xacro:property name="chassis_mass" value="${chassis_parameters['mass']}" scope="parent"/>



<!-- wheel parameters -->
<xacro:property name="wheel_diameter" value="${wheel_parameters['diameter']}" scope="parent"/>
<xacro:property name="wheel_width" value="${wheel_parameters['width']}" scope="parent"/>
<xacro:property name="wheel_mass" value="${wheel_parameters['mass']}" scope="parent"/>
<xacro:property name="wheel_radius" value="${(wheel_parameters['diameter'])/2}" scope="parent"/>




<!-- control parameters -->
<xacro:property name="mechanical_reduction" value="${control_parameters['mechanical_reduction']}" scope="parent"/>
Expand All @@ -34,6 +41,26 @@
</inertial>
</xacro:macro>

<xacro:macro name="chassis_inertia" params="chassis_width:=^ chassis_height:=^ chassis_length:=^ chassis_mass:=^">
<inertial>
<mass value="${chassis_mass}" />
<inertia
ixx="${(1/12)*(((chassis_height)*(chassis_height))+((chassis_width)*(chassis_width)))}" ixy="0.0" ixz="0.0"
iyy="${(1/12)*(((chassis_height)*(chassis_height))+((chassis_length)*(chassis_length)))}" iyz="0.0"
izz="${(1/12)*(((chassis_width)*(chassis_width))+((chassis_length)*(chassis_length)))}"/>
</inertial>
</xacro:macro>

<xacro:macro name="wheel_intertia" params="wheel_radius:=^ wheel_width:=^ wheel_mass:=^">
<inertial>
<mass value="${wheel_mass}" />
<inertia
ixx="${(1/12)*(3*((wheel_radius)*(wheel_radius))+((wheel_width)*(wheel_width)))}" ixy="0.0" ixz="0.0"
iyy="${(1/12)*(3*((wheel_radius)*(wheel_radius))+((wheel_width)*(wheel_width)))}" iyz="0.0"
izz="${(1/2)*((wheel_radius)*(wheel_radius))}"/>
</inertial>
</xacro:macro>

<xacro:macro name="identical_visual_collision" params="**identical_blocks">
<visual>
<xacro:insert_block name="identical_blocks"/>
Expand All @@ -60,7 +87,7 @@
</geometry>
</idential_blocks>
</xacro:identical_visual_collision>
<xacro:default_inertial mass="${wheel_mass}"/>
<xacro:wheel_intertia />
</link>
</xacro:macro>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@
</geometry>
</identical_blocks>
</xacro:identical_visual_collision>
<xacro:default_inertial/>
<xacro:chassis_inertia/>
</link>

<!-- wheels -->
Expand Down

0 comments on commit 8016946

Please sign in to comment.