这里写自定义目录标题
如何获取机械手臂的URDF文件
一般可以通过3D画图软件直接导出机械臂的模型,如下链接:
导出urdf文件
如何修改urdf满足实现GAZEBO仿真
为了实现GAZEBO仿真机械臂同步运动,必须在urdf文件中添加gazebo标签:
gazebo tag
- 在urdf文件中添加gazebo_ros_control plugin,添加插件库实现控制
<gazebo> <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"> <robotNamespace>/MYROBOT</robotNamespace> </plugin> </gazebo>
如果有自己机器人的名称空间就加上,没有的花就不需要,可以注释掉:<robotNamespace>/MYROBOT</robotNamespace>
- 添加 transmission elements to a URDF:
<transmission name="shoulder_pan_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint1">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="shoulder_pan_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
针对每个可移动关节在urdf当中添加该属性,其中name自己定义,类型如上,joint name 与机械臂关节一致即可
根据修改完成的URDF文件,配置moveit包
- 在当前的工作空间中执行moveit的配置指令:
roslaunch moveit_setup_assistant setup_assistant.launch
- 然后就加载自己的urdf文件
moveit配置
修改完成的配置文件,实现gazebo仿真
- 修改config文件当中的ros_controllers,yaml文件,该文件当中的controller_lis[]为空,修改为自己的控制器名称:
controller_list:
- name: fd_arm_controller
action_ns: follow_joint_trajectory
default: True
type: FollowJointTrajectory
joints:
- joint1
- joint2
- joint3
- joint4
- joint5
- joint6
- joint7
2.修改完成后在该配置文件当中插入该控制器
fd_arm_controller:
type: position_controllers/JointTrajectoryController
joints:
- joint1
- joint2
- joint3
- joint4
- joint5
- joint6
- joint7
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
joint1: {trajectory: 0.1, goal: 0.1}
joint2 : {trajectory: 0.1, goal: 0.1}
joint3: {trajectory: 0.1, goal: 0.1}
joint4: {trajectory: 0.1, goal: 0.1}
joint5: {trajectory: 0.1, goal: 0.1}
joint6: {trajectory: 0.1, goal: 0.1}
joint7: {trajectory: 0.1, goal: 0.1}
stop_trajectory_duration: 0.5
state_publish_rate: 25
action_monitor_rate: 1
控制器名称和上面一致即可
3.查看ros_controllers.launch文件:
<?xml version="1.0"?>
<launch>
<!-- Load joint controller configurations from YAML file to parameter server -->
<rosparam file="$(find hj)/config/ros_controllers.yaml" command="load"/>
<!-- Load the controllers -->
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
output="screen" args="fd_arm_controller "/>
</launch>
只需要注意加载的args名字和上述配置文件的控制器名称一致即可
运行demo_gazebo.launch,实现gazebo仿真
roslaunch hj demo_gazebo.launch
就可以实现rviz和gazebo同步通信和运动。