Skip to content

Latest commit

 

History

History
198 lines (126 loc) · 9.79 KB

README.md

File metadata and controls

198 lines (126 loc) · 9.79 KB

b-CAP Command Interface Control

The b-CAP command interface allows to control DENSO robots by sending "high-level" commands to the robot controller. Considering robot motion, only the final target point is sent to the DENSO robot controller. Motion planning and trajectory generation are internally managed by the DENSO controller (the final robot trajectory is not exposed to ROS2 nodes). Compared to the ORiN2 command interface, the b-CAP command interface exposes basic functions and methods to the ROS2 nodes.

Please refer to the ORiN2 Programming Manual for details about the available robot commands and their parameters:

Usage

The main launch file that starts the application is in the bcap_service package.

  • COBOTTA robot:
ros2 launch bcap_service bcap_service.launch.py model:=cobotta ip_address:=192.168.0.1
  • NOT COBOTTA robot (e.g. VS-060 robot):
ros2 launch bcap_service bcap_service.launch.py model:=vs060 ip_address:=192.168.0.1

Launch File Details

The main launch file that starts the application is in the bcap_service package:

ros2 launch bcap_service bcap_service.launch.py model:=<robot_model> ip_address:=<robot_ip_address>

The arguments for launch files can be listed using:

ros2 launch bcap_service bcap_service.launch.py --show-args

The most relevant arguments are the following:

  • robot_ip (mandatory) - IP address of the robot
  • conn_type (default: tcp) - type of connection protocol to be used (tcp/udp)
  • port_number (default: 5007) - number of the port that will be used for connection
  • wait_time (default: 0) - time to wait before connecting to the robot controller [s]
  • model (default: "") - the model of the DENSO robot (COBOTTA, VS-060, etc.). In the original DENSO ROS2 stack 2 robot models are already available ( "cobotta" , "vs060")

PLEASE NOTE THAT THE model PARAMETER WILL ALSO SET A NAMESPACE FOR THE bcap_service NODE AND ASSOCIATED TOPICS AND SERVICES !!

Commands Examples

NOTE: following example commands assume that the bcap_service node was launched with model parameter not set (default value: "") !! When setting e.g. model:=cobotta, the name of the topics and services will change from e.g. /bcap_service to /cobotta/bcap_service

