文章目录
1.基础
官方RRBOT案例:传送门
ros_control和controller:传送门
moveit配置:传送门
2.思路梳理
ros与gazebo/真实机器人通信架构
来个简化版的:
省略了机器人实体部分,其中Driver就负责moveit与真实机器人或者gazebo通信,真实机器人与gazebo仿真的区别就在于:
- ① gazebo仿真时,这个Driver已经帮我们集成好了,我们只需要写个controller就可以实现通信!
- ② 真实机器人中,如果是自己开发的机器人,这个Driver需要我们自己去编写
同理,其他仿真软件,由于没有帮我们集成好这个Driver,所以当我们使用其他仿真软件与ros联合使用时,就需要自己完成这个Driver的实现,这个过程和真实机器人中是相同的!
从上图可以看到,这个Driver负责控制命令的翻译、下发和机器人状态的反馈,牢牢记住这个图!!!
moveit架构
我们可以看到,JointTrajectoryAction
部分,是通过Robot Controllers
进行翻译的,而这个整体框架即 ros与gazebo/真实机器人通信架构 的细节部分!
moveit联合gazebo仿真时需要的控制器
使用MoveIt! Setup Assistant 配置完后,会有两个控制器文件,在moveit_config包的**/config**下:
fake_controllers.yaml
:为了发布一个虚假的状态,来骗过moveit,目的是可以单独的在rviz里运行moveitros_controllers.yaml
:里面配置了些与硬件接口和仿真相关的内容
但是这两个控制器文件不能达到我们联合仿真的目的!!!
古月君对MoveIt+Gazebo的仿真框架有个很生动的比喻:他把MoveIt下发的FollowJointTrajectory
比喻成插头,把机器人接收轨迹Joint Trajectory Controller
和状态反馈部分Joint State Controller
比喻成插座,所以我们需要两个控制器来实现moveit和gazebo的联合仿真:
robot_control.yaml
myrobot:
# Publish all joint states -----------------------------------
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50
myrobot:
arm_joint_controller:
type: "position_controllers/JointTrajectoryController"
joints:
- joint_1
- joint_2
- joint_3
- joint_4
- joint_5
- joint_6
gains:
joint_1: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}
joint_2: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}
joint_3: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}
joint_4: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}
joint_5: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}
joint_6: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}
启动控制器:
<launch>
<!-- 运行robot_state_publisher节点,发布tf -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"
respawn="false" output="screen">
<param name="publish_frequency" type="double" value="50.0" />
<param name="tf_prefix" type="string" value="" />
</node>
<!-- Robot state publisher -->
<rosparam file="$(find robot_gazebo)/config/robot_control.yaml" command="load"/>
<node name="arm_controller_spawner"
pkg="controller_manager"
type="spawner"
respawn="false"
output="screen"
ns="/myrobot"
args="arm_joint_controller"/>
<!-- joint_state_controller -->
<rosparam file="$(find robot_gazebo)/config/robot_gazebo_joint_states.yaml" command="load"/>
<node name="joint_controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
output="screen" ns="/myrobot" args="joint_state_controller" />
</launch>
controllers.yaml
controller_manager_ns: controller_manager
controller_list:
- name: myrobot/arm_joint_controller
action_ns: follow_joint_trajectory
type: FollowJointTrajectory
default: true
joints:
- joint_1
- joint_2
- joint_3
- joint_4
- joint_5
- joint_6
启动控制器:
moveit_controller_manager.launch.xml
<launch>
<!-- gazebo Controller -->
<rosparam file="$(find robot_moveit_config)/config/controllers_gazebo.yaml"/>
<arg name="moveit_controller_manager" default="moveit_simple_controller_manager/MoveItSimpleControllerManager"/>
<param name="moveit_controller_manager" value="$(arg moveit_controller_manager)"/>
</launch>
注意:这些控制器文件中关节的名称和描述文件中必须统一!!!
3. 具体实现
描述文件
需要保证描述文件中已经添加gazebo_ros_control
插件
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
</plugin>
</gazebo>
已经添加transmission
,尤其注意硬件接口的配置
参考文献: