Subscrine Cmd_vel / If not
I want to create a subscriber with python. I want to get cmdvel data and publish it with another Publisher. If I run twist keyboard.py , code work properly. However . If i don't execute teleopkeyboard.py code don't jump in "cmdgelen" and of course give me a an error NameError: global name 'x' is not defined... I want to initialize the code with x=0,y=0,z=0. After initilizing If "cmd_vel" give me any data, run with this data. How can code this ?
Code
def cmdgelen (msg):
rospy.loginfo("cmdgiris")
global x
global y
global z
x=msg.linear.x
y=msg.linear.y
z=msg.angular.z
def publishera():
output = HoldingRegister()
cxx=0
cyy=2
czz=0
#cmdgelen()
output.data = [x,y,z,cxx,cyy,czz]
output2 = HoldingRegister()
output2.data = [0,0,0,0,0,0]
rospy.loginfo("Sending arrays to the modbus server")
for i in xrange(10):
rospy.sleep(1)
pub.publish(output)
rospy.sleep(1)
pub.publish(output2)`
`if __name__=="__main__":
rospy.init_node("modbus_client_s7_1200")
host = "192.168.0.199"
port = 502
if rospy.has_param("~ip"):
host = rospy.get_param("~ip")
else:
rospy.loginfo("For not using the default IP %s, add an arg e.g.: '_ip:=\"192.168.0.198\"'",host)
if rospy.has_param("~port"):
port = rospy.get_param("~port")
else:
rospy.loginfo("For not using the default port %d, add an arg e.g.: '_port:=1234'",port)
# setup modbus client for siemens s7 PLC
modclient = S7ModbusClient(host,port)
rospy.loginfo("Setup complete")
cmd=rospy.Subscriber('cmd_vel', Twist, cmdgelen)
time.sleep(2)
pub = rospy.Publisher("modbus_wrapper/output",HoldingRegister,queue_size=500)
publishera()
Asked by bfdmetu on 2020-06-12 02:04:54 UTC
Answers
I'm not sure if I got your question, however, I made a code like yours but using a class to subscribe and publish the data, with this, you avoid using global variables. With this code, you receive data from /cmd_vel and publish it into modbus_wrapper/output.
import rospy
from geometry_msgs.msg import Twist
class PublisherAndSubscriber():
def __init__(self, pub_topic, sub_topic):
self.publisher = rospy.Publisher(pub_topic, HoldingRegister, queue_size=500)
self.subscriber = rospy.Subscriber(sub_topic, Twist, self.callback)
self.x, self.y, self.z = 0, 0, 0
self.cxx, self.cyy, self.czz = 0, 2, 0
def publishera(self, x, y, z):
output = HoldingRegister()
output.data = [self.x, self.y, self.z, self.cxx, self.cyy, self.czz]
emptyMsg = HoldingRegister()
emptyMsg.data = 6*[0]
rospy.loginfo("Sending arrays to the modbus server")
for _ in xrange(10):
self.publisher.publish(output)
rospy.sleep(1)
self.publisher.publish(emptyMsg)
def callback(self, cmd_vel_msg):
self.x = cmd_vel_msg.linear.x
self.y = cmd_vel_msg.linear.y
self.z = cmd_vel_msg.linear.z
if __name__ == "__main__":
rospy.init_node("modbus_client_s7_1200")
host = "192.168.0.199"
port = 502
if rospy.has_param("~ip"):
host = rospy.get_param("~ip")
else:
rospy.loginfo("For not using the default IP %s, add an arg e.g.: '_ip:=\"192.168.0.198\"'",host)
if rospy.has_param("~port"):
port = rospy.get_param("~port")
else:
rospy.loginfo("For not using the default port %d, add an arg e.g.: '_port:=1234'",port)
# setup modbus client for siemens s7 PLC
modclient = S7ModbusClient(host,port)
rospy.loginfo("Setup complete")
pubAndSub = PublisherAndSubscriber("modbus_wrapper/output", "cmd_vel")
rate = rospy.Rate(100)
while not rospy.is_shutdown():
pubAndSub.publishera()
rate.sleep()
Asked by Teo Cardoso on 2020-06-13 19:44:58 UTC
Comments
First of all thank you, your help. Some small changes and adding some parts your code works.Without any /cmd_vel data ( from outside ) code warn me something is missing. I add some default parameter. It works. with your wonderfull help
Asked by bfdmetu on 2020-06-16 06:16:13 UTC
Is this code will work for any System pubilshing /cmd_vel ?? I also need to send data from topic through modbus communication to my PLC.
Anyone please help me
Asked by Arun_kumar on 2021-12-07 00:26:35 UTC
Comments
Please format your question properly, especially the code you've included.
+100 for not posting a screenshot of an editor, but as-is, the code is very hard to read.
Copy-paste your code again, select all the lines and press
ctrl+k
(or click the Preformatted Text button (the one with101010
on it)).After you've done this, we can re-open.
Asked by gvdhoorn on 2020-06-12 02:27:14 UTC
Thank you your guidance. I hope this time is correct . After this warning i will be careful about. Thanks again
Asked by bfdmetu on 2020-06-12 03:28:29 UTC