initial commit

This commit is contained in:
Bastian Hofmann
2022-02-25 13:38:01 +01:00
commit c7e1e82b42
29 changed files with 1581 additions and 0 deletions

Binary file not shown.

View File

@@ -0,0 +1,29 @@
cmake_minimum_required(VERSION 3.8)
project(gaz_simulation)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
# find dependencies
find_package(ament_cmake REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)
install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})
install(DIRECTORY world DESTINATION share/${PROJECT_NAME})
install(DIRECTORY urdf DESTINATION share/${PROJECT_NAME})
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# uncomment the line when a copyright and license is not present in all source files
#set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# uncomment the line when this package is not in a git repo
#set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
ament_package()

16
src/gaz_simulation/calc.lua Executable file
View File

@@ -0,0 +1,16 @@
#!/usr/bin/lua
io.write("Radius: ")
local radius=io.read("*line")
io.write("Height: ")
local height=io.read("*line")
io.write("Weight: ")
local weight=io.read("*line")
local ix_and_y=(1/12)*weight*(3*radius*radius+height*height)
local iz=(1/2)*weight*radius*radius
print([[<inertial>
<mass value="]]..tostring(weight)..[["/>
<inertia ixx="]]..tostring(ix_and_y)..[[" ixy="0.0" ixz="0.0" iyy="]]..tostring(ix_and_y)..[[" iyz="0.0" izz="]]..tostring(iz)..[["/>
</inertial>]])

View File

@@ -0,0 +1,72 @@
import os
from launch import LaunchDescription
from launch_ros.actions import Node
from launch.actions import ExecuteProcess, IncludeLaunchDescription
from launch_ros.substitutions import FindPackageShare
from launch.substitutions import Command
from launch.launch_description_sources import PythonLaunchDescriptionSource
def generate_launch_description():
robot_name = "iisy"
package_name = "gaz_simulation"
pkg_gazebo_ros = FindPackageShare(package='gazebo_ros').find('gazebo_ros')
path = FindPackageShare(package=package_name).find(package_name)
world_path = os.path.join(path, "world/test2.xml")
urdf_path = os.path.join(path, "urdf/iisy.urdf")
return LaunchDescription([
IncludeLaunchDescription(
PythonLaunchDescriptionSource(os.path.join(pkg_gazebo_ros, 'launch', 'gzserver.launch.py')),
launch_arguments={'world': world_path}.items()
),
# Start Gazebo client
IncludeLaunchDescription(
PythonLaunchDescriptionSource(os.path.join(pkg_gazebo_ros, 'launch', 'gzclient.launch.py'))
),
Node(
package='tf2_ros',
namespace='gaz_simulation',
executable='static_transform_publisher',
name='lidar_1_broadcaster',
arguments=["1", "-1.9", "1", "1.5707963267949", "0", "0", "map", "lidar_1_link"]
),
Node(
package='tf2_ros',
namespace='gaz_simulation',
executable='static_transform_publisher',
name='lidar_2_broadcaster',
arguments=["-1.9", "1", "1", "0", "0", "0", "map", "lidar_2_link"]
),
Node(
package='gazebo_ros',
executable='spawn_entity.py',
arguments=['-entity', robot_name,
'-topic', 'robot_description',
'-x', '-1',
'-y', '-1',
'-z', '1',
'-Y', '0'], # Yaw
output='screen'
),
# Subscribe to the joint states of the robot, and publish the 3D pose of each link.
Node(
package='robot_state_publisher',
executable='robot_state_publisher',
parameters=[{'robot_description': Command(['xacro ', urdf_path])}]
),
# Publish the joint states of the robot
Node(
package='joint_state_publisher',
executable='joint_state_publisher',
name='joint_state_publisher'
)
# ,
# Node(
# namespace='turtlesim1',
# executable='gazebo',
# name='gazebo',
# arguments=["test.xml"]
# )
])

View File

