ORiN 2 - Programming in Python 3 (bCAP Packets)

Modified on Wed, 16 Oct at 7:06 PM

Please read our Legal Disclaimer before executing any steps on this article. 


Overview

b-CAP is a communication protocol to access CAO provider and improve the transmission rate. b-CAP has the same service structure as the object of CAO provider. b-CAP is mounted as TCP stream communication. Since b-CAP packet does not contain check code, and error-free protocol is required at the lower-layer protocol.

This article is meant to help to gather information on resources that can help you get started with interfacing with the library to build bCAP packets in Python 3 (bCAPClient). This article is not intended to aid you with programming in Python. 


Tools and Parts needed


NOTE:
The following sample code is provided "AS IS" under the MIT License. Programming support service of Python is out of warranty. Please note that we do not provide any programming support service beyond basic setup and troubleshooting. 


Previous Steps...

Please make sure that you have reviewed the ORiN2 - Overview article and that your RC controller is properly setup. You can use the CAOTester to make sure that your PC is ready to communicate with the controller. 

 


Set up your controller to accept messages from your PC.


ORiN 2 - Robot Controller Setup (RC8 / RC8A / COBOTTA)

Test communication using b-CAP Tester application (Windows OS only)

 

RC7 b-CAP Tester

C:\ORiN2\CAP\b-CAP\CapLib\DENSO\RC7\Bin\b-CAP Tester.exe
 

RC8 (VRC) b-CAP Tester

C:\ORiN2\CAP\b-CAP\CapLib\DENSO\RC8\Bin\b-CAP Tester_RC8.exe

Locate b-CAP Library (bCAPClient.py) for Python


C:\ORiN2\CAP\b-CAP\CapLib\DENSO\RC8\Include\Python 


Programming References

At this point, you should be ready to begin programming your application to interface with your robot controller. When connecting to the controller, you will need to specify the ORiN provider you are trying to use to establish communication. The provider differs based on the robot controller you are using. RC5, RC7, and RC7M controllers use the NetwoRC provider. RC8, RC8A, and COBOTTA controllers us the RC8 provider.

NetwoRC provider directory

C:\ORiN2\CAO\ProviderLib\DENSO\NetwoRC


RC8 provider directory

C:\ORiN2\CAO\ProviderLib\DENSO\RC8


NOTE:
Please consult the Owner's manual for information on how to program your DENSO Robot or details on specific robot commands. 


Programming using the Provider

The following samples are for performing various basic but essential operations. The samples are for connecting using the RC8 Provider.

For more information you can reference Section 4 RC8 Programming Using the Provider from the RC8 Provider User's Guide PDF document

 

Variable Sample

This sample code shows how to read from and write to various the global variable data types from the Global Variable in the controller.  Several global variables (integer, single precision real number, double precision real number, position, and string). 

  • The write value for integer variable I1 will be >> write value = current value + 1
  • The write value for single precision variable F1 and double precision D1 will be >> write value = current value + 1.1
  • The write value for position variable P1 will be >> write value  = P(current x + 1.1, current y + 2.2, current z + 3.3, current rx + 4.4, current ry + 5.5, current rz + 6.6, current fig + 0)
  • The write value for string variable S1 will be >> write value = current text + the word "hoge"

For more information, reference Section 4.1 RC8 controller variable access.


# -*- coding:utf-8 -*-

# Sample program
# read and write value of Global Variables using b-cap
# I(Integer),F(Sigle Precision Real Number),D(Double Precision Real Number),
# P(Position),S(String)

# b-cap lib URL
# https://github.com/DENSORobot/orin_bcap

import pybcapclient.bcapclient as bcapclient

# set IP Address , Port number and Timeout of connected RC8
host = "192.168.0.1"
port = 5007
timeout = 2000

# Connection processing of tcp communication
m_bcapclient = bcapclient.BCAPClient(host, port, timeout)
print("Open Connection")

# start b_cap Service
m_bcapclient.service_start("")
print("Send SERVICE_START packet")


# set Parameter
Name = ""
Provider = "CaoProv.DENSO.VRC"
Machine = "localhost"
Option = ""

# Connect to RC8 (RC8(VRC)provider)
hCtrl = m_bcapclient.controller_connect(Name, Provider, Machine, Option)
print("Connect RC8")

# get I[1] Object Handl
IHandl = 0
IHandl = m_bcapclient.controller_getvariable(hCtrl, "I1", "")
# read value of I[1]
retI = m_bcapclient.variable_getvalue(IHandl)
print("Read Variable I[1] = %d" % retI)
# Generate random value
newval = retI + 1
# write value of I[1]
m_bcapclient.variable_putvalue(IHandl, newval)
print("Write Variable :newval = %d" % newval)
# read value of I[1]
retI = m_bcapclient.variable_getvalue(IHandl)
print("Read Variable I[1] = %d" % retI)

# get F[1] Object Handl
FHandl = 0
FHandl = m_bcapclient.controller_getvariable(hCtrl, "F1", "")
# read value of F[1]
retF = m_bcapclient.variable_getvalue(FHandl)
print("Read Variable F[1] = ", retF)
# Generate random value
newval = retF + 1.1
# write value of F[1]
m_bcapclient.variable_putvalue(FHandl, newval)
print("Write Variable :newval =", newval)
# read value of F[1]
retF = m_bcapclient.variable_getvalue(FHandl)
print("Read Variable F[1] =", retF)

# get D[1] Object Handl
DHandl = 0
DHandl = m_bcapclient.controller_getvariable(hCtrl, "D1", "")
# read value of D[1]
retD = m_bcapclient.variable_getvalue(DHandl)
print("Read Variable D[1] = ", retD)
# Generate random value
newval = retD + 1.1
# write value of D[1]
m_bcapclient.variable_putvalue(DHandl, newval)
print("Write Variable :newval =", newval)
# read value of D[1]
retD = m_bcapclient.variable_getvalue(DHandl)
print("Read Variable D[1] =", retD)

# get P[1] Object Handl
PHandl = 0
PHandl = m_bcapclient.controller_getvariable(hCtrl, "P1", "")
# read value of P[1]
retP = m_bcapclient.variable_getvalue(PHandl)
print("Read Variable P[1] = ", retP)
# Generate random value
newval = [x + y for (x, y) in zip(retP, [1.1, 2.2, 3.3, 4.4, 5.5, 6.6, 0])]
# write value of P[1]
m_bcapclient.variable_putvalue(PHandl, newval)
print("Write Variable :newval =", newval)
# read value of P[1]
retP = m_bcapclient.variable_getvalue(PHandl)
print("Read Variable P[1] =", retP)

# get S[1] Object Handl
SHandl = 0
SHandl = m_bcapclient.controller_getvariable(hCtrl, "S1", "")
# read value of S[1]
retS = m_bcapclient.variable_getvalue(SHandl)
print("Read Variable S[1] = ", retS)
# Generate random value
newval = retS + "hoge"
# write value of S[1]
m_bcapclient.variable_putvalue(SHandl, newval)
print("Write Variable :newval =", newval)
# read value of S[1]
retS = m_bcapclient.variable_getvalue(SHandl)
print("Read Variable S[1] =", retS)

# Disconnect
if(IHandl != 0):
    m_bcapclient.variable_release(IHandl)
    print("Release I[1]")
if(FHandl != 0):
    m_bcapclient.variable_release(FHandl)
    print("Release F[1]")
if(DHandl != 0):
    m_bcapclient.variable_release(DHandl)
    print("Release D[1]")
if(PHandl != 0):
    m_bcapclient.variable_release(PHandl)
    print("Release P[1]")
if(SHandl != 0):
    m_bcapclient.variable_release(SHandl)
    print("Release S[1]")

if(hCtrl != 0):
    m_bcapclient.controller_disconnect(hCtrl)
    print("Release Controller")
# End If
m_bcapclient.service_stop()
print("B-CAP service Stop")

Task Sample

This sample code will start or stop a robot program (Pro1.pcs), also known as tasks, based on the mode value.

Prerequisites:

  • Controller must have a program named Pro1.pcs 
  • Controller must be set to Auto mode
  • Set program variable mode to the desired value.

For more information, reference Section 4.2 Task controller with RC8 controller.

# -*- coding:utf-8 -*-

# Sample program
# Control of task(pro1.pcs) using b-cap

#b-cap Lib URL 
# https://github.com/DENSORobot/orin_bcap

import pybcapclient.bcapclient as bcapclient


### set IP Address , Port number and Timeout of connected RC8
host = "192.168.0.1"
port = 5007
timeout = 2000

### Connection processing of tcp communication
m_bcapclient = bcapclient.BCAPClient(host,port,timeout)
print("Open Connection")

### start b_cap Service
m_bcapclient.service_start("")
print("Send SERVICE_START packet")

### set Parameter
Name = ""
Provider="CaoProv.DENSO.VRC"
Machine = ("localhost")
Option = ("")

### Connect to RC8 (RC8(VRC)provider)
hCtrl = m_bcapclient.controller_connect(Name,Provider,Machine,Option)
print("Connect RC8")
### get task(pro1) Object Handl
HTask = 0
HTask = m_bcapclient.controller_gettask(hCtrl,"Pro1","")

