Gazebo | Ignition | Community
Ask Your Question
1

The best way of having my model in gazebo

asked 2017-05-27 03:42:39 -0600

RH gravatar image

updated 2017-06-03 04:12:23 -0600

I have a SOLID-WORKS model of a humanoid robot and I wonder which of the following is the best to import and have my model in gazebo:
1. Saving different parts of the robot in STL format, adding them from "model editor" environment and then defining relations and joints in gazebo model editor.
2. Downloading SW2URDF add-in for SOLID-WORKS use it for defining joints and tree structure, saving the URDF file and open in in gazebo. (which I haven't found a proper tutorial for so I actually don't know how should I do :( ).
3. Any better way you suggest :)

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
2

answered 2017-06-01 09:54:12 -0600

GuillaumeB gravatar image

updated 2017-06-02 08:05:52 -0600

Hello,

  1. For this method I recommend you to define frame coordinate in SW. Export meshes respecting theses coordinates frames. Then you can define joints by measuring the difference between two coordinate frame (measure tool in SW). I recommend you to write an urdf file and not to use the gazebo model editor because it will be clearer for you to setup your model. This method will work if you have simple meshes (not too much triangles).

  2. I do not recommend you to use the plug-in, mainly because it's no longer maintained. At the end you will simply edit the generated urdf by hand...

  3. A third method (my favorite by now) is to create a simplified model of your robot (It will simplify collisions and speed up the simulation). You still have to create coordinates frames on every part in your SW (for joint setup). You will have to approximate every shapes by basic shapes (box, cylinder) for visual and collisions (inertial matrix will be easier to calculate (https://en.wikipedia.org/wiki/List_of...). For example a wheel could be:

    <link name="wheel">
    <inertial>
        <mass value="${WheelWeight}" />
        <origin xyz="0 0 0" />
        <inertia  ixx="${INERTIA_XX}" ixy="0.0"  ixz="0.0"  iyy="${INERTIA_YY"  iyz="0.0"  izz="INERTIA_ZZ" />
    </inertial>
    <visual>
        <origin xyz="0 0 0" rpy="$0 0 0" />
        <geometry>
            <cylinder radius="${WheelRadius}" length="${WheelWidth}" />
        </geometry>
        <material name="Green"/>
    </visual>
    <collision>
        <origin xyz="0 0 0" rpy="$0 0 0" />
        <geometry>
            <cylinder radius="${WheelRadius}" length="${WheelWidth}" />
        </geometry>
    </collision>
    </link>
    

    This approach take time but this is the best way to have a stable simulation (in my opinion).

Please give me feedback if you tried any of the approach, I am really interested in bringing SW model to gazebo.

edit flag offensive delete link more

Comments

hello , thanks a lot for your complete answer I've been searching for bringing SW model to gazebo for a while and it's nice to see that someone who is interested in it has answered my question. I'll try the third way and ask you my further questions if I may . thanks a lot again

RH gravatar imageRH ( 2017-06-01 15:41:21 -0600 )edit

And It also would be really helpful if you could recommend a source with complete tutorial over that method :)) Cause right now my biggest question is how I should open the model in gazebo afterward !!!!

RH gravatar imageRH ( 2017-06-01 15:45:59 -0600 )edit

actually the third method do not come from any tutorial, I decided to do that to make my own simulation faster. To bring a urdf into gazebo just use spawn_model -> http://wiki.ros.org/simulator_gazebo/Tutorials/SpawningObjectInSimulation

GuillaumeB gravatar imageGuillaumeB ( 2017-06-02 07:40:23 -0600 )edit

Unfortunately [ http://wiki.ros.org/simulator_gazebo/Tutorials/SpawningObjectInSimulation ] didn't exist ! I found a tutorial over spawn_model at [ http://gazebosim.org/tutorials?tut=ros_roslaunch ] ,but I have another question : where should I place my URDF file ? Doesn't it need a spacial location in order to [ rosrun gazebo_ros spawn_model -file `rospack find MYROBOT_description`/urdf/MYROBOT.urdf -urdf -x 0 -y 0 -z 1 -model MYROBOT ] works properly ?! sorry for asking too much Questions !

RH gravatar imageRH ( 2017-06-03 04:20:16 -0600 )edit

Actually I know I should add it in to my catkin workspace , but I don't now how , since the command in the example of the tutorial looks specified to the example situation which is getting the URDF from the on-line source!

RH gravatar imageRH ( 2017-06-03 04:33:47 -0600 )edit

In your rosrun cmd, you are searching for a file called MYROBOT.urdf in a urdf/ directory in the MYROBOT_description package. If you have another question ask another one. But this one is more a ROS question than a gazebo one

GuillaumeB gravatar imageGuillaumeB ( 2017-06-05 03:13:44 -0600 )edit
0

answered 2019-05-31 21:26:41 -0600

You could use our Fusion360 exporter SDFusion, it gives you a full pipeline from Fusion360 to gazebo and more. Its open-source, using the python API of fusion. Fusion is free for students. Your SolidWorks project can easily be imported into fusion. After assigning each rigid link and joint of your robot, the plugin will generate your model.sdf (including joints) and export your links as stl .

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2017-05-27 03:42:39 -0600

Seen: 1,962 times

Last updated: Jun 03 '17