由于仿人双足机器人需要仿真在柔性地面上(比如沙地, 橡胶充气床, 野外有树枝落叶堆积地表)行走的表现, 我需要将Gazebo中的ground_plane模型做修改. 本来打算可视化变形的地面, 需要将Gazebo物理引擎换为bullet后, 自己写插件作为地面, 工作量过大, 之后有机会可再基于下面这篇论文探索.https://lcsr.jhu.edu/wp-content/uploads/2016/09/Hudson-Thomas-softbody-simulation-gazebo-final.pdfhttps://lcsr.jhu.edu/wp-content/uploads/2016/09/Hudson-Thomas-softbody-simulation-gazebo-final.pdf
故本文只讨论在ODE物理引擎下, 在力学特性上模拟柔性地面, 下面首先展示原有的硬质地面的代码:
<?xml version="1.0" ?>
<sdf version='1.4'>
<world name='default'>
<gravity>0.000000 0.000000 -9.810000</gravity>
<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>
</light>
<physics type="ode">
<real_time_update_rate>1000.0</real_time_update_rate>
<max_step_size>0.001</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>1000</real_time_update_rate>
<ode>
<solver>
<type>quick</type>
<iters>200</iters>
<precon_iters>0</precon_iters>
<sor>1.4</sor>
<use_dynamic_moi_rescaling>1</use_dynamic_moi_rescaling>
</solver>
<constraints>
<cfm>0.000000</cfm>
<erp>0.8</erp>
<contact_max_correcting_vel>2000.000000</contact_max_correcting_vel>
<contact_surface_layer>0.01000</contact_surface_layer>
</constraints>
</ode>
</physics>
<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>
<friction>
<ode>
<mu>100</mu>
<mu2>50</mu2>
<fdir1>1 0 0</fdir1>
</ode>
</friction>
<bounce/>
<contact>
<ode/>
</contact>
</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>
<velocity_decay>
<linear>0</linear>
<angular>0</angular>
</velocity_decay>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
<gravity>1</gravity>
</link>
</model>
<scene>
<ambient>0.4 0.4 0.4 1</ambient>
<background>0.7 0.7 0.7 1</background>
<shadows>1</shadows>
</scene>
<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>18 131000000</sim_time>
<real_time>18 249402717</real_time>
<wall_time>1442867251 89781872</wall_time>
<model name='ground_plane'>
<pose>0 0 0 0 -0 0</pose>
<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>
</state>
<gui fullscreen='0'>
<camera name='user_camera'>
<pose>5 -5 2 0 0.275643 2.35619</pose>
<view_controller>orbit</view_controller>
</camera>
</gui>
</world>
</sdf>
经过研究, 本质上我们需要改变碰撞的两个物体的刚度 stiffness - kp (500 is pretty ridiculously malleable, like a really underinflated yoga ball, ; 500,000 is good for truly solid objects like metals) 和对碰撞是否为完美弹性碰撞的程度 damping - kd (0 represents a perfectly elastic collision (no kinetic energy is lost during collision) ; 100 is more like dropping a block of wood on the ground). 本文中, 一方面机器人的两只脚材质为铝合金, 故kp很大, 考虑脚底有海绵吸振, 故kd非零. 整体设置如下:
<gazebo reference="r_leg_foot_link">
<kp>100000.0</kp> <!--500 is pretty ridiculously malleable, like a really underinflated yoga ball, ; 500,000 is good for truly solid objects like metals-->>
<kd>100.0</kd> <!--0 represents a perfectly elastic collision (no kinetic energy is lost during collision) ; 100 is more like dropping a block of wood on the ground-->>
<mu1>1.0</mu1>
<mu2>1.0</mu2>
<!--mu1>1.5</mu1>
<mu2>1.5</mu2-->
<fdir1>1 0 0</fdir1>
<maxVel>1.0</maxVel>
<minDepth>0.0</minDepth>
<material>Gazebo/Grey</material>
</gazebo>
另一方面, 地面希望是软性的, 而且希望机器人脚可以穿透表面 (类似人站立在弹性跳床上), 因此除了大约5000的kp. 和完美弹性碰撞的0的kd外, 还需要考虑另外两个参数: 最小入侵深度min_depth和最大反弹速度max_vel. 在一次碰撞里, 最终的两个物体最大入侵深度min_depth会是"2个物体各自的<min_depth>"和".world文件<contact_surface_layer>"三个值的最小值. max_vel也会是"2个物体各自的<max_vel>"和".world文件<contact_max_correcting_vel>"三个值中的最小值, 保证max_vel比碰撞的物体应有运动最大速度更大, 就可以忽略其具体的值. 故修改后的地面代码为:
<?xml version="1.0" ?>
<sdf version='1.4'>
<world name='default'>
<gravity>0.000000 0.000000 -9.810000</gravity>
<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>
</light>
<physics type="ode">
<real_time_update_rate>1000.0</real_time_update_rate>
<max_step_size>0.001</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>1000</real_time_update_rate>
<ode>
<solver>
<type>quick</type>
<iters>200</iters>
<precon_iters>0</precon_iters>
<sor>1.4</sor>
<use_dynamic_moi_rescaling>1</use_dynamic_moi_rescaling>
<friction_model>cone_model</friction_model>
</solver>
<constraints>
<cfm>0.000000</cfm>
<erp>0.8</erp>
<contact_max_correcting_vel>2000.000000</contact_max_correcting_vel>
<contact_surface_layer>1.0</contact_surface_layer>
</constraints>
</ode>
</physics>
<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>
<friction>
<ode>
<mu>1</mu>
<mu2>1</mu2>
<fdir1>1 0 0</fdir1>
<slip1>0.0</slip1>
<slip2>0.0</slip2>
</ode>
</friction>
<bounce/>
<contact>
<ode>
<kp>5000</kp> <!--5000 is pretty ridiculously malleable, like a really underinflated yoga ball, ; 500,000 is good for truly solid objects like metals-->>
<kd>0</kd> <!--0 represents a perfectly elastic collision (no kinetic energy is lost during collision) ; 100 is more like dropping a block of wood on the ground-->>
<min_depth>1.0</min_depth>
<max_vel>100</max_vel>
</ode>
</contact>
</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/Green</name>
</script>
</material>
</visual>
<velocity_decay>
<linear>0</linear>
<angular>0</angular>
</velocity_decay>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
<gravity>1</gravity>
</link>
</model>
<scene>
<ambient>0.4 0.4 0.4 1</ambient>
<background>0.7 0.7 0.7 1</background>
<shadows>1</shadows>
</scene>
<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>18 131000000</sim_time>
<real_time>18 249402717</real_time>
<wall_time>1442867251 89781872</wall_time>
<model name='ground_plane'>
<pose>0 0 0 0 -0 0</pose>
<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>
</state>
<gui fullscreen='0'>
<camera name='user_camera'>
<pose>5 -5 2 0 0.275643 2.35619</pose>
<view_controller>orbit</view_controller>
</camera>
</gui>
</world>
</sdf>
机器人在如上设置的柔性地面步行效果
其实还有两个字面上和柔软直接相关的参数我还不理解, 希望大佬指点:
-
soft_cfm
Soft constraint force mixing. This is useful to make surfaces soft. -
soft_erp
Soft error reduction parameter. This is useful to make surfaces soft.
本次修改参考了官方ODE参数介绍和另一个网页, 希望帮到大家: