文章目录
项目基础
(ROS)差分轮式机械臂机器人(二)六轴机械臂Moveit配置&深度相机kinect配置
(ROS)差分轮式机械臂机器人(一)模型搭建
项目源码
https://gitee.com/HOY_Z/ros_-visual-nav_-arm
控制框架
- 首先当指令进来后,由 Moveit (Action 客户端)做规划输出Trajectory Data ,也就是轨迹数据,通过 Follow Joint Trajectory 这个接口,将轨迹信息封装成 Action,Action 发送给Trajectory Controller ,不论是在实际的机器人控制器还是Gazebo(Action服务端)中,都会在这里进行插补运算(因为轨迹里边是一些中间间隔一定时间长度的轨迹点,这个时间不可以直接用做控制,控制器要求这个时间必须细微,所以就涉及到了插补算法),插补算法会完成六个轴的插补运算,插补后将数据发送给 Position Servo(位置伺服驱动器),驱动器收到信号之后驱动电机发生运动。机器人端还要将状态信息通过Joint State Controller反馈给Moveit,形成一个信息的闭环
Gazebo控制插件:position_controllers/JointTrajectoryController 关节轨迹控制器
- gazebo端(action sever)接受Moveit端(action client)发送过来的轨迹要求 然后控制到每一个关节
- 可以通过一个trajectory_control.yaml文件加载gazebo端的控制器arm_joint_controller和gripper_controller
arm: #工作空间
arm_joint_controller: #控制器名字
type: "position_controllers/JointTrajectoryController" #官方的数据类型
joints:
- joint1
- joint2
- joint3
- joint4
- joint5
- joint6
gains:
joint1: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}
joint2: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}
joint3: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}
joint4: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}
joint5: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}
joint6: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}
gripper_controller:
type: "position_controllers/JointTrajectoryController"
joints:
- finger_joint1
gains:
finger_joint1: {p: 50.0, d: 1.0, i: 0.01, i_clamp: 1.0}
- 然后通过一个launch文件加载这个配置文件并生效
- vnarm_gazebo/launch/arm_trajectory_controller.launch
<launch>
<!-加载配置文件->
<rosparam file="$(find vnarm_gazebo)/config/trajectory_control.yaml" command="load"/>
<!-启动控制器节点:通过控制管理产生配置文件中规定的两个控制器arm_joint_controller gripper_controller->
<node name="arm_controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
output="screen" ns="/arm" args="arm_joint_controller gripper_controller"/>
</launch>
Moveit控制插件 :FollowJointTrajectory
- 配置文件followJoint_controller.yaml
- 注意工作空间和控制器的名字必须要与gazebo端的controller一致 ,这样子插头插座才能匹配
controller_manager_ns: controller_manager
controller_list:
- name: arm/arm_joint_controller
action_ns: follow_joint_trajectory
type: FollowJointTrajectory
default: true
joints:
- joint1
- joint2
- joint3
- joint4
- joint5
- joint6
- name: arm/gripper_controller
action_ns: follow_joint_trajectory
type: FollowJointTrajectory
default: true
joints:
- finger_joint1
-
launch 文件加载配置文件
-
vnarm_moveit_config/launch/moveit_planning_execution.launch
<launch> # The planning and execution components of MoveIt! configured to # publish the current configuration of the robot (simulated or real) # and the current state of the world as seen by the planner <include file="$(find vnarm_moveit_config)/launch/move_group.launch"> <arg name="publish_monitored_planning_scene" value="true" /> </include> <!--同时打开rviz--> <include file="$(find vnarm_moveit_config)/launch/moveit_rviz.launch"/> <!-- 产生关节信息并发出话题 --> <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher"> <param name="/use_gui" value="false"/> <rosparam param="/source_list">[/arm/joint_states]</rosparam> </node> <!-- 加载FollowJonitTrajectory配置文件 --> <rosparam file="$(find vnarm_moveit_config)/config/followJoint_controllers.yaml" command="load"/> </launch>
加载全部配置文件
- vnarm_gazebo/launch/arm_gazebo_bringup_all.launch
<launch>
<!--启动gazebo环境 tf坐标变化 加载模型 运行joint_state_publisher节点-->
<include file="$(find vn_robot_description)/launch/display_vnbot_gazebo.launch" />
<!--启动gazobo端 JointTrajectoryController-->
<include file="$(find vnarm_gazebo)/launch/arm_trajectory_controller.launch"/>
<!--加载moveit端需要用到的launch文件-->
<include file="$(find vnarm_moveit_config)/launch/moveit_planning_execution.launch"/>
</launch>
-
vn_robot_decription/launch/display_vnbot_gazebo.launch
- 主要加载机器人模型和场景
<launch>
<!-- 设置launch文件的参数 -->
<arg name="world_name" value="$(find vn_robot_description)/urdf/xacro/gazebo/worlds/cloister.world"/>
<arg name="paused" default="false"/>
<arg name="use_sim_time" default="true"/>
<arg name="gui" default="true"/>
<arg name="headless" default="false"/>
<arg name="debug" default="false"/>
<!-- 运行gazebo仿真环境 -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(arg world_name)" />
<arg name="debug" value="$(arg debug)" />
<arg name="gui" value="$(arg gui)" />
<arg name="paused" value="$(arg paused)"/>
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
<arg name="headless" value="$(arg headless)"/>
</include>
<!-- 加载机器人模型描述参数 -->
<param name="robot_description" command="$(find xacro)/xacro '$(find vn_robot_description)/urdf/xacro/gazebo/vnbot_with_kinect_gazebo.xacro'" />
<!-- 运行joint_state_publisher节点,发布机器人的关节状态 -->
<node pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" name="joint_state_publisher_gui" output="screen" />
<!-- 运行robot_state_publisher节点,发布tf -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" output="screen" >
<param name="publish_frequency" type="double" value="50.0" />
</node>
<!-- 在gazebo中加载机器人模型-->
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
args="-urdf -model mrobot -param robot_description"/>
</launch>
执行
运行roslaunch vnarm_gazebo arm_gazebo_bringup_all.launch
- 首先配置rviz 点击左下角“Add” 添加“MotionPlanning”
- 选择好frame
- plan and execute
-
保存rviz中的config: 左上角:file–》save config as–》保存到“vnarm_gazebo/config/moveit_gazebo.rviz”
并在vnarm_moveit_config/launch/moveit_rviz.launch中加载配置文件
<launch> <arg name="debug" default="false" /> <arg unless="$(arg debug)" name="launch_prefix" value="" /> <arg if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" /> <arg name="rviz_config" default="$(find vnarm_gazebo)/config/moveit_gazebo.rviz" /> <arg if="$(eval rviz_config=='')" name="command_args" value="" /> <arg unless="$(eval rviz_config=='')" name="command_args" value="-d $(arg rviz_config)" /> <node name="$(anon rviz)" launch-prefix="$(arg launch_prefix)" pkg="rviz" type="rviz" respawn="false" args="$(arg command_args)" output="screen"> </node> </launch>