@@ -0,0 +1,28 @@
<package format="3">
<name>gaz_simulation</name>
<version>0.244.1</version>
<description>Launch file for simulation of pick and place</description>
<license>Apache 2.0</license>
<maintainer email="bastian.hofmann@xitaso.com">Bastian Hofmann</maintainer>
<buildtool_depend>ament_cmake</buildtool_depend>
<exec_depend>gazebo-11</exec_depend>
<exec_depend>image_transport_plugins</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>ros_ign_bridge</exec_depend>
<exec_depend>ros_ign_gazebo</exec_depend>
<exec_depend>ros_ign_image</exec_depend>
<!-- See https://github.com/osrf/ros_ign/issues/40 -->
<!--exec_depend>ros_ign_point_cloud</exec_depend-->
<exec_depend>rqt_image_view</exec_depend>
<exec_depend>rqt_plot</exec_depend>
<exec_depend>rqt_topic</exec_depend>
<exec_depend>rviz2</exec_depend>
<exec_depend>xacro</exec_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>

View File

@@ -0,0 +1,195 @@
<?xml version="1.0"?>
<robot name="iisy" xmlns:xacro="http://ros.org/wiki/xacro">
<static>true</static>
<link name='base'>
<pose>0.025 0 0.05 0 0 0</pose>
<collision name='collision'>
<geometry>
<box size=".15 .1 .1"/>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<box size=".15 .1 .1"/>
</geometry>
</visual>
<inertial>
<mass value="6"/>
<inertia ixx="0.0032666666666667" ixy="0.0" ixz="0.0" iyy="0.0032666666666667" iyz="0.0" izz="0.0025"/>
</inertial>
</link>
<link name="base_rot">
<pose>0 0 0.155 0 0 0</pose>
<collision name="collision">
<geometry>
<cylinder radius=".05" length=".11"/>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder radius=".05" length=".11"/>
</geometry>
</visual>
<inertial>
<mass value="2"/>
<inertia ixx="0.0032666666666667" ixy="0.0" ixz="0.0" iyy="0.0032666666666667" iyz="0.0" izz="0.0025"/>
</inertial>
</link>
<link name="link1">
<pose>0 0 0.36 0 0 0</pose>
<collision name="collision">
<geometry>
<cylinder radius=".05" length=".30"/>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder radius=".05" length=".30"/>
</geometry>
</visual>
<inertial>
<mass value="4"/>
<inertia ixx="0.0325" ixy="0.0" ixz="0.0" iyy="0.0325" iyz="0.0" izz="0.005"/>
</inertial>
</link>
<link name="link2_rot">
<pose>0 0 0.585 0 0 0</pose>
<collision name="collision">
<geometry>
<cylinder radius=".05" length=".15"/>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder radius=".05" length=".15"/>
</geometry>
</visual>
<inertial>
<mass value="2"/>
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.0025"/>
</inertial>
</link>
<link name="link2">
<pose>0 0 0.735 0 0 0</pose>
<collision name="collision">
<geometry>
<cylinder radius=".05" length=".15"/>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder radius=".05" length=".15"/>
</geometry>
</visual>
<inertial>
<mass value="2"/>
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.0025"/>
</inertial>
</link>
<link name="link3_rot">
<pose>0 0 0.86 0 0 0</pose>
<collision name="collision">
<geometry>
<cylinder radius=".05" length=".10"/>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder radius=".05" length=".10"/>
</geometry>
</visual>
<inertial>
<mass value="2"/>
<inertia ixx="0.0029166666666667" ixy="0.0" ixz="0.0" iyy="0.0029166666666667" iyz="0.0" izz="0.0025"/>
</inertial>
</link>
<link name="link3">
<pose>0 0 0.94025 0 0 0</pose>
<collision name="collision">
<geometry>
<cylinder radius=".05" length=".0605"/>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder radius=".05" length=".0605"/>
</geometry>
</visual>
<inertial>
<mass value="0.8"/>
<inertia ixx="0.00074401666666667" ixy="0.0" ixz="0.0" iyy="0.00074401666666667" iyz="0.0" izz="0.001"/>
</inertial>
</link>
<joint type="continuous" name="base_rot_joint">
<pose>0 0 -0.055 0 0 0</pose>
<parent link="base"/>
<child link="base_rot"/>
<axis>
<xyz>0 0 1</xyz>
</axis>
<limit effort="30" velocity="1.7453292519943"/>
</joint>
<joint type="revolute" name="link1_joint">
<pose>0 0 -0.15 0 0 0</pose>
<parent link="base_rot"/>
<child link="link1"/>
<axis>
<xyz>1 0 0</xyz>
</axis>
<limit effort="30" velocity="1.7453292519943" lower="-1.221730476396" upper="1.221730476396"/>
</joint>
<joint type="revolute" name="link2_rot_joint">
<pose>0 0 -0.075 0 0 0</pose>
<parent link="link1"/>
<child link="link2_rot"/>
<axis>
<xyz>1 0 0</xyz>
</axis>
<limit effort="30" velocity="1.7453292519943" lower="-1.3089969389957" upper="1.3089969389957"/>
</joint>
<joint type="continuous" name="link2_joint">
<pose>0 0 -0.075 0 0 0</pose>
<parent link="link2_rot"/>
<child link="link2"/>
<axis>
<xyz>0 0 1</xyz>
</axis>
<limit effort="30" velocity="1.7453292519943"/>
</joint>
<joint type="revolute" name="link3_rot_joint">
<pose>0 0 -0.05 0 0 0</pose>
<parent link="link2"/>
<child link="link3_rot"/>
<axis>
<xyz>1 0 0</xyz>
</axis>
<limit effort="30" velocity="1.7453292519943" lower="-0.95993108859688" upper="0.95993108859688"/>
</joint>
<joint type="continuous" name="link3_joint">
<pose>0 0 -0.03025 0 0 0</pose>
<parent link="link3_rot"/>
<child link="link3"/>
<axis>
<xyz>0 0 1</xyz>
</axis>
<limit effort="30" velocity="1.7453292519943"/>
</joint>
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/simple_model</robotNamespace>
</plugin>
</gazebo>
</robot>

