一、.ROS中的控制器插件
1.ros_control是什么?
1)為開發者提供的機器人控制中間件;
2)包含一系列控制器接口、傳動裝置接口、硬件接口、控制器工具等;
3)可以幫助機器人應用功能包快速落地。
控制器管理:提供一種通用的借口來管理不同的控制器
控制器:讀取硬件狀態,發布控制指令,完成每個joint的控制
硬件資源:為上下兩層提供硬件資源的接口
機器人硬件抽象:機器人硬件抽象和硬件資源直接打交道,通過write和reaf方法完成硬件操作
真實機器人:執行接收到的命令
2.控制器(Controllers):
joint_state_controller:監控機器人狀態
joint_effort_controller
joint_position_controller:最常用!
joint_velocity_controller
二、完善機器人模型
1)為Link添加慣性參數和碰撞屬性(注意物理參數,這里將質量設置的很小,慣性設置的較大,讓我們仿真穩定)
2)為joint添加傳動裝置
3)添加gazebo控制器插件
啟動:可能會出現PID增益不存在的報錯,需要修改參數配置的形式
roslaunch probot_gazebo probot_anno_gazebo_world.launch
三、構建MoveIt!+Gazebo仿真
划重點!!!
Joint Trajectory Controller :
接收action發來的trajecotry軌跡,並完成每個軸的插補運算,讓每個軸動起來
1)參數配置,配置控制器arm_joint_conotroller的類型、關節、增益等參數
probot_anno:
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}
2)控制器啟動,probot_anno_trajectory_controller.launch,啟動了一個arm_joint_controller控制器
<launch> <rosparam file="$(find probot_gazebo)/config/probot_anno_trajectory_control.yaml" command="load"/> <node name="arm_controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" ns="/probot_anno" args="arm_joint_controller"/> </launch>
插補運算提供了三種算法(默認使用五次樣條):
1)線性樣條:位置連續、速度、加速度不連續
2)三次樣條:位置和速度連續,加速度不連續
3)五次樣條:位置、速度、加速度都連續
Joint State Controller:
監控關節實時狀態
1)參數配置,設置發布頻率50hz,即20ms一次
probot_anno:
# Publish all joint states -----------------------------------
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50
2)控制器啟動,probot_anno_gazebo_states.launch,與上面的類似
<launch> <!-- 將關節控制器的配置參數加載到參數服務器中 --> <rosparam file="$(find probot_gazebo)/config/probot_anno_gazebo_joint_states.yaml" command="load"/> <node name="joint_controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" ns="/probot_anno" args="joint_state_controller" /> <!-- 運行robot_state_publisher節點,發布tf --> <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="false" output="screen"> <remap from="/joint_states" to="/probot_anno/joint_states" /> </node> </launch>
注意區分joint_state_publisher和robot_state_publisher
Follow Joint Trajectory
封裝trajectory成action,並發出去
1)參數配置,注意這個文件是在MoveIt!中的probot_annp_moveit_config功能包中,這個文件將會被probot_anno_moveit_controller_manager.launch加載,啟動時會自動啟動這個controller
controller_manager_ns: controller_manager
controller_list:
- name: probot_anno/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
2)控制器啟動,probot_anno_moveit_controller_manager.launch,注意這個launch文件也在probot_annp_moveit_config功能包中,后綴.xml沒有用!
<launch> <arg name="moveit_controller_manager" default="moveit_simple_controller_manager/MoveItSimpleControllerManager"/> <param name="moveit_controller_manager" value="$(arg moveit_controller_manager)"/> <!-- gazebo Controller --> <rosparam file="$(find probot_anno_moveit_config)/config/controllers_gazebo.yaml"/> </launch>
最終的launch文件:
<launch> <!-- Launch Gazebo --> <include file="$(find probot_gazebo)/launch/probot_anno/probot_anno_gazebo_world.launch" /> <!-- ros_control arm launch file --> <include file="$(find probot_gazebo)/launch/probot_anno/probot_anno_gazebo_states.launch" /> <!-- ros_control trajectory control dof arm launch file --> <include file="$(find probot_gazebo)/launch/probot_anno/probot_anno_trajectory_controller.launch" /> <!-- moveit launch file --> <include file="$(find probot_anno_moveit_config)/launch/moveit_planning_execution.launch" /> </launch>
這邊最后調用的moveit_planning_execution.launch包含了很多文件的,需要仔細分析
實際運行:
roslaunch probot_gazebo probot_anno_bringup_moveit.launch
觀察trajectory數據:
rostopic echo /probot_anno/arm_joint_controller/follow_joint_trajectory/goal
數據格式為:關節空間的軌跡,可以進行細插補
觀察每個關節位置的曲線
rosrun rqt_plot rqt_plot
訂閱/probot_anno/joint_states/position[5]
最后,尷尬的是仿真了40幾分鍾的時候,gazebo中的機械臂翻了,應該是重力的影響,可以嘗試把底座固定在地面上,添加一個固定關節。
學習資料鏈接:
Gazebo Tutorial:http://www.gazebosim.org/tutorials
gazebo和rviz有具體的區別嗎?那個更好用?(因為公眾號遷移,鏈接有點長)https://mp.weixin.qq.com/s?__biz=MzU1NjEwMTY0Mw==&mid=2247485881&idx=1&sn=8a450bf099e5a865da0e4950aedab970&source=41#wechat_redirect
ROS技術點滴----ros_control:https://mp.weixin.qq.com/s?__biz=MzU1NjEwMTY0Mw==&mid=2247485887&idx=1&sn=83d036542f242f8831bf1a43df70d89a&source=41#wechat_redirect
ROS探索哦總結(二十四)---使用gazebo中的插件:https://www.guyuehome.com/388