Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Feature/eduard #1

Merged
merged 7 commits into from
Oct 7, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
18 changes: 18 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
cmake_minimum_required(VERSION 3.5)
project(edu_simulation)

find_package(ament_cmake REQUIRED)

# install(DIRECTORY world
# DESTINATION share/${PROJECT_NAME}
# )

ament_package()

install(DIRECTORY model
DESTINATION share/${PROJECT_NAME}/
)

install(DIRECTORY launch
DESTINATION share/${PROJECT_NAME}/
)
47 changes: 47 additions & 0 deletions launch/eduard.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
import os

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import ExecuteProcess, DeclareLaunchArgument
from launch_ros.actions import Node
from launch.substitutions import LaunchConfiguration
from launch.actions import SetEnvironmentVariable
from launch.substitutions import EnvironmentVariable

def generate_launch_description():
robot_name = 'edu_simulation'
world_file_name = 'empty.world'

# full path to sdf and world file

# world = os.path.join(get_package_share_directory(robot_name), 'world', world_file_name)
model_path = os.path.join(get_package_share_directory(robot_name), 'model')
world = "worlds/empty.world"
robot_sdf = os.path.join(model_path, 'eduard/eduard.sdf')

# read sdf contents because to spawn an entity in
# gazebo we need to provide entire sdf as string on command line

# xml = open(robot_sdf, 'r').read()

# double quotes need to be with escape sequence
# xml = xml.replace('"', '\\"')

# this is argument format for spwan_entity service
# spwan_args = '{name: \"eduard\", xml: \"' + xml + '\" }'

# create and return launch description object
return LaunchDescription([
#SetEnvironmentVariable(name='GAZEBO_MODEL_PATH', value=[EnvironmentVariable('GAZEBO_MODEL_PATH'), ':' + model_path]),
SetEnvironmentVariable(name='GAZEBO_MODEL_PATH', value=model_path),
# start gazebo, notice we are using libgazebo_ros_factory.so instead of libgazebo_ros_init.so
# That is because only libgazebo_ros_factory.so contains the service call to /spawn_entity
ExecuteProcess(
cmd=['gazebo', '--verbose', world ],#'-s', 'libgazebo_ros_factory.so'],
output='screen'),

# tell gazebo to spwan your robot in the world by calling service
# ExecuteProcess(
# cmd=['ros2', 'service', 'call', '/spawn_entity', 'gazebo_msgs/SpawnEntity', spwan_args],
# output='screen'),
])
325 changes: 325 additions & 0 deletions model/eduard_mecanum/eduard.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,325 @@
<?xml version='1.0'?>
<sdf version='1.5'>
<model name="eduard-mecanum">
<static>false</static>
<pose>0 0 0 0 0 0</pose>
<!-- chassis -->
<link name="chassis">
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>5.0</mass>
<inertia>
<ixx>9.885e-1</ixx>
<iyy>2.099e0</iyy>
<izz>1.317e0</izz>
<ixy>-7.521e-4</ixy>
<ixz>1.126e-3</ixz>
<iyz>6.915e-3</iyz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<mesh>
<uri>model://eduard_offroad/mesh/eduard-chassis.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="collision">
<pose>0 0 0.06 0 0 0</pose>
<geometry>
<box>
<size>0.38 0.22 0.12</size>
</box>
</geometry>
</collision>
</link>

<!-- wheel front left -->
<link name="wheel_front_left">
<pose>0.125 0.18 0.02 1.570796327 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.3</mass>
<inertia>
<ixx>3.0e-5</ixx>
<iyy>3.0e-5</iyy>
<izz>5.0e-5</izz>
<ixy>0</ixy>
<ixz>0</ixz>
<iyz>0</iyz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<mesh>
<uri>model://eduard_mecanum/mesh/mecanum-wheel-left-eduard.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="collision">
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.05</radius>
<length>0.055</length>
</cylinder>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<friction>
<torsional>
<coefficient>0.9</coefficient>
<surface_radius>0.0865</surface_radius>
<use_patch_radius>false</use_patch_radius>
<ode>
<slip>0.02</slip>
</ode>
</torsional>
<!-- <ode>
<mu>0.45</mu>
<mu2>0.45</mu2>
<fdir1>1 1 1</fdir1>
<slip1>0.02</slip1>
<slip2>0.02</slip2>
</ode> -->
</friction>
<contact>
<ode>
<min_depth>0.005</min_depth>
</ode>
</contact>
</surface>
</collision>
</link>

