前两篇文章是关于在关节空间中进行机械臂的运动控制: MoveIt简单编程实现关节空间机械臂运动(逆运动学) MoveIt简单编程实现关节空间机械臂运动(正运动学) 通过对关节空间下的机器人6个轴进行控制,每个轴的变化都是通过插补进行完成运动,六个轴互相不会关心其他轴是如何运动的,机器人轴端在两个点之间走出的轨迹是任意的曲线。 但是对于一些任务重,要求机械臂终端轨迹的形状是直线或者圆弧等,即对轨迹的形状是有要求的,这个时候就要使用笛卡尔孔家,增加笛卡尔路径约束。 首先使用以下命令,看一下执行的效果:  
roslaunch probot_anno_moveit_config demo.launch
  走直线:  
rosrun probot_demo moveit_cartesian_demo.py _cartesian:=True
  自由曲线:  
rosrun probot_demo moveit_cartesian_demo.py _cartesian:=False
  效果: 直线:   1     2 任意曲线   Python代码以及解析:  
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
 
  1. 获取参数,使用 rospy.get_param(param_name)
 
# 获取全局参数
rospy.get_param('/global_param_name')
 
# 获取目前命名空间的参数
rospy.get_param('param_name')
 
# 获取私有命名空间参数
rospy.get_param('~private_param_name')
 
# 获取参数,如果没,使用默认值
rospy.get_param('foo', 'default_value')
  2.路径规划API,(plan, fraction) = arm.compute_cartesian_path 返回值:
  • plan:规划出来的运动轨迹
  • fraction:描述规划成功的轨迹在给定路径点列表的覆盖率【0~1】。如果fraction小于1,说明给定的路径点列表没有办法完整规划
C++代码解析:  
#include <ros/ros.h>
#include <moveit/move_group_interface/move_group_interface.h>
#include <moveit/robot_trajectory/robot_trajectory.h>
 
int main(int argc, char **argv)
{
    //初始化节点
	ros::init(argc, argv, "moveit_cartesian_demo");
    //引入多线程
	ros::AsyncSpinner spinner(1);
    //开启多线程
	spinner.start();
 
    //初始化需要使用move group控制的机械臂中的arm group
    moveit::planning_interface::MoveGroupInterface arm("manipulator");
 
    //获取终端link的名称
    std::string end_effector_link = arm.getEndEffectorLink();
 
    //设置目标位置所使用的参考坐标系
    std::string reference_frame = "base_link";
    arm.setPoseReferenceFrame(reference_frame);
 
    //当运动规划失败后,允许重新规划
    arm.allowReplanning(true);
 
    //设置位置(单位:米)和姿态(单位:弧度)的允许误差
    arm.setGoalPositionTolerance(0.001);
    arm.setGoalOrientationTolerance(0.01);
 
    //设置允许的最大速度和加速度
    arm.setMaxAccelerationScalingFactor(0.5);
    arm.setMaxVelocityScalingFactor(0.5);
 
    // 控制机械臂先回到初始化位置
    arm.setNamedTarget("home");
    arm.move(); //规划+移动
    sleep(1);  //停1s
 
    // 获取当前位姿数据最为机械臂运动的起始位姿
    geometry_msgs::Pose start_pose = arm.getCurrentPose(end_effector_link).pose;
 
    //初始化路径点向量
	std::vector<geometry_msgs::Pose> waypoints;
 
    //将初始位姿加入路点列表
	waypoints.push_back(start_pose);
	
    start_pose.position.z -= 0.2;
	waypoints.push_back(start_pose);
 
    start_pose.position.x += 0.1;
	waypoints.push_back(start_pose);
 
    start_pose.position.y += 0.1;
	waypoints.push_back(start_pose);
 
	// 笛卡尔空间下的路径规划
	moveit_msgs::RobotTrajectory trajectory;
	const double jump_threshold = 0.0;
	const double eef_step = 0.01;
	double fraction = 0.0;
    int maxtries = 100;   //最大尝试规划次数
    int attempts = 0;     //已经尝试规划次数
 
    while(fraction < 1.0 && attempts < maxtries)
    {
        fraction = arm.computeCartesianPath(waypoints, eef_step, jump_threshold, trajectory);
        attempts++;
        
        if(attempts % 10 == 0)
            ROS_INFO("Still trying after %d attempts...", attempts);
    }
    
    if(fraction == 1)
    {   
        ROS_INFO("Path computed successfully. Moving the arm.");
 
	    // 生成机械臂的运动规划数据
	    moveit::planning_interface::MoveGroupInterface::Plan plan;
	    plan.trajectory_ = trajectory;
 
	    // 执行运动
	    arm.execute(plan);
        sleep(1);
    }
    else
    {
        ROS_INFO("Path planning failed with only %0.6f success after %d attempts.", fraction, maxtries);
    }
 
    // 控制机械臂先回到初始化位置
    arm.setNamedTarget("home");
    arm.move();
    sleep(1);
 
	ros::shutdown(); 
	return 0;
}