Open DobbyPeng opened 2 years ago
Hi I'm not from Denso and can't answer your question unfortunately but I am also interested in it. You want to use /bcap_service because it will probably fix the error and also enables you to give the figure as a parameter right?
If you don't use MoveIt, I recommend directly use of bcap library instead of bcap_service node. Here is the sample of moving robot by bcap library: https://github.com/ShoheiKobata/orin_bcap_python_samples/blob/master/SimpleSamples/04_00_Move.py
bcap_service node is the ROS wrapper of bcap library. So both can achieve the same thing. But bcap library has a simple format and less overhead compared to bcap_service node.
I would still use MoveIt for its collision detection. And sometimes I use MoveIt when the end effector needs to move at constant velocity. Can /denso_robot_control and /bcap_service work together?
Can /denso_robot_control and /bcap_service work together?
Yes. But it is need to coordinate taking an arm semaphore and switching slave mode.
Here is a python script using bcap_service. This moves robot to P0 by PTP @0.
import rospy
from bcap_service.msg import variant
from bcap_service.srv import *
def main():
rospy.init_node('robot_move_node', anonymous=True)
bcapSrv = rospy.ServiceProxy('bcap_service', bcap)
# Controller Connect
bcapReq = bcap_service.srv.bcapRequest()
bcapReq.func_id = 3
bcapReq.vntArgs.append(variant(vt=8, value=""))
bcapReq.vntArgs.append(variant(vt=8, value="CaoProv.DENSO.RC8"))
bcapReq.vntArgs.append(variant(vt=8, value="localhost"))
bcapReq.vntArgs.append(variant(vt=8, value=""))
response = bcapSrv(bcapReq)
ctrlHandle = response.vntRet.value
print("Controller Handle:" + ctrlHandle)
# Get Robot
bcapReq = bcap_service.srv.bcapRequest()
bcapReq.func_id = 7
bcapReq.vntArgs.append(variant(vt=3, value=ctrlHandle))
bcapReq.vntArgs.append(variant(vt=8, value=""))
bcapReq.vntArgs.append(variant(vt=8, value=""))
response = bcapSrv(bcapReq)
robotHandle = response.vntRet.value
print("Robot Handle:" + robotHandle)
# Execute Take Arm
bcapReq = bcap_service.srv.bcapRequest()
bcapReq.func_id = 64
bcapReq.vntArgs.append(variant(vt=3, value=robotHandle))
bcapReq.vntArgs.append(variant(vt=8, value="takearm"))
bcapReq.vntArgs.append(variant(vt=8, value=""))
response = bcapSrv(bcapReq)
print("Take Arm")
# Execute Motor ON
bcapReq = bcap_service.srv.bcapRequest()
bcapReq.func_id = 64
bcapReq.vntArgs.append(variant(vt=3, value=robotHandle))
bcapReq.vntArgs.append(variant(vt=8, value="motor"))
bcapReq.vntArgs.append(variant(vt=3, value="1"))
response = bcapSrv(bcapReq)
print("Motor ON")
# Move
bcapReq = bcap_service.srv.bcapRequest()
bcapReq.func_id = 72
bcapReq.vntArgs.append(variant(vt=3, value=robotHandle))
# 1=PTP
bcapReq.vntArgs.append(variant(vt=3, value="1"))
# Pose
bcapReq.vntArgs.append(variant(vt=8, value="@0 P0"))
# Option
bcapReq.vntArgs.append(variant(vt=8, value=""))
response = bcapSrv(bcapReq)
print("Move to P0 by PTP @0")
# Execute GiveArm
bcapReq = bcap_service.srv.bcapRequest()
bcapReq.func_id = 64
bcapReq.vntArgs.append(variant(vt=3, value=robotHandle))
bcapReq.vntArgs.append(variant(vt=8, value="givearm"))
bcapReq.vntArgs.append(variant(vt=8, value=""))
response = bcapSrv(bcapReq)
print("Give Arm")
if __name__ == '__main__':
main()
I have tried something these days.
At step 10, the robot got an error saying that my command was sent too fast. I forget the error code number. I will check it tomorrow.
There are two errors: 83500121 and 84204051 at step 10.
But if I skip step 6, I can change to slave mode successfully and control the robot by MoveIt.
Sorry. I forget to describe my environment. I use Ubuntu 16.04 and ROS Kinetic.
The robot is VM-6083M and the controller is RC8.
Dear @DobbyPeng san, Thank you for using the DENSO Robot. I apologize for this late reply.
rosservice call /bcap_service '{func_id: 72, vntArgs: [{vt: 3, value: "robot handle index"}, {vt: 8, value: "@0 P(x, y, z, rx, ry, rz, fig)"}, {vt: 8, value: "Next"}]}'
You put Next option, but is there any intention?
If the following command is a non-motion command, the non-motion command can be executed simultaneously with the robot motion of the current command.
You send a command "ChangeMove" while executing Move, and I think the error is occurring.
Could you delete Next and execute ChangeMode after the Move is complete.
Next option : https://www.fa-manuals.denso-wave.com/en/usermanuals/000534/
■Errors 83500121:SlvMove command was executed while the Slave mode was not selected. Switch to the Slave mode and then retry. 84204051:J1 command speed limit over. Unexpected error. If the system is set to the Slave mode, confirm that the motion command from the master is correct.
You can check the error here. For the error code, refer to ErrorList.pdf. To view it, you need to register as a member.
Various operations are available with bcapservice. Please refer this documentation in your ORiN installed folder. "C:\ORiN2\CAP\b-CAP\CapLib\DENSO\RC8\Doc\b-CAP_Guide_RC8_en.pdf"
I'm sorry to trouble you, but I appreciate your cooperation. Thank you very much!
I used MoveIt to control the arm before, but I often get 8440454 or 8420404 errors when executing the trajectory planned by MoveIt.
So I want to use the /bcap_service service to move the arm to the specific pose by given [x, y, z, rx, ry, rz, fig]. And set the speed/acceleration of the robot. But I don't know how to set the value of vntArgs.