<!-- wheel front right -->
<link name="wheel_front_right">
<pose>0.125 -0.18 0.02 -1.570796327 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.3</mass>
<inertia>
<ixx>3.0e-5</ixx>
<iyy>3.0e-5</iyy>
<izz>5.0e-5</izz>
<ixy>0</ixy>
<ixz>0</ixz>
<iyz>0</iyz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<mesh>
<uri>model://eduard_mecanum/mesh/mecanum-wheel-right-eduard.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="collision">
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.05</radius>
<length>0.055</length>
</cylinder>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<friction>
<torsional>
<coefficient>0.9</coefficient>
<surface_radius>0.0865</surface_radius>
<use_patch_radius>false</use_patch_radius>
<ode>
<slip>0.02</slip>
</ode>
</torsional>
<!-- <ode>
<mu>0.45</mu>
<mu2>0.45</mu2>
<fdir1>1 1 1</fdir1>
<slip1>0.02</slip1>
<slip2>0.02</slip2>
</ode> -->
</friction>
<contact>
<ode>
<min_depth>0.005</min_depth>
</ode>
</contact>
</surface>
</collision>
</link>

<!-- wheel rear left -->
<link name="wheel_rear_left">
<pose>-0.125 0.18 0.02 1.570796327 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.3</mass>
<inertia>
<ixx>3.0e-5</ixx>
<iyy>3.0e-5</iyy>
<izz>5.0e-5</izz>
<ixy>0</ixy>
<ixz>0</ixz>
<iyz>0</iyz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<mesh>
<uri>model://eduard_mecanum/mesh/mecanum-wheel-right-eduard.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="collision">
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.05</radius>
<length>0.055</length>
</cylinder>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<friction>
<torsional>
<coefficient>0.9</coefficient>
<surface_radius>0.0865</surface_radius>
<use_patch_radius>false</use_patch_radius>
<ode>
<slip>0.02</slip>
</ode>
</torsional>
<!-- <ode>
<mu>0.45</mu>
<mu2>0.45</mu2>
<fdir1>1 1 1</fdir1>
<slip1>0.02</slip1>
<slip2>0.02</slip2>
</ode> -->
</friction>
<contact>
<ode>
<min_depth>0.005</min_depth>
</ode>
</contact>
</surface>
</collision>
</link>

<!-- wheel rear right -->
<link name="wheel_rear_right">
<pose>-0.125 -0.18 0.02 -1.570796327 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.3</mass>
<inertia>
<ixx>3.0e-5</ixx>
<iyy>3.0e-5</iyy>
<izz>5.0e-5</izz>
<ixy>0</ixy>
<ixz>0</ixz>
<iyz>0</iyz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<mesh>
<uri>model://eduard_mecanum/mesh/mecanum-wheel-left-eduard.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="collision">
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.05</radius>
<length>0.055</length>
</cylinder>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<friction>
<torsional>
<coefficient>0.9</coefficient>
<surface_radius>0.0865</surface_radius>
<use_patch_radius>false</use_patch_radius>
<ode>
<slip>0.02</slip>
</ode>
</torsional>
<!-- <ode>
<mu>0.45</mu>
<mu2>0.45</mu2>
<fdir1>1 1 1</fdir1>
<slip1>0.02</slip1>
<slip2>0.02</slip2>
</ode> -->
</friction>
<contact>
<ode>
<min_depth>0.005</min_depth>
</ode>
</contact>
</surface>
</collision>
</link>

<!-- Joints. -->
<joint type="revolute" name="axis_front_left">
<pose>0 0 0 0 0 0</pose>
<child>wheel_front_left</child>
<parent>chassis</parent>
<axis>
<xyz>0 0 1</xyz>
</axis>
</joint>
<joint type="revolute" name="axis_front_right">
<pose>0 0 0 0 0 0</pose>
<child>wheel_front_right</child>
<parent>chassis</parent>
<axis>
<xyz>0 0 1</xyz>
</axis>
</joint>
<joint type="revolute" name="axis_rear_left">
<pose>0 0 0 0 0 0</pose>
<child>wheel_rear_left</child>
<parent>chassis</parent>
<axis>
<xyz>0 0 1</xyz>
</axis>
</joint>
<joint type="revolute" name="axis_rear_right">
<pose>0 0 0 0 0 0</pose>
<child>wheel_rear_right</child>
<parent>chassis</parent>
<axis>
<xyz>0 0 1</xyz>
</axis>
</joint>

<!-- plugins to control robot behavior -->
<plugin name="gazebo_ros_planar_move" filename="libgazebo_ros_planar_move.so">
<ros>
<!-- Add a namespace -->
<!-- <namespace>/demo</namespace> -->
<!-- Remap the default topic -->
<!-- <remapping>cmd_vel:=custom_cmd_vel</remapping> -->
<!-- <remapping>odom:=custom_odom</remapping> -->
</ros>
<update_rate>100</update_rate>
<publish_rate>10</publish_rate>
<!-- output -->
<publish_odom>true</publish_odom>
<publish_odom_tf>true</publish_odom_tf>
<odometry_frame>odom</odometry_frame>
<robot_base_frame>chassis</robot_base_frame>
<covariance_x>0.0001</covariance_x>
<covariance_y>0.0001</covariance_y>
<covariance_yaw>0.01</covariance_yaw>
</plugin>
</model>
</sdf>
Loading