使用越疆科技的M1-B1机器人进行ROS下移动加机械臂加视觉抓取代码

16 篇文章 9 订阅
12 篇文章 3 订阅

使用越疆科技的M1-B1机器人进行ROS下移动加机械臂加视觉抓取代码 

#include "ros/ros.h"
#include "ar_track_alvar_msgs/AlvarMarkers.h"
#include "iostream"
#include "stdio.h"
#include "cv.h"
#include "opencv2/opencv.hpp"
#include "cv_bridge/cv_bridge.h"
#include <unistd.h>
#include <nav_msgs/Odometry.h>
#include <string.h>
#include <move_base_msgs/MoveBaseAction.h>
#include <actionlib/client/simple_action_client.h>
#include <cmath>

#include "std_msgs/String.h"
#include "dobot/SetCmdTimeout.h"
#include "dobot/SetQueuedCmdClear.h"
#include "dobot/SetQueuedCmdStartExec.h"
#include "dobot/SetQueuedCmdForceStopExec.h"
#include "dobot/GetDeviceVersion.h"

#include "dobot/SetEndEffectorParams.h"
#include "dobot/SetPTPJointParams.h"
#include "dobot/SetPTPCoordinateParams.h"
#include "dobot/SetPTPJumpParams.h"
#include "dobot/SetPTPCommonParams.h"
#include "dobot/SetPTPCmd.h"
#include "dobot/SetEndEffectorGripper.h"
#include "dobot/SetHOMECmd.h"
#include "dobot/SetHOMEParams.h"
#include "dobot/SetIODO.h"
#include "dobot/GetAlarmsState.h"
#include "dobot/ClearAllAlarmsState.h"


using namespace std;
using namespace cv;



相机区域
//机械臂拍照点位
float picture_x = 237.633
    , picture_y = 60.6892
    , picture_z = 230.7879
;

//标定像素坐标 3个点
float cam_x1 = 159.387
    , cam_y1 = -21.6633

    , cam_x2 = 34.927
    , cam_y2 = 40.634

    , cam_x3 = 165.001
    , cam_y3 = 81.35
;

//标定机械包坐标 3个点
float rob_x1 = 327.7778
    , rob_y1 = -78.2467

    , rob_x2 = 357.0341
    , rob_y2 = 43.5529
    
    , rob_x3 = 250.8334
    , rob_y3 = -21.1507
;

//标定像素坐标 3个点
Mat A = (Mat_<float>(3,3) <<
	cam_x1, cam_y1, 1,
	cam_x2, cam_y2, 1,
	cam_x3, cam_y3, 1
	); //3×3
	
//标定机械包坐标 3个点
Mat B = (Mat_<float>(3,3) <<
	rob_x1, rob_y1, 1,
	rob_x2, rob_y2, 1,
	rob_x3, rob_y3, 1
	); //3×3

//矩阵参数
Mat X;


//相机得到图像的坐标和ID
int   ar_ID;
float cam_getX;
float cam_getY;
	
//机械臂最后执行的点位
float X_pose;
float Y_pose;
float Z_pose = 155.9403;

//服务注册
ros::ServiceClient client;
ros::ServiceClient clientPTP;
ros::ServiceClient clientIO;

//函数声明
void robot_pose(Mat X);
void setIO(uint8_t address, uint8_t level, bool isQueued, ros::ServiceClient client);
void setPTP(uint8_t ptpMode ,float x, float y, float z, float r, ros::ServiceClient client);
int getState(ros::ServiceClient client);
int ClearState(ros::ServiceClient client);
void sub_ar_callback(const ar_track_alvar_msgs::AlvarMarkers::ConstPtr& msg);

//回调函数获取二维码的位置
void sub_ar_callback(const ar_track_alvar_msgs::AlvarMarkers::ConstPtr& msg)
{
ros::ServiceClient client;
 	cout<<"回调函数获取二维码的位置"	<<endl;
	//if((msg->markers.size() > 0) && (msg->markers[0].id < 30) )
	if(msg->markers.size() > 0 && (msg->markers[0].id < 30) )
	{
	ar_ID = msg->markers[0].id;
	cam_getX = msg->markers[0].pose.pose.position.x*1000;
	cam_getY = msg->markers[0].pose.pose.position.y*1000;

	cout<<"获取二维码的位置"<<endl<<"二维码ID:"<<ar_ID<<endl;
	cout<<"Point position:"<<endl;
	cout<<"cam_getX: "<<cam_getX<<endl;
	cout<<"cam_getY: "<<cam_getY<<endl;
	cout<<"-----------"<<endl;
	} 

	//获取机器人抓取位置
	robot_pose(X);

	
}