View File

@@ -0,0 +1,320 @@
<sdf version='1.7'>
<world name='default'>
<light name='sun' type='directional'>
<cast_shadows>1</cast_shadows>
<pose>0 0 10 0 -0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
<spot>
<inner_angle>0</inner_angle>
<outer_angle>0</outer_angle>
<falloff>0</falloff>
</spot>
</light>
<model name='walls'>
<static>1</static>
<link name='walls_1'>
<self_collide>0</self_collide>
<pose>3 8 1.2</pose>
<collision name='collision'>
<geometry>
<box>
<size>10.1 .1 2.4</size>
</box>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<box>
<size>10.1 .1 2.4</size>
</box>
</geometry>
</visual>
</link>
<link name='walls_2'>
<self_collide>0</self_collide>
<pose>3 -2 1.2</pose>
<collision name='collision'>
<geometry>
<box>
<size>10.1 .1 2.4</size>
</box>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<box>
<size>10.1 .1 2.4</size>
</box>
</geometry>
</visual>
</link>
<link name='walls_3'>
<self_collide>0</self_collide>
<pose>8 3 1.2</pose>
<collision name='collision'>
<geometry>
<box>
<size>.1 9.9 2.4</size>
</box>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<box>
<size>.1 9.9 2.4</size>
</box>
</geometry>
</visual>
</link>
<link name='walls_4'>
<self_collide>0</self_collide>
<pose>-2 3 1.2</pose>
<collision name='collision'>
<geometry>
<box>
<size>.1 9.9 2.4</size>
</box>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<box>
<size>.1 9.9 2.4</size>
</box>
</geometry>
</visual>
</link>
</model>
<model name="lidar_1">
<static>1</static>
<link name="lidar_1_link">
<pose>1 -2 1 0 0 1.5707963267949</pose>
<!--<collision name='collision'>
<geometry>
<box>
<size>.1 .1 .1</size>
</box>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<box>
<size>.1 .1 .1</size>
</box>
</geometry>
</visual>-->
<sensor name="laser" type="gpu_ray">
<pose>0.1 0 0 0 0 0</pose>
<ray>
<scan>
<horizontal>
<samples>270</samples>
<resolution>1</resolution>
<min_angle>-2.3561944901923</min_angle>
<max_angle>2.3561944901923</max_angle>
</horizontal>
</scan>
<range>
<min>0.05</min>
<max>10</max>
<resolution>0.05</resolution>
</range>
</ray>
<always_on>1</always_on>
<update_rate>10</update_rate>
<visualize>true</visualize>
<plugin name='laser' filename='libgazebo_ros_ray_sensor.so'>
<ros>
<namespace>/lidar_1</namespace>
<argument>--ros-args --remap ~/out:=scan</argument>
</ros>
<output_type>sensor_msgs/PointCloud2</output_type>
</plugin>
</sensor>
</link>
</model>
<model name="lidar_2">
<static>1</static>
<link name="lidar_2_link">
<pose>-2 1 1 0 0 </pose>
<collision name='collision'>
<geometry>
<box>
<size>.1 .1 .1</size>
</box>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<box>
<size>.1 .1 .1</size>
</box>
</geometry>
</visual>
<sensor name="laser" type="gpu_ray">
<pose>0.1 0 0 0 0 0</pose>
<ray>
<scan>
<horizontal>
<samples>270</samples>
<resolution>1</resolution>
<min_angle>-2.3561944901923</min_angle>
<max_angle>2.3561944901923</max_angle>
</horizontal>
</scan>
<range>
<min>0.05</min>
<max>10</max>
<resolution>0.05</resolution>
</range>
</ray>
<always_on>1</always_on>
<update_rate>10</update_rate>
<visualize>true</visualize>
<plugin name='laser' filename='libgazebo_ros_ray_sensor.so'>
<ros>
<namespace>/lidar_2</namespace>
<frameName>/lidar_2_link</frameName>
<argument>--ros-args --remap ~/out:=scan</argument>
</ros>
<output_type>sensor_msgs/PointCloud2</output_type>
</plugin>
</sensor>
</link>
</model>
<model name='ground_plane'>
<static>1</static>
<link name='link'>
<collision name='collision'>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<surface>
<contact>
<collide_bitmask>65535</collide_bitmask>
<ode/>
</contact>
<friction>
<ode>
<mu>100</mu>
<mu2>50</mu2>
</ode>
<torsional>
<ode/>
</torsional>
</friction>
<bounce/>
</surface>
<max_contacts>10</max_contacts>
</collision>
<visual name='visual'>
<cast_shadows>0</cast_shadows>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
</model>
<actor name="actor1">
<pose>0 1 1.25 0 0 0</pose>
<skin>
<filename>walk.dae</filename>
<scale>1.0</scale>
</skin>
<animation name="walking">
<filename>walk.dae</filename>
<scale>1.000000</scale>
<interpolate_x>true</interpolate_x>
</animation>
<plugin name="actor1_plugin" filename="/home/bastian/dev_ws/build/gazebo_ros_actor/libRosActorPlugin.so">
<target>2 2 1</target>
<target_weight>1.15</target_weight>
<obstacle_weight>1.8</obstacle_weight>
<animation_factor>5.1</animation_factor>
<ignore_obstacles>
<model>ground_plane</model>
</ignore_obstacles>
</plugin>
</actor>
<gravity>0 0 -9.8</gravity>
<magnetic_field>6e-06 2.3e-05 -4.2e-05</magnetic_field>
<atmosphere type='adiabatic'/>
<physics type='ode'>
<max_step_size>0.001</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>1000</real_time_update_rate>
</physics>
<scene>
<ambient>0.4 0.4 0.4 1</ambient>
<background>0.7 0.7 0.7 1</background>
<shadows>1</shadows>
</scene>
<wind/>
<spherical_coordinates>
<surface_model>EARTH_WGS84</surface_model>
<latitude_deg>0</latitude_deg>
<longitude_deg>0</longitude_deg>
<elevation>0</elevation>
<heading_deg>0</heading_deg>
</spherical_coordinates>
<state world_name='default'>
<sim_time>21 655000000</sim_time>
<real_time>21 863005214</real_time>
<wall_time>1644846646 70909467</wall_time>
<iterations>21655</iterations>
<model name='ground_plane'>
<pose>0 0 0 0 -0 0</pose>
<scale>1 1 1</scale>
<link name='link'>
<pose>0 0 0 0 -0 0</pose>
<velocity>0 0 0 0 -0 0</velocity>
<acceleration>0 0 0 0 -0 0</acceleration>
<wrench>0 0 0 0 -0 0</wrench>
</link>
</model>
<light name='sun'>
<pose>0 0 10 0 -0 0</pose>
</light>
</state>
<gui fullscreen='0'>
<camera name='user_camera'>
<pose>5 -5 2 0 0.275643 2.35619</pose>
<view_controller>orbit</view_controller>
<projection_type>perspective</projection_type>
</camera>
</gui>
<plugin name="gazebo_ros_state" filename="libgazebo_ros_state.so">
<ros>
<namespace>/demo</namespace>
<argument>model_states:=model_states_demo</argument>
</ros>
<update_rate>1.0</update_rate>
</plugin>
</world>
</sdf>