1、## 这个博客实现了urdf在gazebo的整个实现过程
2、上述博客里面的模型乱飞问题需要修改urdf的关节速度,因为速度过大,模型发生了碰撞,因此模型就乱飞
3、最近一段时间,在调试gazebo的反馈和simulink的输入给定一致
4、调试过程中遇到了比较多的问题,最后慢慢摸索解决最终的运行效果如下,可以看到gazebo里面的机械臂能够和simulink的机械臂运动估计基本一致,前期存在较大抖动,应该是什么参数没调好,后续还需要进行修改。
5、实现上述过程我主要是修改了
(.world文件)添加ode物理引擎
<physics name="default_physics" default="0" type="ode">
<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>50</iters>
<sor>1.0</sor> <!-- Important, see issue #2209 -->
<use_dynamic_moi_rescaling>1</use_dynamic_moi_rescaling>
</solver>
</ode>
</physics>
.world文件的整体代码如下:
<?xml version="1.0"?>
<sdf version='1.6'>
<world name="default">
<physics name="default_physics" default="0" type="ode">
<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>50</iters>
<sor>1.0</sor> <!-- Important, see issue #2209 -->
<use_dynamic_moi_rescaling>1</use_dynamic_moi_rescaling>
</solver>
</ode>
</physics>
<joint name="world_to_robot" type="fixed">
<parent>world</parent>
<child>Gluon_6L3::base_link</child>
</joint>
<include>
<uri>model://ground_plane</uri>
</include>
<include>
<uri>model://sun</uri>
</include>
<model name="box">
<pose>0.2 0.4 0.6 0 0 0</pose>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>0.05 0.05 0.05</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.05 0.05 0.05</size>
</box>
</geometry>
</visual>
</link>
</model>
<plugin name='GazeboPlugin' filename='lib/libGazeboCoSimPlugin.so'>
<portNumber>14581</portNumber>
</plugin>
</world>
</sdf>
(2)urdf文件:这部分必须是hardwareInterface/PositionJointInterface;如果只写PositionJointInterface会回到初始状态位置
<transmission name="shoulder_pan_joint_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="shoulder_pan_joint">
<hardwareInterface>hardwareInterface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="shoulder_pan_joint_motor">
<hardwareInterface>hardwareInterface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>0.05</mechanicalReduction>
</actuator>
</transmission>
<transmission name="shoulder_lift_joint_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="shoulder_lift_joint">
<hardwareInterface>hardwareInterface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="shoulder_lift_joint_motor">
<hardwareInterface>hardwareInterface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>0.05</mechanicalReduction>
</actuator>
</transmission>
<transmission name="elbow_joint_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="elbow_joint">
<hardwareInterface>hardwareInterface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="elbow_joint_motor">
<hardwareInterface>hardwareInterface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>0.05</mechanicalReduction>
</actuator>
</transmission>
<transmission name="wrist_1_joint_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="wrist_1_joint">
<hardwareInterface>hardwareInterface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="wrist_1_joint_motor">
<hardwareInterface>hardwareInterface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>0.05</mechanicalReduction>
</actuator>
</transmission>
<transmission name="wrist_2_joint_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="wrist_2_joint">
<hardwareInterface>hardwareInterface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="wrist_2_joint_motor">
<hardwareInterface>hardwareInterface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>0.05</mechanicalReduction>
</actuator>
</transmission>
<transmission name="wrist_3_joint_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="wrist_3_joint">
<hardwareInterface>hardwareInterface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="wrist_3_joint_motor">
<hardwareInterface>hardwareInterface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>0.05</mechanicalReduction>
</actuator>
</transmission>
6、经过上述两部分,我是实现了图片那种效果,不知道是不是大家也能实现。也可能我过程中乱七八糟改了很多地方忘记记录,准备再走一遍新的urdf试一下是不是能够实现上述过程。