//矩阵变换函数(只是开始调用一次,求出矩阵参数X)
Mat solve_equation(Mat A, Mat B)
{
	//矩阵转换公式
	solve(A, B, X, CV_SVD);
	cout<<"矩阵转换完成,参数X:"<<endl<<X<<endl;
	return X;
}

//机器人抓取位置函数
void robot_pose(Mat X)
{
	cout<<"cam_getX"<<cam_getX<<endl;
	cout<<"cam_getY"<<cam_getY<<endl;
	//相机得到图像的坐标来计算机械臂点位
	Mat cam_pose = (Mat_<float>(1,3) << cam_getX, cam_getY, 1);
	//通过矩阵变换得到机器人抓取的物理坐标
	Mat rot_pose = cam_pose*X; 
	
	//机械臂抓取点位输出
	X_pose = rot_pose.at<float>(0);
	Y_pose = rot_pose.at<float>(1);
	cout<<"抓取点位:"<<endl;
	cout<<"X_pose:"<<X_pose<<endl;
	cout<<"Y_pose:"<<Y_pose<<endl;	

	//运行到抓取点位PTP
	setPTP(0 ,X_pose ,Y_pose ,Z_pose ,0 , clientPTP);

	//开启气泵setIO	
	setIO(18,0,1,clientIO);
	setIO(17,1,1,clientIO);

	//运行到拍照点位PTP
	setPTP(0 ,picture_x ,picture_y ,picture_z ,0 , clientPTP);

	//关闭气泵setIO	
	//setIO(18,1,1,clientIO);
	//setIO(17,1,1,clientIO);
		
}
相机区域
/机械臂区域


//清除系统所有报警
int ClearState(ros::ServiceClient client) 
{
	dobot::ClearAllAlarmsState srv;
	client.call(srv);
}

//获取系统报警状态
int getState(ros::ServiceClient client)
{
	dobot::GetAlarmsState srv;
	client.call(srv);
	cout<<"State result: "<<srv.response.result<<endl;
	cout<<"size_alarmsState:"<<srv.response.alarmsState.size()<<endl;
	for(int i = 0; i<srv.response.alarmsState.size(); i++)
	{
		cout<<srv.response.alarmsState[i];
	}
	cout<<"end  "<<endl;
	//cout<<"State alarmsState: "<<srv.response.alarmsState[0]<<endl;
}

//执行 PTP 指令
void setPTP(uint8_t ptpMode ,float x, float y, float z, float r, ros::ServiceClient client)
{
	dobot::SetPTPCmd srv;
	srv.request.ptpMode = ptpMode;
        srv.request.x = x;
        srv.request.y = y;
        srv.request.z = z;
        srv.request.r = r;
        client.call(srv);   
}

//设置 I/O 输出电平
void setIO(uint8_t address, uint8_t level, bool isQueued, ros::ServiceClient client)
{
	dobot::SetIODO IO;
	IO.request.address = address;
	IO.request.level = level;
	IO.request.isQueued = isQueued;
	client.call(IO);
	ROS_INFO("SetIODO%d ok, %d", IO.request.address , IO.response.queuedCmdIndex);
}
/机械臂区域

//调用拍照和机械臂抓取部分
void cam_pick()
{
	ros::Rate loop_rate(0.5);
	int i = 1;
	while(i >= 0 && ros::ok())
	{
		ros::spinOnce();
		i = i-1;
		cout<<"call :"<<i<<endl;
		loop_rate.sleep();
	}	
}

//机械臂放置物料函数
void robot_place()
{
	//关闭气泵setIO	
	setIO(18,1,1,clientIO);
	setIO(17,1,1,clientIO);
		
}

