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

ROS Theoretical Question - How does work properly a node

asked 2019-03-22 09:04:00 -0500

I'm new at ROS and I'm trying to figure out how does the node works with a pyton/C++ code. I have two codes for the same situation: Use a Xbox Controller to move the turtle in turtlesim

FIRST EXAMPLE - Using global variables and a if __name__ == '__main__' with rospy.spin()

#!/usr/bin/env python
import rospy
from geometry_msgs.msg import Twist 
from sensor_msgs.msg import Joy

# FUNCTION - GET JOY VALUES TRANSFORM TO TURTLE MOVE
def joy_to_twist_transform(jData):
    twt = Twist()
    twt.linear.x = 5*jData.axes[1]
    twt.angular.z = 4*jData.axes[0]
    pub.publish(twt)

# FUNCTION - START PROCESS
def process():
    global pub
    pub = rospy.Publisher('turtle1/cmd_vel', Twist, queue_size=10)
    sub = rospy.Subscriber("joy", Joy, joy_to_twist_transform, queue_size=1)
    rospy.init_node('control_2turtle')
    rospy.spin()

# MAIN
if __name__  == '__main__':
    try:
        process()
    except rospy.ROSInterruptException:
        pass

SECOND EXAMPLE - Using class python and a while as a main

#!/usr/bin/env python
import rospy
from geometry_msgs.msg import Twist
from sensor_msgs.msg import Joy

# DEFINING CLASS
class pubSub:
    def __init__(self):
        # DEFINE VARIABLE TO KEEP LAST VALUE
        rospy.init_node('c2t')
        self.twt = Twist()
        self.hold = Twist()

    def callback_function(self,joyData):
        self.twt.linear.x = 4*joyData.axes[1]
        self.twt.angular.z = 4*joyData.axes[0]
        self.hold = self.twt

    def assuming_cont(self):
        pub = rospy.Publisher('turtle1/cmd_vel', Twist, queue_size=10)
        rospy.Subscriber("joy", Joy, self.callback_function, queue_size=10)
        pub.publish(self.twt)

ps = pubSub()
while not rospy.is_shutdown():
    ps.assuming_cont()

1 - What I understand about how a node works is: he run the code in a loop until is shutdown. But this does not answer Why can I still save the last value published in a topic (in my head, if I run my code in a loop I start from the beginning everytime)?

2 - Why is necessary to keep creating a rospy.Publisher and rospy.Subscriber in every loop? it is possible to create those guy one time only?(for example using them into __init__ function in the second example)

3 - What is the difference between while not rospy.is_shutdown(): and if __name__ == '__main__' with rospy.spin()?

4 - What is rospy.spin()? in any documentation says that keeps your node running, but the way I see he stuck the code in that line and keep there only.

If any could give any recommendation to read about those problems and improve my understatement of how work ROS works would thanks a lot!

edit retag flag offensive close merge delete

Comments

1

Not a full answer (so a comment):

2 - Why is necessary to keep creating a rospy.Publisher and rospy.Subscriber in every loop? it is possible to create those guy one time only?(for example using them into __init__ function in the second example)

it isn't, and your second example shows either a non-functional node, or one that does not follow best practices.

gvdhoorn gravatar image gvdhoorn  ( 2019-03-22 11:55:47 -0500 )edit

Do you have any link to see the best practices? And the node works... But what method to recommend to code? the first one is a good example of best practices?

kaike_wesley_reis gravatar image kaike_wesley_reis  ( 2019-03-22 12:11:34 -0500 )edit

2 Answers

Sort by » oldest newest most voted
0

answered 2019-04-02 12:45:49 -0500

Well, after learning more I understand:

1 - The codes get into the while not rospy.shutdown() or rospy.spin(). When I asked, I thought the loop was into all the code (starting from import all over again).

2 - It is not necessary.

3 - while not rospy.shutdown() give more control if your node do complex tasks and rospy.spin() is to just keep that node alive in the thread (used for more simple ones, where you only have a simple tasks as be a service or a subscriber only). if __name__ == '__main__' it is a good practice in python only, nothing related to ROS.

4 - following this question basically rospy.spin() is a while not rospy.shutdown(), so when I asked my code get bugged most because I did such thing as:

while not rospy.shutdown():
    ....
    rospy.spin()

So this is basically wrong (in my POV), because is equally to:

while not rospy.shutdown():
    ....
    while not rospy.shutdown():
edit flag offensive delete link more
0

answered 2019-04-03 02:12:49 -0500

Benyamin Jafari gravatar image

updated 2019-04-03 02:17:38 -0500

if __name__ == '__main__': doesn't matter at here (in the second code), also you could run your code without it like here:

Second code:

.
.
.
# MAIN
try:
    process()
except rospy.ROSInterruptException:
    pass

i.e. when you don't want your code to run when it imported in another python code, you should use if __name__ == '__main__':

More information.


The main difference between First code and Second code is that the First code used the rospy.spin() method which is a built-in ROS loop that triggers the publisher and subscriber in another thread, so you wouldn't need to an inner while in your code like the Second example.

Relevant Question.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2019-03-22 09:04:00 -0500

Seen: 664 times

Last updated: Apr 03 '19