在ROS下控制越疆科技dobot(magician)机械手的夹抓

代码:

#include "ros/ros.h"
#include "ros/console.h"
#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 <unistd.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"
 
int main(int argc, char **argv)
{
    ros::init(argc, argv, "DobotClient");
    ros::NodeHandle n;
 
    ros::ServiceClient client;
 
    // 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 end effector parameters
    client = n.serviceClient<dobot::SetEndEffectorParams>("/DobotServer/SetEndEffectorParams");
    dobot::SetEndEffectorParams srv5;
    srv5.request.xBias = 70;
    srv5.request.yBias = 0;
    srv5.request.zBias = 0;
    client.call(srv5);
 
    // 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);
 
    
    do{
        client = n.serviceClient<dobot::SetHOMEParams>("/DobotServer/SetHOMEParams"); // The client is using the nodehandler 
                                                                                      // to access the advertised service SetHOMEParams 
                                                                                      // within the DobotServer.
        dobot::SetHOMEParams home; // Sets the position of the home.
        home.request.x = 200; // Setting the x coordinate through a client request.
        home.request.y = 0; // Setting the x coordinate through a client request.
        home.request.z = 0; // Setting the x coordinate through a client request.
        home.request.r = 0; // Setting the x coordinate through a client request.
        home.request.isQueued = 1; // Enabling the queue through a client request.
        client.call(home); // Calls the service with all the requests made but won't be performed until a spin is called.
 
    } while(0);
 
    do{
        client = n.serviceClient<dobot::SetHOMECmd>("/DobotServer/SetHOMECmd");
        dobot::SetHOMECmd home1; // SetHomeCmd needs to be called after SetHOMEParams otherwise the magician will not move to the user defined positions.
        client.call(home1);
    } while(0);
    ros::spinOnce(); // All the callbacks will be called from spinOnce() 
 
    client = n.serviceClient<dobot::SetPTPCmd>("/DobotServer/SetPTPCmd");
    dobot::SetPTPCmd srv;    
    // The first point
    do{
        srv.request.ptpMode = 1;
        srv.request.x = 200;
        srv.request.y = 0;
        srv.request.z = 0;
        srv.request.r = 0;
        client.call(srv);
    } while(0);
 
    do{
        srv.request.ptpMode = 1;
        srv.request.x = 250;
        srv.request.y = 0;
        srv.request.z = 0;
        srv.request.r = 0;
        client.call(srv);
    } while(0);
 
    do{
        srv.request.ptpMode = 1;
        srv.request.x = 250;
        srv.request.y = -30;
        srv.request.z = 0;
        srv.request.r = 0;
        client.call(srv);
    } while(0);
    
 
    client = n.serviceClient<dobot::SetEndEffectorGripper>("/DobotServer/SetEndEffectorGripper");
    dobot::SetEndEffectorGripper grp1;
    // Pick up
    do{
        grp1.request.enableCtrl = 1; // When the enableCtrl == 1 the motor will operate.
        grp1.request.grip = 1; // When grip == 1 the gripper will close. 
        grp1.request.isQueued = true; // This command puts the request in the queue.
        client.call(grp1);
    } while(0);
 
    client = n.serviceClient<dobot::SetPTPCmd>("/DobotServer/SetPTPCmd");
    dobot::SetPTPCmd srv6;
    do{
        srv6.request.ptpMode = 1;
        srv6.request.x = 250;
        srv6.request.y = 0;
        srv6.request.z = 0;
        srv6.request.r = 0;
        client.call(srv6);
    } while(0);
 
    do{
        srv6.request.ptpMode = 1;
        srv6.request.x = 250;
        srv6.request.y = 50;
        srv6.request.z = 0;
        srv6.request.r = 0;
        client.call(srv6);
    }while(0);
 
    do{
        srv6.request.ptpMode = 1;
        srv6.request.x = 250;
        srv6.request.y = 50;
        srv6.request.z = -30;
        srv6.request.r = 0;
        client.call(srv6);
    }while(0);
 
 
    client = n.serviceClient<dobot::SetEndEffectorGripper>("/DobotServer/SetEndEffectorGripper");
    dobot::SetEndEffectorGripper grp2;
    // Drop object  
    do{   
        grp2.request.grip = 0; // Release grip.
        grp2.request.enableCtrl = 1;
        grp2.request.isQueued = true;
        client.call(grp2);
    } while(0);
 
    client = n.serviceClient<dobot::SetPTPCmd>("/DobotServer/SetPTPCmd");
    dobot::SetPTPCmd srv7;
 
    do{
        srv7.request.ptpMode = 1;
        srv7.request.x = 250;
        srv7.request.y = 50;
        srv7.request.z = 0;
        srv7.request.r = 0;
        client.call(srv7);
    } while(0);
 
    do{
        srv7.request.ptpMode = 1;
        srv7.request.x = 250;
        srv7.request.y = 0;
        srv7.request.z = 0;
        srv7.request.r = 0;
        client.call(srv7);
    } while(0);    
 
    client = n.serviceClient<dobot::SetEndEffectorGripper>("/DobotServer/SetEndEffectorGripper");
    dobot::SetEndEffectorGripper grp3;
    // Turn off motor
    do{    
        grp3.request.grip = 0;
        grp3.request.enableCtrl = 0; // Turn off the power. 
        grp3.request.isQueued = true;
        client.call(grp3);
    } while(0);
    ros::spinOnce();
    
 
    return 0;
}