int main(int argc, char **argv)
{
ros::init(argc, argv, "moveit_magician_pick_demo");
ros::AsyncSpinner spinner(1);
spinner.start();
ros::NodeHandle n;
ros::ServiceClient client;
client = n.serviceClient("/DobotServer/SetEndEffectorSuctionCup");
//设置气泵吸取suck1
magician_hardware::SetEndEffectorSuctionCup suck1;
suck1.request.enableCtrl = 1;
suck1.request.suck =1;
suck1.request.isQueued = true;
//设置气泵关闭suck2
magician_hardware::SetEndEffectorSuctionCup suck2;
suck2.request.enableCtrl = 0;
suck2.request.suck =0;
suck2.request.isQueued = true;
moveit::planning_interface::MoveGroupInterface arm("magician_arm");
//获取终端link的名称
std::string end_effector_link = arm.getEndEffectorLink();
//设置目标位置所使用的参考坐标系
s