国内协作臂厂家一般会提供3D模型,有些厂家与ROS对接较好,可以提供用solidworks导出的urdf工程。如果厂家没有提供,也可以基于3D模型自己使用solidworks导出urdf工程。具体可以参考下面链结:
http://wiki.ros.org/sw_urdf_exporter我自己使用1.5版本的exporter在solidworks2016上,ROS版本为melodic,已确保安装所有gazebo和ros_control相关的软件包。使用厂家提供的3D模型导出urdf工程,再用moveit_setup_assistant生成ROBOT_moveit_config工程,基于这个工程配置gazebo仿真。在网上查阅了gazebo的tutorials,但按照上面的方法并不完全适合moveit_config工程。搞了一天,终于弄好了,现把方法分享如下:

步骤1、在ROBOT_moveit_config/config/ros_controllers.yaml中增加joint trajectory controller配置。
这部分配置就是上面图中JointTrajectoryAction需要机器人控制器实现的Action Server部分(Robot Controllers)。配置关节,配置PID增益。关节部分需要与urdf中的关节对应,PID增益则需要自己微调(小心有坑)。
xxxROBOT_controller:
type: position_controllers/JointTrajectoryController
joints:
- joint1
- joint2
- joint3
- joint4
- joint5
- joint6
gazebo_ros_control/pid_gains:
# gains:
joint1: {p: 100.0, i: 1.0, d: 10.0, i_clamp_min: -1.0, i_clamp_max: 1.0}
joint2: {p: 100.0, i: 1.0, d: 10.0, i_clamp_min: -1.0, i_clamp_max: 1.0}
joint3: {p: 100.0, i: 1.0, d: 10.0, i_clamp_min: -1.0, i_clamp_max: 1.0}
joint4: {p: 100.0, i: 1.0, d: 10.0, i_clamp_min: -1.0, i_clamp_max: 1.0}
joint5: {p: 100.0, i: 1.0, d: 10.0, i_clamp_min: -1.0, i_clamp_max: 1.0}
joint6: {p: 100.0, i: 1.0, d: 10.0, i_clamp_min: -1.0, i_clamp_max: 1.0}