Run the following commands in a new Terminal

  • Establish connection with the controller, and get the Controller Object Handle:

    ros2 service call /bcap_service bcap_service_interfaces/srv/Bcap '{func_id: 3, vnt_args: [{vt: 8, value: "b-CAP"}, {vt: 8, value: "CaoProv.DENSO.VRC"}, {vt: 8, value: "localhost"}, {vt: 8, value: ""}] }'

    Output will be (please note the returned controller handle in the response field, "value=`2`"):

    requester: making request: bcap_service_interfaces.srv.Bcap_Request(func_id=3, vnt_args=[bcap_service_interfaces.msg.Variant(vt=8, value='b-CAP'), bcap_service_interfaces.msg.Variant(vt=8, value='CaoProv.DENSO.VRC'), bcap_service_interfaces.msg.Variant(vt=8, value='localhost'), bcap_service_interfaces.msg.Variant(vt=8, value='')])
    
    response:
    bcap_service_interfaces.srv.Bcap_Response(hresult=0, vnt_ret=bcap_service_interfaces.msg.Variant(vt=19, value='2'))
  • Get the list of Robot Objects from the controller (please use the value of the controller handle returned by the previous command, "{vt: 19, value: '2'}"):

    ros2 service call /bcap_service bcap_service_interfaces/srv/Bcap '{func_id: 13, vnt_args: [{vt: 19, value: '2'}, {vt: 8, value: ''}] }'

    Output will be (please note the returned robot identifier in the response field, "value=`Arm0`"):

    waiting for service to become available...
    requester: making request: bcap_service_interfaces.srv.Bcap_Request(func_id=13, vnt_args=[bcap_service_interfaces.msg.Variant(vt=19, value='2'), bcap_service_interfaces.msg.Variant(vt=8, value='None')])
    
    response:
    bcap_service_interfaces.srv.Bcap_Response(hresult=0, vnt_ret=bcap_service_interfaces.msg.Variant(vt=8200, value='Arm0'))
  • Get the Robot Object Handle (please use the values of the controller handle, "{vt: 19, value: '2'}" , and of the robot identifier, "{vt: 8, value: 'Arm0'}" , returned by the previous commands):

    ros2 service call /bcap_service bcap_service_interfaces/srv/Bcap '{func_id: 7, vnt_args: [{vt: 19, value: '2'}, {vt: 8, value: 'Arm0'}, {vt: 8, value: ''}] }'

    Output will be (please note the returned robot handle in the response field, "value=`16`"):

    waiting for service to become available...
    requester: making request: bcap_service_interfaces.srv.Bcap_Request(func_id=7, vnt_args=[bcap_service_interfaces.msg.Variant(vt=19, value='15'), bcap_service_interfaces.msg.Variant(vt=8, value='Arm0'), bcap_service_interfaces.msg.Variant(vt=8, value='None')])
    
    response:
    bcap_service_interfaces.srv.Bcap_Response(hresult=0, vnt_ret=bcap_service_interfaces.msg.Variant(vt=19, value='16'))
  • Call service request for b-CAP command, e.g. "TakeArm" command (please use the value of the robot handle returned by the previous command, "{vt: 19, value: '16'}"):

    ros2 service call /bcap_service bcap_service_interfaces/srv/Bcap '{func_id: 64, vnt_args: [{vt: 19, value: '16'}, {vt: 8, value: 'TakeArm'}, {vt: 8195, value: "0,0"}] }'

    Output will be:

    requester: making request: bcap_service_interfaces.srv.Bcap_Request(func_id=64, vnt_args=[bcap_service_interfaces.msg.Variant(vt=19, value='16'), bcap_service_interfaces.msg.Variant(vt=8, value='TakeArm'), bcap_service_interfaces.msg.Variant(vt=8195, value='0,0')])
    
    response:
    bcap_service_interfaces.srv.Bcap_Response(hresult=0, vnt_ret=bcap_service_interfaces.msg.Variant(vt=0, value=''))
  • Call service request for b-CAP command, e.g. "Motor" ON command (please use the value of the robot handle returned by the previous command, "{vt: 19, value: '16'}"):

    ros2 service call /bcap_service bcap_service_interfaces/srv/Bcap '{func_id: 64, vnt_args: [{vt: 19, value: '16'}, {vt: 8, value: 'Motor'}, {vt: 8195, value: "1,0"}] }'

    Output will be:

    waiting for service to become available...
    requester: making request: bcap_service_interfaces.srv.Bcap_Request(func_id=64, vnt_args=[bcap_service_interfaces.msg.Variant(vt=19, value='16'), bcap_service_interfaces.msg.Variant(vt=8, value='Motor'), bcap_service_interfaces.msg.Variant(vt=8195, value='1,0')])
    
    response:
    bcap_service_interfaces.srv.Bcap_Response(hresult=0, vnt_ret=bcap_service_interfaces.msg.Variant(vt=0, value=''))
  • Call service request for b-CAP command, e.g. "Move" command to position stored in controller's variable P[1] (please use the value of the robot handle returned by the previous command, "{vt: 19, value: '16'}"):

    ros2 service call /bcap_service bcap_service_interfaces/srv/Bcap '{func_id: 72, vnt_args: [{vt: 19, value: '16'}, {vt: 3, value: '1'}, {vt: 8, value: "P1"}, {vt: 8, value: 'SPEED=10'}] }'

    Output will be (please note that the robot will move!!):

    waiting for service to become available...
    requester: making request: bcap_service_interfaces.srv.Bcap_Request(func_id=72, vnt_args=[bcap_service_interfaces.msg.Variant(vt=19, value='16'), bcap_service_interfaces.msg.Variant(vt=3, value='1'), bcap_service_interfaces.msg.Variant(vt=8, value='P1'), bcap_service_interfaces.msg.Variant(vt=8, value='SPEED=10')])
    
    response:
    bcap_service_interfaces.srv.Bcap_Response(hresult=0, vnt_ret=bcap_service_interfaces.msg.Variant(vt=0, value=''))
  • Call service request for b-CAP command, e.g. "HandMoveA" command (please use the value of the controller handle returned by the previous command, "{vt: 19, value: '2'}"):

    NOTE: this command is only available for COBOTTA robot models !!

    ros2 service call /bcap_service bcap_service_interfaces/srv/Bcap '{func_id: 17, vnt_args: [{vt: 19, value: '2'}, {vt: 8, value: "HandMoveA"}, {vt: 8195, value: "30, 100"}] }'

    Output will be (please note that the robot will move!!):

    waiting for service to become available...
    requester: making request: bcap_service_interfaces.srv.Bcap_Request(func_id=17, vnt_args=[bcap_service_interfaces.msg.Variant(vt=19, value='2'), bcap_service_interfaces.msg.Variant(vt=8, value='HandMoveA'), bcap_service_interfaces.msg.Variant(vt=8195, value='30, 100')])
    
    response:
    bcap_service_interfaces.srv.Bcap_Response(hresult=0, vnt_ret=bcap_service_interfaces.msg.Variant(vt=0, value=''))
  • Call service request for b-CAP command, e.g. "Motor" OFF command (please use the value of the robot handle returned by the previous command, "{vt: 19, value: '16'}"):

    ros2 service call /bcap_service bcap_service_interfaces/srv/Bcap '{func_id: 64, vnt_args: [{vt: 19, value: '16'}, {vt: 8, value: 'Motor'}, {vt: 8195, value: "0,0"}] }'

    Output will be:

    waiting for service to become available...
    requester: making request: bcap_service_interfaces.srv.Bcap_Request(func_id=64, vnt_args=[bcap_service_interfaces.msg.Variant(vt=19, value='16'), bcap_service_interfaces.msg.Variant(vt=8, value='Motor'), bcap_service_interfaces.msg.Variant(vt=8195, value='0,0')])
    
    response:
    bcap_service_interfaces.srv.Bcap_Response(hresult=0, vnt_ret=bcap_service_interfaces.msg.Variant(vt=0, value=''))