经过两天的研究,终于实现了magician机械臂夹爪的张开与闭合(在ubuntu20.04环境下),记录一下。
在此,感谢一下梦豪学长对我的帮助
话不多说,下面是代码:
#include "ros/ros.h"
#include "ros/console.h"
#include "dobot/SetEndEffectorGripper.h"
// 1 张开 0闭合
dobot::SetEndEffectorGripper gripflag(int n)
{
dobot::SetEndEffectorGripper srv;
if (n == 1) // 张开
{
srv.request.enableCtrl = 1;
srv.request.grip = 0;
srv.request.isQueued = 1;
}
else if (n == 0) // 闭合
{
srv.request.enableCtrl = 1;
srv.request.grip = 1;
srv.request.isQueued = 1;
}
else
{
srv.request.enableCtrl = 0;
srv.request.grip = 0;
srv.request.isQueued = 0;
}
return srv;
}
int main(int argc, char **argv)
{
setlocale(LC_ALL, "");
ros::init(argc, argv, "DobotGripperClient");
ros::NodeHandle n;
ros::ServiceClient client;
// 设置夹爪开闭服务
client = n.serviceClient<dobot::SetEndEffectorGripper>("/DobotServer/SetEndEffectorGripper");
// 闭合
auto srv = gripflag(0);
// 张开
auto srv1 = gripflag(1);
if (client.call(srv1))
{
if (srv.response.result == 0)
{
ROS_INFO("夹爪已张开");
}
else
{
ROS_INFO("夹爪已张开");
}
}
else
{
ROS_ERROR("Failed to call SetEndEffectorGripper service");
return -1;
}
// 等待一段时间
ros::Duration(2.0).sleep();
if (client.call(srv))
{
if (srv.response.result == 0)
{
ROS_INFO("夹爪已闭合");
}
else
{
ROS_INFO("夹爪未能闭合");
}
}
else
{
ROS_ERROR("Failed to call SetEndEffectorGripper service");
return -1;
}
// 等待一段时间
ros::Duration(2.0).sleep();
//关闭控制器
auto close = gripflag(2);
client.call(close);
ROS_INFO("资源已释放");
ros::shutdown();
return 0;
}
实际效果如下:
magician机械臂夹爪张开与闭合