int main(int argc, char** argv)
{
	ros::init(argc, argv, "cam_robot_sent_pose");
	ros::NodeHandle n;

	//订阅move_base操作服务器
	actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> ac("move_base",true);

	//设置我们要机器人走的几个点。
	geometry_msgs::Point point;
	geometry_msgs::Quaternion quaternion;
	geometry_msgs::Pose pose_list1;
	geometry_msgs::Pose pose_list2;
	
	point.x = -0.174;
	point.y = -0.921;
	point.z = 0.000;
	quaternion.x = 0.000;
	quaternion.y = 0.000;
	quaternion.z = -0.728;
	quaternion.w = 0.684;
	pose_list1.position = point;
	pose_list1.orientation = quaternion;
	
	point.x = 1.842;
	point.y = 0.893;
	point.z = 0.000;
	quaternion.x = 0.000;
	quaternion.y = 0.000;
	quaternion.z = -0.0331;
	quaternion.w = 0.999;
	pose_list2.position = point;
	pose_list2.orientation = quaternion;


    // SetCmdTimeout
    client = n.serviceClient<dobot::SetCmdTimeout>("/DobotServer/SetCmdTimeout");
    dobot::SetCmdTimeout srv1;
    srv1.request.timeout = 3000;
    if (client.call(srv1) == false) {
        ROS_ERROR("Failed to call SetCmdTimeout. Maybe DobotServer isn't started yet!");
        return -1;
    }

    // Clear the command queue
    client = n.serviceClient<dobot::SetQueuedCmdClear>("/DobotServer/SetQueuedCmdClear");
    dobot::SetQueuedCmdClear srv2;
    client.call(srv2);

    // Start running the command queue
    client = n.serviceClient<dobot::SetQueuedCmdStartExec>("/DobotServer/SetQueuedCmdStartExec");
    dobot::SetQueuedCmdStartExec srv3;
    client.call(srv3);

    // Get device version information
    client = n.serviceClient<dobot::GetDeviceVersion>("/DobotServer/GetDeviceVersion");
    dobot::GetDeviceVersion srv4;
    client.call(srv4);
    if (srv4.response.result == 0) {
        ROS_INFO("Device version:%d.%d.%d", srv4.response.majorVersion, srv4.response.minorVersion, srv4.response.revision);
    } else {
        ROS_ERROR("Failed to get device version information!");
    }

    // Set PTP joint parameters
    do {
        client = n.serviceClient<dobot::SetPTPJointParams>("/DobotServer/SetPTPJointParams");
        dobot::SetPTPJointParams srv;

        for (int i = 0; i < 4; i++) {
            srv.request.velocity.push_back(100);
        }
        for (int i = 0; i < 4; i++) {
            srv.request.acceleration.push_back(100);
        }
        client.call(srv);
    } while (0);

    // Set PTP coordinate parameters
    do {
        client = n.serviceClient<dobot::SetPTPCoordinateParams>("/DobotServer/SetPTPCoordinateParams");
        dobot::SetPTPCoordinateParams srv;

        srv.request.xyzVelocity = 100;
        srv.request.xyzAcceleration = 100;
        srv.request.rVelocity = 100;
        srv.request.rAcceleration = 100;
        client.call(srv);
    } while (0);

    // Set PTP jump parameters
    do {
        client = n.serviceClient<dobot::SetPTPJumpParams>("/DobotServer/SetPTPJumpParams");
        dobot::SetPTPJumpParams srv;

        srv.request.jumpHeight = 20;
        srv.request.zLimit = 200;
        client.call(srv);
    } while (0);

    // Set PTP common parameters
    do {
        client = n.serviceClient<dobot::SetPTPCommonParams>("/DobotServer/SetPTPCommonParams");
        dobot::SetPTPCommonParams srv;

        srv.request.velocityRatio = 50;
        srv.request.accelerationRatio = 50;
        client.call(srv);
    } while (0);


	//运行到拍照点位PTP
	client = n.serviceClient<dobot::SetPTPCmd>("/DobotServer/SetPTPCmd");
	setPTP(0 ,picture_x ,picture_y ,picture_z ,0 , client);
	//运行到抓取点位PTP
	clientPTP = n.serviceClient<dobot::SetPTPCmd>("/DobotServer/SetPTPCmd");
	//开启气泵setIO	
	clientIO = n.serviceClient<dobot::SetIODO>("/DobotServer/SetIODO");


	cout<<"机械臂准备完成请按下空格键开始检测"<<endl;
	getchar();

	//矩阵变换函数
	solve_equation(A, B);
	cout<<"sub"<<endl;


///导航开始部分
 	ROS_INFO("Waiting for move_base action server...");
  	//等待60秒以使操作服务器可用
  	if(!ac.waitForServer(ros::Duration(60)))
  	{
   	 	ROS_INFO("Can't connected to move base server");
		exit(-1);
 	 }
 	 ROS_INFO("Connected to move base server");
 	 ROS_INFO("Starting navigation test");

         //初始化航点目标 去抓取点
         move_base_msgs::MoveBaseGoal goal1;

         //使用地图框定义目标姿势
         goal1.target_pose.header.frame_id = "map";

         //将时间戳设置为“now”
         goal1.target_pose.header.stamp = ros::Time::now();

        //将目标姿势设置为第i个航点
        goal1.target_pose.pose = pose_list1;

        //让机器人向目标移动
        //将目标姿势发送到MoveBaseAction服务器
        ac.sendGoal(goal1);

        //等3分钟到达那里
        bool finished_within_time1 = ac.waitForResult(ros::Duration(180));

        //如果我们没有及时赶到那里,就会中止目标
        if(!finished_within_time1)
        {
            ac.cancelGoal();
            ROS_INFO("Timed out achieving goal");
        }
	else
        {
            //We made it!
            if(ac.getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
            {
                ROS_INFO("Goal A succeeded!");
		ROS_INFO("send socket succeeded!");
		sleep(3);
		//订阅相机获取二维码的位置
		ros::Subscriber sub = n.subscribe("/ar_pose_marker", 1, sub_ar_callback);
		//调用拍照和机械臂抓取部分
		cam_pick();
            }
            else
            {
                ROS_INFO("The base failed for some reason");
            }
        }


        //初始化航点目标 去放置点
        move_base_msgs::MoveBaseGoal goal2;

        //使用地图框定义目标姿势
        goal2.target_pose.header.frame_id = "map";

        //将时间戳设置为“now”
        goal2.target_pose.header.stamp = ros::Time::now();

        //将目标姿势设置为第i个航点
        goal2.target_pose.pose = pose_list2;

        //让机器人向目标移动
        //将目标姿势发送到MoveBaseAction服务器
        ac.sendGoal(goal2);

        //等3分钟到达那里
        bool finished_within_time2 = ac.waitForResult(ros::Duration(180));

        //如果我们没有及时赶到那里,就会中止目标
        if(!finished_within_time2)
        {
            ac.cancelGoal();
            ROS_INFO("Timed out achieving goal");
        }
	else
        {
            //We made it!
            if(ac.getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
            {
                ROS_INFO("Goal B succeeded!");
		robot_place();
		sleep(3);
            }
            else
            {
                ROS_INFO("The base failed for some reason");
            }
        }


	return 0;

}

 

  • 2
    点赞
  • 24
    收藏
    觉得还不错? 一键收藏
  • 4
    评论
ROS机械臂视觉抓取是通过ROS机器人操作系统)实现带有机械臂移动机器人进行物体抓取的过程。这可以通过使用开源的ROS软件包来实现,例如提到的move_and_grasp软件包。 在机械臂完成视觉抓取任务的过程中,通常会有以下几个步骤: 1. 首先,机械臂处于使能但未运动的状态,准备执行抓取任务。这个初始状态可以在图4.6(a)中示意图中看到。 2. 然后,机械臂移动到适合深度相机拍摄清晰图像的抓取姿态。这个过程可以在图4.6(b)中看到。 3. 接下来,机械臂使用视觉识别技术来检测并识别目标物体。在这个例子中,机械臂会识别红色长方体作为目标物体。 4. 一旦目标物体被识别出来,机械臂会执行抓取操作,将目标物体抓取起来。这一步骤在图4.6(c)中展示出来。 5. 最后,机械臂会将目标物体放置到预设的码垛区,完成抓取任务。这个过程可以在图4.6(d)中看到。 总之,ROS机械臂视觉抓取是通过使用ROS和相关软件包实现机械臂进行物体抓取的过程,包括姿态规划、视觉识别和抓取动作执行等步骤。<span class="em">1</span><span class="em">2</span><span class="em">3</span> #### 引用[.reference_title] - *1* *3* [【Ubuntu&ROS】干货!小伙伴们快来拿,超全机械臂抓取开源项目!](https://blog.csdn.net/weixin_45087775/article/details/105587752)[target="_blank" data-report-click={"spm":"1018.2226.3001.9630","extra":{"utm_source":"vip_chatgpt_common_search_pc_result","utm_medium":"distribute.pc_search_result.none-task-cask-2~all~insert_cask~default-1-null.142^v93^chatsearchT3_2"}}] [.reference_item style="max-width: 50%"] - *2* [基于机器视觉ROS机械臂抓取实验](https://blog.csdn.net/Yong_Qi2015/article/details/128310565)[target="_blank" data-report-click={"spm":"1018.2226.3001.9630","extra":{"utm_source":"vip_chatgpt_common_search_pc_result","utm_medium":"distribute.pc_search_result.none-task-cask-2~all~insert_cask~default-1-null.142^v93^chatsearchT3_2"}}] [.reference_item style="max-width: 50%"] [ .reference_list ]

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

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

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值