Robotics StackExchange | Archived questions

Is it possible create a rosnode in python with both subscriber and publisher?

Is it possible to make a rosnode with both a publisher an subscriber. Based on the tutorials, it looks like each are running in separate thread or infinite while loop? making it impossible to switch between listener and talker?

Is possible to make one rosnode which both has a subscriber and publish, handled by the same node.

Edit:

The case is as you mention @NEngelhard.. The python script establishes a Modbus TCP connection with an server. The server is currently only able to handle request from one master, which is why need the subscriber and publisher to be within the same node, such that I don't need to establish two connections.

This is the code I am running currently.

#!/usr/bin/env python

import rospy
from std_msgs.msg import Empty
from std_msgs.msg import Int8
from std_msgs.msg import String
from pymodbus.client.sync import ModbusTcpClient
import numpy as np


server = ModbusTcpClient('192.168.0.10', port=502)
connection = server.connect()

pub = rospy.Publisher('/conveyor_status', String)

def callback(data):
    result_0 = server.read_coils(0,1)
    result_1 = server.read_coils(1,1)
    result_2 = server.read_coils(2,1)
    result_3 = server.read_coils(3,1)

    server.write_coil(0, not int(result_0.bits[0]))
    server.write_coil(1, not int(result_1.bits[0]))
    server.write_coil(2, not int(result_2.bits[0]))
    server.write_coil(3, not int(result_3.bits[0]))

    print "Message received"
def bin(s):
    return str(s) if s<=1 else bin(s>>1) + str(s&1)

def callback_2(data):
    received = bin(data.data)
    print received[0] + received[1] + received[2] + received[3]


def listener():


    rospy.Subscriber('conveyor_control', Empty, callback)
    rospy.Subscriber('conveyor_HMI_control',Int8,callback_2)
    pub.publish(String("SASAS")) #This is not the actual message, but if this work it should be ok.. 
    rospy.spin()

if __name__ == '__main__':
    print "Running"
    listener()

Asked by 215 on 2016-11-01 14:45:40 UTC

Comments

In short: Yes, this is perfectly possible.

Asked by NEngelhard on 2016-11-01 15:18:01 UTC

How?... would you do this.

Asked by 215 on 2016-11-01 15:21:01 UTC

What have you tried so far and where exactly is your problem?

Asked by NEngelhard on 2016-11-01 15:28:09 UTC

making two def the talker and listener and adding them in the "main" loop loop.

Asked by 215 on 2016-11-01 15:44:18 UTC

The case is as you mention@NEngelhard.. The python script establishes a Modbus TCP connection with an server. The server is currently only able to handle request from one master, which is why need the subscriber and publisher to be within the same node, such that I don't need to establish two conn.

Asked by 215 on 2016-11-09 08:16:33 UTC

Answers

You should instead create a service node

Asked by ubuntuslave on 2016-11-01 14:56:46 UTC

Comments

Sorry, but this is a really bad advice for a beginner as you have no idea what he is trying to achieve.

Asked by NEngelhard on 2016-11-01 15:16:46 UTC

Yes, it is possible.

I don't know what is your goal but please reconsider your software design. In most cases is not needed publisher and subscriber at one place (doesn't have to be your case). Mostly: publisher is for sensor and subscriber is for the actuator, for example you may want to publish the data from rotary encoder from motor, and then you may want to send the data to the subscriber to the driver of the motor. At the very beginning the motor is considered as an one part. But in the detailed view there are two parts: the sensor and the actuator. And they can be launched via launch file in two separate threads. But again I don't know your intentions so doesn't have to be your case.

To your question: Take a look at this: link text

Try to google it (it may take i while) but there are examples on the internet.

Or you can publish your data in callback from subscriber (that is an Echo node) also a plenty examples on the internet. (Study this as an example)

Hope it helps. :-)

Asked by robopo on 2016-11-02 01:46:27 UTC

Comments

"In most cases is not needed publisher and subscriber at one place" This is not correct. How would you implement a robot that reads data from the sensor to compute commands for your actuator?

Asked by NEngelhard on 2016-11-02 03:27:13 UTC