通過ROS的Node(節點)調用bhand_controller服務實現barrett_hand基本動作控制

簡介:編寫一個node,實現通過該node進行barrett機械手的初始化。bhand_controller提供很多關於機械手操作的服務,如我們可以通過終端運行下面命令:

$ rosservice call /bhand_node/actions "action: 1",實現機械手初始化,恢復到手指初始展開位姿,並進入到ready狀態。本文將初始化等系列操作集成到一個node中,可以實現機械初始化和如開合等基本動作。

效果:運行 rosrun beginner_tutorials bhand_test 後,機械手自動初始化,然後等待3s後手指閉合。

環境:ubuntu 14.04 +indigo.

[正文]

1 獲取調用服務需要的相關信息。通過roslaunch bhand_controller bhand_controller.launch運行barrett機械手控制主節點,通過service list可以查詢到當前節點中服務如下圖所示,本次要用到是/bhand_node/actions服務。

       爲了能夠在測試node中使用該服務,通過rosservice type查詢其服務類型爲bhand_controller/Actions,後文調用該服務是需要引用的一個頭文件來自於這裏。

      此外通過rossrv show指令可以查詢到actions的類型爲int32,wiki barrett頁面事實上沒有說明我們最終調用的action的取值範圍,但示例給的init hand的action爲1,通過rosmsg show bhand_controller/Service可以查詢到相關action的取值,推測調用取值是如文件所示。


2 實現節點對於服務的調用。傳統client.call()調用的步驟如下,

(1)引入所要調用的服務類型的頭文件。

      本文中通過type查詢到的類型爲bhand_controller/Actions,故引入bhand_controller/Actions.h頭文件。

(2)定義NodeHandle,client。並將client定義爲 NodeHandle對象的serviceClient鏈接到的目標服務。其中bhand_node/actions爲service list裏的服務名稱,bhand_controller::Actions爲服務類型。

    client=nh.serviceClient<bhand_controller::Actions>("bhand_node/actions");

(3)通過目標服務類型定義測試服務對象。並根據服務request實現服務對象的數據填充。

    文中已通過rossrv show 知道目標服務只有一個int32參數,所以填充如下。

    bhand_controller::Actions test_action;
    test_action.request.action=1;

(4)將填充好數據的服務對象代入client.call()實現調用。

    client.call()函數調用成功會返回True因此可通過if判讀是否調用成功,文中實現如下:

    if(client.call(test_action))
    {
        ROS_INFO("Init the robotic hand successfully!");
        ......
    }
    else
        ROS_INFO("Failed to Init the robotic hand!");

完整實現程序如下:

#include <ros/ros.h>
#include "bhand_controller/Service.h"
#include "bhand_controller/Actions.h"

int main(int argc,char **argv)
{
    ros::init(argc,argv,"example_srv_bhand");
    ros::NodeHandle nh;
    ros::ServiceClient client;
    client=nh.serviceClient<bhand_controller::Actions>("bhand_node/actions");

    bhand_controller::Actions test_action;
    test_action.request.action=1;

    if(client.call(test_action))
    {
        ROS_INFO("Init the robotic hand successfully!");
        ros::Duration(3).sleep();
        test_action.request.action=2;
        if(client.call(test_action))
            ROS_INFO("Closed the robotic hand successfully!");
        else
            ROS_INFO("Failed to close robotic hand!");
    }
    else
        ROS_INFO("Failed to Init the robotic hand!");

    ros::spinOnce();
    return 0;
}

備註:

1.由於此處引用了bhand_controller/Service.h,因此在test_action.request.action=1初始化是也可以採用下面方案:

 test_action.request.action=bhand_controller::Service::INIT_HAND;

  效果相同。

2.原計劃通過ros::service::call()實現調用,但總是調用不成功,機械手動作執行了但不能打印調用成功信息。調用代碼如下:

    if(ros::service::call("bhand_node/actions",test_action))
        ROS_INFO("Init the robotic hand successfully!");
    else
        ROS_INFO("Failed to call action service!");

懷疑爲第一個參數給的不正確,可能是名稱問題,之前使用該函數名稱使用的base name,此處爲global name,不知道是不是相關,如果有相關研究者知道,還煩請告知,此處該如何調用。


發表評論
所有評論
還沒有人評論,想成為第一個評論的人麼? 請在上方評論欄輸入並且點擊發布.
相關文章