介绍
为了方便开发者使用我们的平台,本次开源的算法在12自由度的pai上面进行了仿真验证。
本次开源的算法是基于桥介数物(BridgeDP)的hunter_bipedal_control做的一些改进,包括对踝关节两自由度的锁定,使其同步成为一个自由度,以及适配高擎自己开发的SDK接口,用于真机调试。
开源的代码放在了github上 ,项目名为livelybot_dynamic_control:
https://github.com/HighTorque-Robotics/livelybot_dynamic_control.git
README.md有详细的配置过程。
仿真环境
本框架使用gazebo进行仿真,同时支持rivz查看机器人的状态以及规划轨迹,gazebo的环境安装可以直接使用鱼香ROS的一键安装,安装ubuntu20.04对应的noetic版本的ros环境,该环境包含gazebo。搭建仿真环境的过程为,使用solidworks的urdf插件将图纸导出为urdf。
一个注意事项,solidworks的urdf插件直接导出的转动惯量矩阵是错误的,你需要自行修改urdf中的转动惯量矩阵。具体的做法是,使用solidworks的“评估-质量属性”功能,在选项中设置单位制,设置当前link所对应坐标系的坐标值,设置为负张量计数法(要求solidworks版本至少为2021SP5),并使用“由重心决定,并且对齐输出的坐标系。 (使用负张量记数法。)”的惯性矩阵。
导出的urdf不能直接给gazebo使用,需要添加gazebo_ros_control插件,以及一些传感器和执行器插件等,具体如下:
<gazebo> //以及gazebo_ros_control插件
<plugin name="gazebo_ros_control" filename="libhunter_bipedal_hw_sim.so">
<robotNamespace>/</robotNamespace>
<robotParam>legged_robot_description</robotParam>
<robotSimType>legged_gazebo/LeggedHWSim</robotSimType>
</plugin>
</gazebo>
<gazebo> //imu插件
<plugin filename="libgazebo_ros_p3d.so" name="p3d_base_controller">
<alwaysOn>true</alwaysOn>
<updateRate>500.0</updateRate>
<bodyName>base_link</bodyName>
<topicName>ground_truth/state</topicName>
<gaussianNoise>0</gaussianNoise>
<frameName>world</frameName>
<xyzOffsets&g