DOBOT magician魔术师在ROS下使用moveit编写代码控制(笛卡尔空间控制)

55 篇文章 35 订阅
16 篇文章 10 订阅
#include <string>
#include <iostream>
#include <ros/ros.h>
#include <moveit/move_group_interface/move_group_interface.h>

using namespace std;

int main(int argc, char** argv)
{
	//初始化ROS节点
	ros::init(argc, argv,"magician_moveit_ik_demo");

	//开辟一个线程
	ros::AsyncSpinner spinner(1);
	spinner.start();
	
	//初始化需要使用move group控制的机械臂中的arm group
	moveit::planning_interface::MoveGroupInterface arm_magician("magician_arm");

	//获取终端link的名称
	std::string end_effector_link = arm_magician.getEndEffectorLink();
	
	//设置目标位置所使用的参考坐标系
	std::string reference_frame = "magician_origin";
	arm_magician.setPoseReferenceFrame(reference_frame);

	//当运动规划失败后,允许重新规划
	arm_magician.allowReplanning(true);

	//设置位置(单位:米)和姿态(单位:弧度)的允许误差
	arm_magician.setGoalPositionTolerance(0.001);
	arm_magician.setGoalOrientationTolerance(0.01);
	
	//设置允许的最大速度和加速度
	arm_magician.setMaxAccelerationScalingFactor(1);
	arm_magician.setMaxVelocityScalingFactor(1);

	//控制机械臂先回到初始化位置
	arm_magician.setNamedTarget("home");
	arm_magician.move();
	sleep(1);

	// 设置机器人终端的目标位置
	geometry_msgs::Pose target_pose;
	target_pose.orientation.x = 0;
	target_pose.orientation.y = 0;
	target_pose.orientation.z = 0;
	target_pose.orientation.w = 1;

	target_pose.position.x = 0.20242;
	target_pose.position.y = 0.0;
	target_pose.position.z = -0.11736;

	//设置机器臂当前的状态作为运动初始状态
	arm_magician.setStartStateToCurrentState();
	
	arm_magician.setPoseTarget(target_pose);
	
	// 进行运动规划,计算机器人移动到目标的运动轨迹,此时只是计算出轨迹,并不会控制机械臂运动
	moveit::planning_interface::MoveGroupInterface::Plan plan;
	moveit::planning_interface::MoveItErrorCode success = arm_magician.plan(plan);
	
	ROS_INFO("Plan (pose goal) %s", success?"":"FAILED");

	//让机械臂按照规划的轨迹开始运动。
	if(success)
	{
		arm_magician.execute(plan);
		sleep(1);
	}
	
	//控制机械臂先回到初始化位置
	arm_magician.setNamedTarget("home");
	arm_magician.move();
	sleep(1);

	ros::shutdown();

	return 0;
		
}

 

  • 0
    点赞
  • 2
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值