#Start pro1
#mode  1:One cycle execution, 2:Continuous execution, 3:Step forward
mode = 1
hr = m_bcapclient.task_start(HTask,mode,"")

# Disconnect
if(HTask != 0):
    m_bcapclient.task_release(HTask)
    print("Release Pro1")
#End If
if(hCtrl != 0):
    m_bcapclient.controller_disconnect(hCtrl)
    print("Release Controller")
#End If
m_bcapclient.service_stop()
print("B-CAP service Stop")


Robot Motion Sample

This sample code will turn the motor ON or OFF. When the Start Robot button is pressed the robot will Move to position P1 and then to position P2.

Prerequisites:

  • Global variables P10 and P11 must have valid coordinate data
  • Robot state must be set to Auto mode

For more information reference Section 4.3 Robot control with RC8 controller.


# -*- coding:utf-8 -*-

# Send "Move" command to RC8

#b-cap Lib URL 
# https://github.com/DENSORobot/orin_bcap

import pybcapclient.bcapclient as bcapclient

### set IP Address , Port number and Timeout of connected RC8
host = "127.0.0.1"
port = 5007
timeout = 2000

### Connection processing of tcp communication
m_bcapclient = bcapclient.BCAPClient(host,port,timeout)
print("Open Connection")

### start b_cap Service
m_bcapclient.service_start("")
print("Send SERVICE_START packet")

### set Parameter
Name = ""
Provider="CaoProv.DENSO.VRC"
Machine = ("localhost")
Option = ("")

### Connect to RC8 (RC8(VRC)provider)
hCtrl = m_bcapclient.controller_connect(Name,Provider,Machine,Option)
print("Connect RC8")
### get Robot Object Handl
HRobot = m_bcapclient.controller_getrobot(hCtrl,"Arm","")
print("AddRobot")

### TakeArm
Command = "TakeArm"
Param = [0,0]
m_bcapclient.robot_execute(HRobot,Command,Param)
print("TakeArm")

###Motor On
Command = "Motor"
Param = [1,0]
m_bcapclient.robot_execute(HRobot,Command,Param)
print("Motor On")

###set ExtSpeed Speed,Accel,Decel
Command = "ExtSpeed"
Speed = 100
Accel = 100
Decel = 100
Param = [Speed,Accel,Decel]
m_bcapclient.robot_execute(HRobot,Command,Param)
print("ExtSpeed")

### Set Parameters
#Interpolation
Comp=1
#PoseData
Pose = "@P P1"
m_bcapclient.robot_move(HRobot,Comp,Pose,"SPEED=F2,NEXT")
print("Complete Move P,@P P[1]")
Pose = [2,"P","@0"]
m_bcapclient.robot_move(HRobot,Comp,Pose,"")
print("Complete Move P,@0 P[2]")

'''
position_Value = [210.0,0.0,260.0,180.0,0.0,180.0,261]
Pose = [position_Value,"P","@E"]
m_bcapclient.robot_move(HRobot,Comp,Pose,"")
print("Complete Move P,@E P(x,y,z,Rx,Ry,Rz,Fig)")
'''
###Motor Off
Command = "Motor"
Param = [0,0]
m_bcapclient.robot_execute(HRobot,Command,Param)
print("Motor Off")

###Give Arm
Command = "GiveArm"
Param = None
m_bcapclient.robot_execute(HRobot,Command,Param)
print("GiveArm")

#Disconnect
if(HRobot != 0):
    m_bcapclient.robot_release(HRobot)
    print("Release Robot Object")
#End If
if(hCtrl != 0):
    m_bcapclient.controller_disconnect(hCtrl)
    print("Release Controller")
#End If
m_bcapclient.service_stop()
print("B-CAP service Stop")

More samples...

You can find Python on GitHub. Here are some recommendations:


RC8 Provider Samples

Sample NameDirectory Path
Read / Write Single Variables01_00_ReadWrite.py
Read / Write All Variables01_01_ReadWrite.py
Set / Reset IO02_00_IOReadWrite.py
Task03_00_Task.py
Task (loop)03_01_Task.py
Robot Motion04_00_Move.py
Robot Motion (b-CAP Slave)05_00_slvMove.py
3D Mouse Control3DMouse_Control
MasterSlaveMasterSlave
OthersOthers


Owner's Manual Reference

Was this article helpful?

That’s Great!

Thank you for your feedback

Sorry! We couldn't be helpful

Thank you for your feedback

Let us know how can we improve this article!

Select at least one of the reasons
CAPTCHA verification is required.

Feedback sent

We appreciate your effort and will try to fix the article