Gazebo | Ignition | Community
Ask Your Question
0

Collision between static models, or should I move to non-static? Can I force non-static model to be immovable?

asked 2020-09-29 12:14:40 -0500

ateator gravatar image
  • ROS2 Eloquent
  • Gazebo 9.14
  • SDF 1.6
  • Ubuntu 18.04

Hello,

I am currently simulating my custom tandem one-armed wall-mounted pick-and-place robots in Gazebo. Currently they are static models <static>true</static> that know their position rotary encoders on the machine and I am simulating movement in gazebo by model_->GetJointController()->SetJointPosition(...). This means that I will not have collision information for these robots, since physics calculations are not run on static models. When I make my model non-static <static>false</static>, I can no longer move my joints using the method above, instead I use gazebo::common::PID and joint->SetForce(...) to move my machine around.

My issue is that I cannot both get collision data and directly control joint positions of my model. By the design of my robot, it is not stable and if I put it non-static, it will fall. Also the PID method is not preferable, and I would rather set positions directly. But, if I make my robot static, I cannot get collision data from it.

What is the best solution for this issue? Can I keep my model as static, but force the physics engine to calculate collision information? Can I put my model as non-static, but anchor the best to a certain position? Other solutions can be considered

Thank you for your help

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-09-29 16:17:01 -0500

ateator gravatar image

This post is awaiting moderation as I answer but the solution I found was tho affix my robot to the world using a joint (fixed joints dont exist, so we put revolute limits at 0 to simulate fixed) in the SDF as follows

    <joint name='base_to_world' type='revolute'>
  <pose>0 0 0 0 0 0</pose>
  <parent>world</parent>
  <child>base_link</child>
  <axis>
    <xyz>0 0 1</xyz>
    <limit>
      <lower>0</lower>
      <upper>0</upper>
    </limit>        
  </axis>
</joint>

And now I can treat my robot as non-static (dynamic) to get physics on it. I'm having trouble getting the joints to tthe correct positions now, but thats a separate issue ;)

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2020-09-29 10:30:21 -0500

Seen: 352 times

Last updated: Sep 29 '20