## For instruction on writing tutorials ## http://www.ros.org/wiki/WritingTutorials #################################### ##FILL ME IN #################################### ## for a custom note with links: ## note = ## for the canned note of "This tutorial assumes that you have completed the previous tutorials:" just add the links ## note.0= ## descriptive title for the tutorial ## title = Create your own object ## multi-line description to be displayed in search ## description = This tutorial shows how to model your own object and add it to gazebo ## the next tutorial description (optional) ## next = ## links to next tutorial (optional) ## next.0.link= ## next.1.link= ## what level user is this tutorial for ## level= (BeginnerCategory, IntermediateCategory, AdvancedCategory) ## keywords = #################################### <<IncludeCSTemplate(TutorialCSHeaderTemplate)>> <<TableOfContents(4)>> == Modelling == In general: avoid zero thickness for planes, this will cause rendering problems === Model the object using urdf === see [[urdf/Tutorials/Building a Visual Robot Model with URDF from Scratch]] === Model the object using Google Sketchup === 1. Model your object in [[http://sketchup.google.com|Google Sketchup]] using SI-Units, e.g. meter. 2. Export to dae format in Sketchup 3. Put the resulting dae file into the package ''cob_gazebo_objects'' into the folder ''Media/models/''. The folder with the textures (same name as dae-filename) should also be added to this folder. 4. Create a new object file in the package ''cob_gazebo_objects'' in the folder ''objects'' named "MY_OBJECT.urdf". You can use the following template and replace the dae filenames in line 12 and line 18. Note the scaling in order to reduce the model to metric values (SketchUp is using inch when exporting). {{{#!xml <?xml version="1.0" ?> <robot name="my_object"> <link name="base_link"> <inertial> <mass value="5.0" /> <origin xyz="0 0 0.0" /> <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" /> </inertial> <visual> <origin xyz="0 0 0.0" rpy="0 0 0" /> <geometry> <mesh filename="package://cob_gazebo_objects/Media/models/my_object.dae"/> </geometry> </visual> <collision> <origin xyz="0 0 0.072" rpy="0 0 0" /> <geometry> <mesh filename="package://cob_gazebo_objects/Media/models/my_object.dae"> </geometry> </collision> </link> </robot> }}} 5. Define a object position You have to define a position for this object in the package cob_gazebo_objects, for each world there a configuration file in: cob_gazebo_objects/config/WORLD_NAME/object_locations.yaml. The format for this file is: {{{ MY_OBJECT: model: MY_OBJECT model_type: urdf position: [X,Y,Z] orientation: [0, 0, 0] }}} 6. Start Gazebo and spawn the object You have to spawn the world (for example you can use ipa-apartment): {{{ roslaunch cob_gazebo_worlds WORLD_NAME.launch }}} It is necessary load the position of the object as a parameter: {{{ roslaunch cob_gazebo_objects upload_param.launch }}} And spawn your object using the node spawn object: {{{ rosrun cob_bringup_sim spawn_object.py MY_OBJECT }}} ## AUTOGENERATED DO NOT DELETE ## TutorialCategory ## FILL IN THE STACK TUTORIAL CATEGORY HERE