本文档主要捋清楚机械臂控制包的建立过程,不涉及具体的代码,按照流程的话,代码基本都是自动生成的
1.说明
Moveit是ROS软件的机械臂控制的功能包,如果想进行机械臂的运动规划的话,肯定是必不可少的;
ArbotiX可以认为是一个机械臂硬件的驱动包,同时本身还带有机械臂的仿真功能。
我的理解是,如果想实现通过代码的控制机械臂的话(正向运动学,控制个轴节点,逆向运动学,通过终端位置控制)目前ArbotiX是一个很好的选择。
两者的关系基本情况就是这样。
2.该环境的搭建可以分成三个包
(1)通过solidworks导出的机械臂模型的包:arm
也可以自己编写xacro文件,不过这里采用的是solidwords导入,具体方法可以自己网上搜;
需要注意一点,生成包的时候需要改名字为arm,如果不修改,导出的包的名字与solidwoks的工程名相同,后期想手动修改也可以(要把CMakeLists.txt package.xml还有urdf文件里的名字统统替换掉)
(2)通过setup-assistant配置的moveit的功能包,arm_moveit
(3)运动规划包,arm_planning
下面自己建立的一些文件会放置在这个包中
3.搭建步骤
(1)在通过setup-assistant配置好arm_moveit包后,可以通过如下命令进行验证
roslaunch arm_moveit demo.launch
如果弹出的窗口出现机械臂模型,说明成功;
(2)添加arbotix关节控制器
首先在arm/config中新建arm.yaml文件
joints: {
joint1: {id: 1, neutral: 205, max_angle: 269.6, min_angle: -269.6, max_speed: 90},
joint2: {id: 2, max_angle: 180, min_angle: -180.0, max_speed: 90},
joint3: {id: 3, max_angle: 180, min_angle: -180.0, max_speed: 90},
joint4: {id: 4, max_angle: 180, min_angle: -180.0, max_speed: 90},
joint5: {id: 5, max_angle: 180, min_angle: -180.0, max_speed: 90},
joint6: {id: 6, max_angle: 180, min_angle: -180.0, max_speed: 90},
}
controllers: {
arm_controller: {type: follow_controller, joints: [joint1, joint2, joint3,joint4, joint5, joint6], action_name: arm_controller/follow_joint_trajectory, onboard: False }
}
然后在arm_planning/launch中创建fake_arm.launch文件
<launch>
<!-- 不使用仿真时间 -->
<param
name="/use_sim_time"
value="false" />
<!--arg
name="gui"
default="False" /-->
<!-- 启动arbotix driver-->
<arg
name="sim"
default="true" />
<param
name="robot_description"
textfile="$(find arm)/urdf/inffos_arm.urdf" /> /调用的生成的urdf文件
<node
name="arbotix"
pkg="arbotix_python"
type="arbotix_driver"
output="screen" >
<rosparam
file="$(find arm)/config/arm.yaml" command="load" /> /调用的刚才新建的arm.yaml
<param
name="sim"
value="true"/>
</node>
<node
name="joint_state_publisher"
pkg="joint_state_publisher"
type="joint_state_publisher" />
<node
pkg="robot_state_publisher"
type="robot_state_publisher"
name="rob_st_pub" />
<!-- 启动rviz -->
<node
name="rviz"
pkg="rviz"
type="rviz"
args="-d $(find arm_planning)/urdf.rviz" />
</launch>
第三步是在arm_planning/scripts建立一个python控制文件trajectory_demo.py,通过各joint节点的角度实现机械臂的控制
源码如下:
#!/usr/bin/env python
# -*- coding: utf-8 -*-
import rospy
import actionlib
from control_msgs.msg import FollowJointTrajectoryAction, FollowJointTrajectoryGoal
from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
class TrajectoryDemo():
def __init__(self):
rospy.init_node('trajectory_demo')
# 是否需要回到初始化的位置
reset = rospy.get_param('~reset', False)
# 机械臂中joint的命名
arm_joints = ['joint1',
'joint2',
'joint3',
'joint4',
'joint5',
'joint6']
if reset:
# 如果需要回到初始化位置,需要将目标位置设置为初始化位置的六轴角度
arm_goal = [0, 0, 0, 0, 0, 0]
else:
# 如果不需要回初始化位置,则设置目标位置的六轴角度
arm_goal = [0.9, -0.8, 0.9, 0.4, 0.5, 3]
# 连接机械臂轨迹规划的trajectory action server
rospy.loginfo('Waiting for arm trajectory controller...')
arm_client = actionlib.SimpleActionClient('arm_controller/follow_joint_trajectory', FollowJointTrajectoryAction)
rospy.loginfo('wait_for---')
arm_client.wait_for_server()
rospy.loginfo('...connected.')
# 使用设置的目标位置创建一条轨迹数据
arm_trajectory = JointTrajectory()
arm_trajectory.joint_names = arm_joints
arm_trajectory.points.append(JointTrajectoryPoint())
arm_trajectory.points[0].positions = arm_goal
arm_trajectory.points[0].velocities = [0.0 for i in arm_joints]
arm_trajectory.points[0].accelerations = [0.0 for i in arm_joints]
arm_trajectory.points[0].time_from_start = rospy.Duration(3.0)
rospy.loginfo('Moving the arm to goal position...')
# 创建一个轨迹目标的空对象
arm_goal = FollowJointTrajectoryGoal()
# 将之前创建好的轨迹数据加入轨迹目标对象中
arm_goal.trajectory = arm_trajectory
# 设置执行时间的允许误差值
arm_goal.goal_time_tolerance = rospy.Duration(0.0)
# 将轨迹目标发送到action server进行处理,实现机械臂的运动控制
arm_client.send_goal(arm_goal)
# 等待机械臂运动结束
arm_client.wait_for_result(rospy.Duration(5.0))
rospy.loginfo('...done')
if __name__ == '__main__':
try:
TrajectoryDemo()
except rospy.ROSInterruptException:
pass
然后分别执行
roslaunch arm_planning fake_arm.launch
rosrun arm_planning trajectory_demo.py
其中执行roslaunch后,会出现以下情况,讲map替换为你的base link;并点击下方的add然后添加robotmodel即可
需要说明的是arbotix关节控制器的验证其实并未用到arm_moveit的功能包,此验证其实就是通过python程序直接输出控制机械臂的执行器完成操作;
(3)此处就是moveit联合arbotix一起做运动规划了,首先是正向运动
此处可能会有两处修改,
第一处是arm_moveit包是按照实体机器人生成的,在config的ros_controller.yaml有反应(其中可以看到hardware_interface字样),这里(arm_moveit/config/)需要重建一个controller.yaml包用于仿真;文件内容如下:
controller_list:
- name: arm_controller
action_ns: follow_joint_trajectory
type: FollowJointTrajectory
default: true
joints:
- joint1
- joint2
- joint3
- joint4
- joint5
- joint6
第二处修改
需要修改调用controller.yaml的文件,位置arm_moveit/launch/arm_moveit_controller_manager.launch.xml(此文件会被move_group.launch调用)
将倒数第二行的ros_controller.yaml修改成controller.yaml即可
修改完成之后,在arm_planning/launch中新建文件arm_planning.launch
文件内容如下:
<launch>
<!-- 不使用仿真时间 -->
<param
name="/use_sim_time"
value="false" />
<!-- 启动 arbotix driver-->
<arg
name="sim"
default="true" />
<param
name="robot_description"
textfile="$(find arm)/urdf/inffos_arm.urdf" />
<node
name="arbotix"
pkg="arbotix_python"
type="arbotix_driver"
output="screen">
<rosparam
file="$(find arm)/config/arm.yaml" command="load" />
<param
name="sim"
value="true"/>
</node>
<node
pkg="robot_state_publisher"
type="robot_state_publisher"
name="rob_st_pub" />
<include file="$(find arm_moveit)/launch/move_group.launch" />
<!-- 启动rviz可视化界面 -->
<node
name="rviz"
pkg="rviz"
type="rviz"
args="-d $(find inffos_arm)/urdf.rviz" />
</launch>
在arm_planning/scripts新建python调试文件moveit_fk_demo_arm.py
内容如下:
#!/usr/bin/env python
# -*- coding: utf-8 -*-
import rospy, sys
import moveit_commander
from control_msgs.msg import GripperCommand
class MoveItFkDemo:
def __init__(self):
# 初始化move_group的API
moveit_commander.roscpp_initialize(sys.argv)
# 初始化ROS节点
rospy.init_node('moveit_fk_demo_arm', anonymous=True)
# 初始化需要使用move group控制的机械臂中的arm group
arm = moveit_commander.MoveGroupCommander('arm')
# 设置机械臂和夹爪的允许误差值
arm.set_goal_joint_tolerance(0.1)
# 控制机械臂先回到初始化位置
arm.set_named_target('initial') /此处的initial是setup Assitant中设置robot pose时的名称
arm.go()
rospy.sleep(2)
# 设置机械臂的目标位置,使用si轴的位置数据进行描述(单位:弧度)
joint_positions = [0.5, -0.6, 0.2, 0.8, 0.9, 0.1]
arm.set_joint_value_target(joint_positions)
# 控制机械臂完成运动
arm.go()
rospy.sleep(0.1)
# 关闭并退出moveit
moveit_commander.roscpp_shutdown()
moveit_commander.os._exit(0)
if __name__ == "__main__":
try:
MoveItFkDemo()
except rospy.ROSInterruptException:
pass
然后先后运行上面的launch文件与python文件即可,因模型不同,如果出现规划错误可能是设定的点当前机械臂达不到,所以可是调试位置点后再试
(4)moveit联合arbotix一起做运动规划,逆向运动
首先确认arm_moveit/config/kinematics.yaml内容
初始默认可能为空,添加如下内容:
arm:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.05
kinematics_solver_attempts: 3
如果为空的情况下运行,会报灾难性错误,如下所示:
[ WARN] [1596112458.328783688]: Fail: ABORTED: Catastrophic failure
然后编写python控制代码文件moveit_ik_demo_arm.py 源码如下:
#!/usr/bin/env python
# -*- coding: utf-8 -*-
import rospy, sys
import moveit_commander
from moveit_msgs.msg import RobotTrajectory
from trajectory_msgs.msg import JointTrajectoryPoint
from geometry_msgs.msg import PoseStamped, Pose
from tf.transformations import euler_from_quaternion, quaternion_from_euler
class MoveItIkDemo:
def __init__(self):
# 初始化move_group的API
moveit_commander.roscpp_initialize(sys.argv)
# 初始化ROS节点
rospy.init_node('moveit_ik_demo_inffos_arm')
# 初始化需要使用move group控制的机械臂中的arm group
arm = moveit_commander.MoveGroupCommander('arm')
#
# 获取终端link的名称
end_effector_link = arm.get_end_effector_link()
#end_effector_link = 'Link4'
print(type(end_effector_link))
# 设置目标位置所使用的参考坐标系
reference_frame = 'base_link'
arm.set_pose_reference_frame(reference_frame)
# 当运动规划失败后,允许重新规划
arm.allow_replanning(True)
# 设置位置(单位:米)和姿态(单位:弧度)的允许误差
arm.set_goal_position_tolerance(0.005)
arm.set_goal_orientation_tolerance(0.005)
# 控制机械臂先回到初始化位置
arm.set_named_target('initial')
#arm.set_named_target('work_pose')
arm.go()
rospy.sleep(2)
#
gets_value = arm.get_joint_value_target()
print(gets_value)
print('---------------1--------------')
# 设置机械臂工作空间中的目标位姿,位置使用x、y、z坐标描述,
# 姿态使用四元数描述,基于base_link坐标系
target_pose = PoseStamped()
target_pose.header.frame_id = reference_frame
target_pose.header.stamp = rospy.Time.now()
target_pose.pose.position.x = 0.12
target_pose.pose.position.y = 0.15
target_pose.pose.position.z = 0.4
target_pose.pose.orientation.x = 0
target_pose.pose.orientation.y = 0
target_pose.pose.orientation.z = 0
target_pose.pose.orientation.w = 0
# 设置机器臂当前的状态作为运动初始状态
arm.set_start_state_to_current_state()
print('---------------2--------------')
arm.set_joint_value_target([0,0,0,0,0,0])
arm.go()
rospy.sleep(1)
# 设置机械臂终端运动的目标位姿
xyz = [0,0,0.5]
arm.set_pose_target(target_pose, end_effector_link)
#arm.set_position_target(xyz, end_effector_link)
print('---------------3--------------')
# 规划运动路径
traj = arm.plan()
print('---------------4--------------')
# 按照规划的运动路径控制机械臂运动
arm.execute(traj)
rospy.sleep(1)
print('---------------5--------------')
# 控制机械臂终端向右移动5cm
arm.shift_pose_target(1, -0.1, end_effector_link)
arm.go()
rospy.sleep(1)
print('---------------6--------------')
# 控制机械臂终端反向旋转90度
arm.shift_pose_target(3, -1.57, end_effector_link)
arm.go()
rospy.sleep(1)
print('---------------7--------------')
# 控制机械臂回到初始化位置
#arm.set_named_target('initial_pose')
#arm.go()
# 关闭并退出moveit
moveit_commander.roscpp_shutdown()
moveit_commander.os._exit(0)
if __name__ == "__main__":
MoveItIkDemo()
然后先后运行arm_planning.launch 与moveit_ik_demo_arm.py即可
最后需要说明,三个包中前两个包为自动生成,最后的arm_planning包是自己创建的,然后按照路径放置前文提到的一个launch与python文件。
ROS中package的创建可以自行百度