笔者工作环境:
ros-kinetic
universal_robot功能包
在进行此工作之前,我相信读者可以通过运行demo程序,在rviz-moveit中可以通过拖动机械臂的末端简单实现机器人的控制,然而我们在控制机械臂运动的时候大都是通过编程的方式控制,而不是Rviz的图形化控制。
本教程以ur3机械臂模型为例,首先看一下 正向运动学规划的例程,正向运动学规划简单的说就是直接给机械臂提供所有关节的目标角度从而实现的机械臂运动。
创建工作空间和拷贝universal_robot功能包不在赘述,参考我其他的博文。
ros-新建ros工作空间与环境变量配置
ros+ur机械臂+robotiq ft300+onrobot rg2+gazebo+rviz联合仿真
这里将universal_robot功能包的地址放在这里。
https://github.com/ros-industrial/universal_robot.git
编译成功后已经完成了第一步工作,此时src下应该有这样功能包。
可以参考我的另一篇博客
ros创建工作空间和功能包
在src文件夹目录下打开终端,输入:
catkin_create_pkg test_ur
注:因为创建的功能包没有添加依赖,所以后边只跟了功能包的名字。
然后再进行编译
cd ..
catkin_make
在test_ur文件目录下创建空的Python程序,打开终端输入:
touch moveit_cartesian_demo.py
将代码拷贝到Python程序中去。
注:本例程中,无论机械臂在什么位置,都将先初始化到home中的位置,然后在运行。这一点可以通过读代码看到。
#!/usr/bin/env python
# -*- coding: utf-8 -*-
import rospy, sys
import moveit_commander
from moveit_commander import MoveGroupCommander
from geometry_msgs.msg import Pose
from copy import deepcopy
class MoveItCartesianDemo:
def __init__(self):
# 初始化move_group的API
moveit_commander.roscpp_initialize(sys.argv)
# 初始化ROS节点
rospy.init_node('moveit_cartesian_demo', anonymous=True)
# 是否需要使用笛卡尔空间的运动规划,获取参数,如果没有设置,则默认为True,即走直线
cartesian = rospy.get_param('~cartesian', True)
# 初始化需要使用move group控制的机械臂中的arm group
arm = MoveGroupCommander('manipulator')
# 当运动规划失败后,允许重新规划
arm.allow_replanning(True)
# 设置目标位置所使用的参考坐标系
arm.set_pose_reference_frame('base_link')
# 设置位置(单位:米)和姿态(单位:弧度)的允许误差
arm.set_goal_position_tolerance(0.001)
arm.set_goal_orientation_tolerance(0.001)
# 设置允许的最大速度和加速度
arm.set_max_acceleration_scaling_factor(0.5)
arm.set_max_velocity_scaling_factor(0.5)
# 获取终端link的名称
end_effector_link = arm.get_end_effector_link()
# 控制机械臂先回到初始化位置
arm.set_named_target('home')
arm.go()
rospy.sleep(1)
# 获取当前位姿数据最为机械臂运动的起始位姿
start_pose = arm.get_current_pose(end_effector_link).pose
# 初始化路点列表
waypoints = []
# 如果为True,将初始位姿加入路点列表
if cartesian:
waypoints.append(start_pose)
# 设置路点数据,并加入路点列表,所有的点都加入
wpose = deepcopy(start_pose)#拷贝对象
wpose.position.z -= 0.2
if cartesian: #如果设置为True,那么走直线
waypoints.append(deepcopy(wpose))
else: #否则就走曲线
arm.set_pose_target(wpose) #自由曲线
arm.go()
rospy.sleep(1)
wpose.position.x += 0.15
if cartesian:
waypoints.append(deepcopy(wpose))
else:
arm.set_pose_target(wpose)
arm.go()
rospy.sleep(1)
wpose.position.y += 0.1
if cartesian:
waypoints.append(deepcopy(wpose))
else:
arm.set_pose_target(wpose)
arm.go()
rospy.sleep(1)
wpose.position.x -= 0.15
wpose.position.y -= 0.1
if cartesian:
waypoints.append(deepcopy(wpose))
else:
arm.set_pose_target(wpose)
arm.go()
rospy.sleep(1)
#规划过程
if cartesian:
fraction = 0.0 #路径规划覆盖率
maxtries = 100 #最大尝试规划次数
attempts = 0 #已经尝试规划次数
# 设置机器臂当前的状态作为运动初始状态
arm.set_start_state_to_current_state()
# 尝试规划一条笛卡尔空间下的路径,依次通过所有路点
while fraction < 1.0 and attempts < maxtries:
#规划路径 ,fraction返回1代表规划成功
(plan, fraction) = arm.compute_cartesian_path (
waypoints, # waypoint poses,路点列表,这里是5个点
0.01, # eef_step,终端步进值,每隔0.01m计算一次逆解判断能否可达
0.0, # jump_threshold,跳跃阈值,设置为0代表不允许跳跃
True) # avoid_collisions,避障规划
# 尝试次数累加
attempts += 1
# 打印运动规划进程
if attempts % 10 == 0:
rospy.loginfo("Still trying after " + str(attempts) + " attempts...")
# 如果路径规划成功(覆盖率100%),则开始控制机械臂运动
if fraction == 1.0:
rospy.loginfo("Path computed successfully. Moving the arm.")
arm.execute(plan)
rospy.loginfo("Path execution complete.")
# 如果路径规划失败,则打印失败信息
else:
rospy.loginfo("Path planning failed with only " + str(fraction) + " success after " + str(maxtries) + " attempts.")
rospy.sleep(1)
# 控制机械臂先回到初始化位置
arm.set_named_target('home')
arm.go()
rospy.sleep(1)
# 关闭并退出moveit
moveit_commander.roscpp_shutdown()
moveit_commander.os._exit(0)
if __name__ == "__main__":
try:
MoveItCartesianDemo()
except rospy.ROSInterruptException:
pass
保存文件并右击属性,将文件权限改为可执行程序
此时我们已经完成了代码创建工作。
然后再返回src文件夹目录下编译一次。
在第一个终端输入一下代码启动demo.launch。
roslaunch ur3_moveit_config demo.launch
在第二个终端输入以下代码启动我们刚刚创建的Python程序。
rosrun test_ur moveit_cartesian_demo.py
这时候我们看到在demo中的机械臂可以运动了,沿着直线运动。
在进行编译和运行Python程序过程中遇到很多问题,我都将放到我的博客里了,可以看一下。
rosrun命令运行Python找不到可执行文件https://blog.csdn.net/weixin_45839124/article/details/106793803
rosrun运行Python程序提示有语法错误问题(一)https://blog.csdn.net/weixin_45839124/article/details/106794474
rosrun运行Python程序报错SyntaxError(二)https://blog.csdn.net/weixin_45839124/article/details/106797739
本文参考链接:
MoveIt编程实现关节空间机械臂运动(正运动学)https://blog.csdn.net/zzu_seu/article/details/90611186