Closed zhoubo2018 closed 5 years ago
Sorry for the late reply.
We are now considering the architecture to control the gripper including 3D model.
Although it's not a smart way, currently you can control the gripper by the following steps:
ubuntu@roslaunch denso_robot_bringup <launch file of COBOTTA> sim:=false ip_address:=<COBOTTA's IP Address>
ubuntu@roslaunch bcap_service bcap_service.launch ip_address:=<COBOTTA's IP Address>
ubuntu@rosservice call /bcap_service '{func_id: 3, vntArgs: [{vt: 8, value: "b-CAP"}, {vt: 8, value: "CaoProv.DENSO.VRC"}, {vt: 8, value: "localhost"}, {vt: 8, value: ""}] }
And then you receive the controller handle as return value.
HRESULT: 0 vntRet: vt: 19 value: "<controller handle>"
ubuntu@rosservice call /bcap_service '{func_id: 17, vntArgs: [{vt: 19, value: "<controller handle>"}, {vt: 8, value: "HandMoveA"}, {vt: 8195, value: "30, 100"}] }'
CAUTION: You cannot move the gripper while moving the arm. This is because the restriction of b-CAP Slave mode. So when you control the gripper (above step.5), be sure to confirm the arm is not moving.
Hello, thank you for reply, I have tried to do as you guide, but there is no values in output when step3(in cobotta driver terminal or bcap terminal there is no), I need the "controller handle" this param to fix that in rosservice command, right? how to get that value? in andriod app can I see that?
Sorry! I wrote the wrong steps. I fixed the above steps. Would you try it again?
ok, thank you very much, it works now. a little question about the cobotta package, do you plan to finish a complete package for cobotta? including whole moveit with gripper and the moveit plan has many limited when my computer send message missed(like the delayed question issuse), the robot will always turn to a warn state, I can't control that further, will that be right in the future?
Is there any way to call bcap_service
from python script? Like rosrun denso_robot_bringup gripper.py
?
I have been trying to write client node in python, but since bcap_service
server side was written in C++, i can't pass arguments to variant[] vntArgs
(there is no variant type in python, only has list type).
Here is the code:
#create handler to call the service bcap_service = rospy.ServiceProxy('bcap_service', bcap) #define the request func_id = 3 vt = 8 value_1 = 'b-CAP' value_2 = 'CaoProv.DENSO.VRC' value_3 = 'localhost' value_4 = '' vntArgs = [vt, value_1, vt, value_2, vt, value_3, vt, value_4] #call the service by passing the request to the handler response = bcap_service(func_id, vntArgs)
@DensoWaveRobot
Thank you for this information. This has always worked for me too. What I noticed now is that when I run the bcap_service
launch and then enter command to get the handler, it only works once. The second time I run the command an error value appears. Restarting the bcap_service
this works once again. trangely enough it has worked for me all the time. What could be the reason for this? Thanks for your help
@Koetzi When you move cobotta hand second, did you send only the 'HandMove' command below?
ubuntu@rosservice call /bcap_service '{func_id: 17, vntArgs: [{vt: 19, value: "
"}, {vt: 8, value: "HandMoveA"}, {vt: 8195, value: "30, 100"}] }'
Once getting the controller handle, you don't have to get it again. Or did you use any other command after first handmove operation?
@DensoWaveRobot
I agree with you there. If I execute the commands in the command line one after the other, everything works. But as soon as I use a script that opens and closes the gripper, it doesn't work anymore. (Please don't ask for the sense, this is just a test). Strangely enough, the script worked the same way before and now it doesn't. Maybe you can look over why it doesn't work or maybe there is a smarter way.
#!/usr/bin/env python
import rospy
from bcap_service.msg import variant
from bcap_service.srv import *
rospy.init_node('test_node', anonymous=True)
bcapReq = bcap_service.srv.bcapRequest()
bcapReq.func_id = 3
bcapReq.vntArgs.append(variant(vt=8, value="b-CAP"))
bcapReq.vntArgs.append(variant(vt=8, value="CaoProv.DENSO.VRC"))
bcapReq.vntArgs.append(variant(vt=8, value="localhost"))
bcapReq.vntArgs.append(variant(vt=8, value=""))
bcapSrv = rospy.ServiceProxy('bcap_service', bcap)
response = bcapSrv(bcapReq)
ControllerHandle = response.vntRet.value
while True:
#bcapReq = bcap_service.srv.bcapRequest()
bcapReq.func_id = 17
bcapReq.vntArgs.append(variant(vt=19, value="\"" + str(ControllerHandle) + "\""))
bcapReq.vntArgs.append(variant(vt=8, value="HandMoveA"))
bcapReq.vntArgs.append(variant(vt=8195, value="0,100"))
response = bcapSrv(bcapReq)
#bcapReq = bcap_service.srv.bcapRequest()
bcapReq.func_id = 17
bcapReq.vntArgs.append(variant(vt=19, value="\"" + str(ControllerHandle) + "\""))
bcapReq.vntArgs.append(variant(vt=8, value="HandMoveA"))
bcapReq.vntArgs.append(variant(vt=8195, value="30,100"))
response = bcapSrv(bcapReq)
I hope you see the mistake and can help me. Thanks a lot!
I can control the arm in ros now, but I see the moveit of ros, there is no group of gripper, how can I control the gripper in ros, I just need to control the gripper with position or even "open and close", could you give me some suggestions about that? thank you very much!