modelling elastic collisions in drake

谁说我不能喝 提交于 2020-05-16 02:29:31

问题


I am trying to model an elastic bouncing ball in drake. However, I have not figured out how to set something like the coefficient of restitution for the urdf model I load. Does drake support elastic collisions for the point contact model? If yes how can I set the respective parameters?

Edit: I already tried setting the penetration allowance with plant.set_penetration_allowance(0.0001) but I got the following error: AttributeError: 'MultibodyPlant_[float]' object has no attribute 'set_penetration_allowance'. But since it models a critically damped system I assume it would not help with my problem anyways.

My current code looks as follows:

plane_friction_coef = CoulombFriction(static_friction=1.0, dynamic_friction=1.0)

# generate the diagram of the system
builder = DiagramBuilder()
plant, scene_graph = AddMultibodyPlantSceneGraph(builder, time_step=0.0)
parser = Parser(plant=plant)

# connect to Drake Visualizer
lcm = DrakeLcm()
ConnectDrakeVisualizer(builder, scene_graph, lcm=lcm)

# add plane to plant
X_WP = xyz_rpy_deg(xyz=[0, 0, 0], rpy_deg=[0,0,0])  # offset and orientation of plane wrt. 
world frame
plant.RegisterVisualGeometry(plant.world_body(), X_BG=X_WP, shape=HalfSpace(),
                             name='InclinedPlaneVisualGeometry', 
                             diffuse_color=np.array([1, 1, 1, 0.999]))
plant.RegisterCollisionGeometry(plant.world_body(), X_BG=X_WP, shape=HalfSpace(),
                                name='InclinedPlaneCollisionGeometry',
                                coulomb_friction=plane_friction_coef)
# set gravity in world
plant.mutable_gravity_field().set_gravity_vector(gravity_vec)

# add object from sdf or urdf file
my_object = parser.AddModelFromFile(obj_file_path, model_name='my_object')

plant.Finalize()

# add a logger
logger = LogOutput(plant.get_state_output_port(), builder)
logger.set_name('logger')
logger.set_publish_period(1 / recording_rate)

# build diagram and set its context
diagram = builder.Build()
diagram_context = diagram.CreateDefaultContext()
plant_context = diagram.GetMutableSubsystemContext(plant, diagram_context)
plant.SetPositionsAndVelocities(plant_context, gen_pos)

# start simulation
simulator = Simulator(diagram, diagram_context)
simulator.Initialize()
simulator.set_target_realtime_rate(1)
simulator.AdvanceTo(sim_time)
time_log = logger.sample_times()
state_log = logger.data()

The urdf file I load looks like this:

<?xml version="1.0"?>
<robot name="my_ball">
  <material name="Black">
    <color rgba="0.0 0.0 0.0 1.0"/>
  </material>
  <link name="base_link">
    <inertial>
      <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
      <mass value="5"/>
      <inertia ixx="0.05" ixy="0" ixz="0" iyy="0.05" iyz="0" izz="0.05"/>
    </inertial>
    <visual>
      <geometry>
        <sphere radius="0.2"/>
      </geometry>
      <material name="Black"/>
    </visual>

    <collision name='collision'>
     <geometry>
       <sphere radius="0.2"/>
     </geometry>

    <drake:proximity_properties>
     <drake:mu_dynamic value="1.0" />
     <drake:mu_static value="1.0" />
    </drake:proximity_properties>
   </collision>
  </link>
</robot>

回答1:


Nicolas,

No, currently we do not support elastic collisions given we focused our efforts on slowly approaching contact surfaces as it is the case with manipulation applications. We will definitely support this as our contact solver matures.

That being said, currently there is no support to specify a coefficient of restitution for your model.

The best solution will depend on your particular problem. Is this a vertically bouncing ball? is friction important? (i.e. can the ball also move horizontally?) is it a 2D or 3D case?

From simpler to more complex I'd suggest:

  1. If a vertically bouncing ball, 1DOF, then I'd suggest writing a the dynamics by hand in a LeafSystem.
  2. An "event driven" hybrid model is also possible. And you have an example in Drake here, though probably an advanced used of Drake.
  3. You can create your own LeafSystem that given the state of an MBP as input, computes a contact force as its output (for instance using something like a Hertz model with Hunt-Crossley dissipation). You'd then wire up the applied force through the MBP port MBP::get_applied_spatial_force_input_port().

I hope this helps you out.



来源:https://stackoverflow.com/questions/61462409/modelling-elastic-collisions-in-drake

标签
易学教程内所有资源均来自网络或用户发布的内容,如有违反法律规定的内容欢迎反馈
该文章没有解决你所遇到的问题?点击提问,说说你的问题,让更多的人一起探讨吧!