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

My node doesn't publish to the topic cmd_vel

asked 2018-10-11 11:07:17 -0500

Jad gravatar image

updated 2018-10-11 12:04:39 -0500

ahendrix gravatar image

I created a node in order to move the robot and rotate it but it seems that the node doesn't publish to Twist can anyone help ?

this is my code

#!/usr/bin/env python

import rospy

from geometry_msgs.msg import Twist

PI = 3.1415926535897


class movement :

    def __init__(self):
        rospy.init_node('move_robot_node', anonymous=False)
            self.pub_move = rospy.Publisher("/marvin/diff_drive_controller/cmd_vel",Twist,queue_size=10)



    def move_forward(self):
        print "hi"
        move =Twist()
        move.linear.x=1
        move.angular.z=0.0
        self.pub_move.publish(move)
        print Twist()

    def move_backward(self):
        move =Twist()
        move.linear.x=-1
        move.angular.z=0.0
        self.pub_move.publish(move)
    def stop(self):
        move =Twist()
        move.linear.x=0
        move.angular.z=0.0
        self.pub_move.publish(move)

    def rotate_right(self):
        move =Twist()
        # Receiveing the user's input
        print("Let's rotate your robot")
        speed = 100
        angle = 90
        clockwise = True #True or false

        #Converting from angles to radians
        angular_speed = speed*2*PI/360
        relative_angle = angle*2*PI/360

            #We wont use linear components
        move.linear.x=0
        move.linear.y=0
        move.linear.z=0
        move.angular.x = 0
        move.angular.y = 0

            # Checking if our movement is CW or CCW
        if clockwise:
            move.angular.z = -abs(angular_speed)
            print move.angular.z
        else:
            move.angular.z = abs(angular_speed)
        # Setting the current time for distance calculus
        t0 = rospy.Time.now().to_sec()
        current_angle = 0

        while(current_angle < relative_angle):
            self.pub_move.publish(move)
            t1 = rospy.Time.now().to_sec()
            current_angle = angular_speed*(t1-t0)
        #Forcing our robot to stop
        move.angular.z = 0
        self.pub_move.publish(move)
        rospy.spin()                
while not rospy.is_shutdown() :

    mov = movement()
    mov.move_forward()
    rospy.spin()
edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
1

answered 2018-10-11 13:33:36 -0500

updated 2018-10-12 04:11:57 -0500

The way your code is now, the nose is initializing itself, creating a publishers object, sending a single Twist message on the topic then it's stays in an infinite loop inside spin until you kill the node.

The reason your not receiving this Twist message is that there is not enough time between creating the publisher and sending the message on it for any listener node to register with this new publisher. If you add a one second sleep after creating the publisher it should solve this problem.

However even then you're only publishing a single message which is not a great way on controlling a robot. Ideally you want to setup a while loop set to run at a specific frequency using a ros::Rate object probably around 100 hz. Your movement functions would then update the current velocity but let the loop actually publish the messages.

This way the robot is getting regular updates for its speed.

Hope this helps.

Edit:

The question is what's triggering the calls to moveForward, stop, etc. The while loop is similar to the one you've already got, except you want to use spinOnce instead of spin and add the Duration object.

The movement functions would then change the velocity of a Twist object which is a part of your object, not a local variation to a function. These movement functions wouldn't publish the message, they just update it.

Then inside the main loop you can measure the current angle of the robot and set the appropriate rotation speed for example or check for key presses from the user.

If you're not familiar with it already, I highly recommend reading up on event based programming. This is the approach used by ROS for handling tasks, this means you'll never have a long loop in a function only a single main loop and short functions which a triggered from within this loop.

edit flag offensive delete link more

Comments

That's definitely helped. Thank you very much.

Jad gravatar image Jad  ( 2018-10-12 02:23:19 -0500 )edit

But I have small question, if i do it as a while loop once i call mov.forward() it keeps running for ever and i donno how to stop the loop to call different type of movement like stop() or backward()

Jad gravatar image Jad  ( 2018-10-12 03:34:30 -0500 )edit

I've just edited my answer to address this for you.

PeteBlackerThe3rd gravatar image PeteBlackerThe3rd  ( 2018-10-12 04:07:04 -0500 )edit

May I ask: why does the code require to have a 1 sec sleep? It seems really irrational and non-logical to me. I mean, it's sequential code. Why do I have to wait so much time?

anonymous userAnonymous ( 2019-08-09 07:02:43 -0500 )edit

This code is sequential, but the wider ROS system it's working within is concurrent. When you create a publisher in one node, it takes time for other ROS nodes to connect to this publisher before any messages can be delivered. Hence the delay is needed for other ROS nodes to connect to this topic, before a message is published on it.

PeteBlackerThe3rd gravatar image PeteBlackerThe3rd  ( 2019-08-12 03:34:01 -0500 )edit
1

answered 2018-10-18 05:49:15 -0500

Alberto E. gravatar image

Hi there! Glad you already had your question answered. I just wanted to add here a very basic updated code (taken from yours) that fixes your problem and also triggers different functions (movements) depending on a user input. Hope it helps to better understand how it works.

#!/usr/bin/env python

import rospy
from geometry_msgs.msg import Twist

PI = 3.1415926535897

class movement :

    def __init__(self):
        rospy.init_node('move_robot_node', anonymous=False)
        self.pub_move = rospy.Publisher("/cmd_vel",Twist,queue_size=10)
        self.move = Twist()

    def publish_vel(self):
        self.pub_move.publish(self.move)

    def move_forward(self):        
        self.move.linear.x=1
        self.move.angular.z=0.0

    def move_backward(self):      
        self.move.linear.x=-1
        self.move.angular.z=0.0

    def stop(self):        
        self.move.linear.x=0
        self.move.angular.z=0.0  


if __name__ == "__main__":

    mov = movement()
    rate = rospy.Rate(1)

    while not rospy.is_shutdown() :

        movement = raw_input('Enter desired movement: ')

        if movement == 'forward':
            mov.move_forward()

        if movement == 'backward':
            mov.move_backward()

        if movement == 'stop':
            mov.stop()

        mov.publish_vel()
        rate.sleep()

Also, I've created a video explaining everything, in case you want to have a look: https://www.youtube.com/watch?v=HOAEX...

edit flag offensive delete link more

Question Tools

3 followers

Stats

Asked: 2018-10-11 11:07:17 -0500

Seen: 2,823 times

Last updated: Oct 18 '18