ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Infinite loop in callback function

asked 2018-11-22 07:07:54 -0500

Spyros gravatar image

updated 2018-11-23 09:56:07 -0500

Hi there! I want to subscribe to a topic (real_position) and save these data in a variable (julio) in order to process them later in my code. I've tried to use something similar to the tutorial for the subscriber node: http://wiki.ros.org/ROS/Tutorials/Wri... The problem is that when I run my node, the code stacks in the callback function, repeating it again and again, until I press Ctrl + C. Then it continues with the rest of the code. Is callback function the only way to get subscribed data? and if it is, how can I make it run once per loop and get the data to a variable? I am new to ROS and Python, and I apologize if this sounds trivial. I use Ubuntu 16.04 LTS, Python 2.7.12 and ROS Kinetic. Thank you in advance!

#!/usr/bin/python
import rospy
import serial
import time
from std_msgs.msg import String

rospy.init_node('serial_connection', anonymous = True)

ser = serial.Serial('/dev/ttyUSB0', 9600)
print (ser.name)
time.sleep(2)

x_d = 0 # mm
y_d = 1000
thita_d = 0 # moires i rads

camera = [0, 0, 0]
error = [0, 0, 0]
sending_data = [0, 0, 0]
print(sending_data)

def callback(data):
    print("callback")
    global camera
    camera = data
    print(camera)
    print("emeina mes to callback kollimeno")

rospy.Subscriber('real_position', String, callback)
rate = rospy.Rate(1) #isws na min xreiazetai


def camera_feedback():
    print("camera feedback")
    print(camera)

def error_calculation():
    print("error caclulation")
    error[0] = x_d - camera[0]
    error[1] = y_d - camera[1]
    error[2] = thita_d - camera[2]

def controller_equations():
    print("controller equations")
    if error != [0, 0, 0]:
        print(error)
        global sending_data
        print(sending_data)
        sending_data[0] = 8
        sending_data[1] = 8
        sending_data[2] = 0

    else:
        sending_data = [0, 0, 0]
    print(error)
    print('kokos')
    print(sending_data)


def serial_connection():
    print("serial connection")
    if not rospy.is_shutdown():      
        if ser.isOpen():
            print ("Port Open")
            for i in range(1):               
                ser.write(bytes(sending_data) + '\n')
                time.sleep(0.001)




if __name__ == '__main__':
    try:
        while not rospy.is_shutdown():
            print("in the while loop")
            camera_feedback()
            error_calculation()
            controller_equations()
            serial_connection()
            rate.sleep()
        ser.close()
    except rospy.ROSInterruptException:
        pass
edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2018-11-22 08:10:27 -0500

updated 2018-11-23 12:05:51 -0500

Your program structure needs a bit of a change so that it will do what you want. Here are some points:

  • You should initialise your node and create your subscribers once only.
  • The rospy.spin() function will spin forever until you close the node down manually.

Bearing these in mind you will need to change your code so that inside main you initialise your node once and create the subscriber once. Then you'll need to create the rospy.Rate object. Finally still within main you'll need to add your while loop.

This while loop will include the rate.sleep() to keep it at the desired frequency. Within this loop you can call your error function, control function and finally your serial connection.

Note, the body of the while loop may well execute before the callback function so you'll have to make sure your code is safe to do this.

Hope this helps.

UPDATE:

Just a style node for you code. You should generally make the start point of code within main, at the moment you do all your initialisation in the global scope of the script before main is reached. Although this will work it's not considered good practice. If you move the following lines and place them between try: and the while statement in main it will tidy this up.

rospy.init_node('serial_connection', anonymous = True)

print (ser.name)
time.sleep(2)

print(sending_data)

rospy.Subscriber('real_position', String, callback)
rate = rospy.Rate(1) #isws na min xreiazetai
edit flag offensive delete link more

Comments

1

There ought to be a notification that someone else is typing up an answer...

lucasw gravatar image lucasw  ( 2018-11-22 08:13:45 -0500 )edit

I couldn't agree more :-)

PeteBlackerThe3rd gravatar image PeteBlackerThe3rd  ( 2018-11-22 08:27:47 -0500 )edit

@lucasw@PeteBlackerThe3rd thank you for your response. I made some changes following your advice and I updated my code on this post. I am not sure about the position of rospy.Subscriber and rospy.rate. I tried to put it right after rospy.init but I got a callback not defined error....

Spyros gravatar image Spyros  ( 2018-11-23 10:01:57 -0500 )edit

...The result now looks ok. Can you tell me if these changes correspond to the tips you gave me? Just to make sure that I got it correctly.

Spyros gravatar image Spyros  ( 2018-11-23 10:04:05 -0500 )edit

Yes that's what I was thinking. I'll update my answer with a few style points. But what you've got should work.

PeteBlackerThe3rd gravatar image PeteBlackerThe3rd  ( 2018-11-23 12:01:12 -0500 )edit
1

I made the changes you pointed out and the node looks to work fine. Thank you for the help!

Spyros gravatar image Spyros  ( 2018-11-26 04:20:10 -0500 )edit
0

answered 2018-11-22 08:08:30 -0500

lucasw gravatar image

You only want to run init_node and create the subscriber once at initialization time, not every time through your update loop: move camera_feedback() up out of the while not rospy.is_shutdown(). The rospy.spin won't return until you hit ctrl-c, so that needs to be removed. In the while loop you could sleep using another Rate.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2018-11-22 07:07:54 -0500

Seen: 3,684 times

Last updated: Nov 23 '18