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

Turtlebot Linear Y has no response

asked 2014-12-19 21:54:12 -0500

Apoorv gravatar image

updated 2014-12-19 22:14:00 -0500

Hi,

I am trying to do Turtlebot Simulation. I am giving Linear x & Linear y . But it seems like linear Y has no effect.

Then i tried below simple code to check linear y effect. after code run there is no movement in Y direction. Please tell reason-

==========================================================================

#!/usr/bin/env python 

import rospy
from geometry_msgs.msg import Twist

def Move():
        Pub = rospy.Publisher('mobile_base/commands/velocity' , Twist , queue_size=20)

        command = Twist()
        command.linear.x = 0
        command.linear.y = 1
        command.linear.z = 0
        command.angular.x = 0
        command.angular.y = 0
        command.angular.z = 0

        r = rospy.Rate(100)

        while not rospy.is_shutdown():
                Pub.publish(command)

                r.sleep()

if __name__ == '__main__' :
        rospy.init_node('TurtleControl')
        Move()

==========================================================================

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2014-12-19 22:25:32 -0500

That geometry_msgs/Twist message is expressed in a frame attached to the base of the robot with it's x-axis in the forward direction, the y-axis to the side, and the z-axis up. See REP 103. The turtlebot has a "non-holonomic constraint" which means in its mathematical model (and really the actual robot) it cannot slide sideways (in the y-direction). This model is often called a unicycle model or a kinematic car model. The result is that the commands the turtlebot accepts are a forward translational velocity (twist.linear.x), and an angular velocity (twist.angular.z).

edit flag offensive delete link more

Comments

thanks. So if i have to move turtlebot in Y direction as well , how to calculate twist.angular.z. I have calculated X direction & Y direction velocities.

I do not know how to convert Y direction velocity into corresponding twist.angular.z Please help.

Apoorv gravatar image Apoorv  ( 2014-12-20 10:52:50 -0500 )edit

You cannot ever have a Y direction velocity in the frame attached to the robot. If you want it to move in both the y and x direction w.r.t. a world frame, you'd first have to rotate the robot and then translate in the direction that you'd want to go. Or use a controller to follow the desired dir.

jarvisschultz gravatar image jarvisschultz  ( 2014-12-20 10:58:49 -0500 )edit

IMO, the paper Control of Wheeled Mobile Robots: An Experimental Overview provides a nice introduction to the model the turtlebot uses and several different strategies for controlling it. http://www.dis.uniroma1.it/~labrob/pu...

jarvisschultz gravatar image jarvisschultz  ( 2014-12-20 10:59:51 -0500 )edit

If you're going to use ROS navigation eventually, you could also check out some of the local planners such as dwa_local_planner or eband_local_planner. These planners control the robot to follow a path while avoiding obstacles.

jarvisschultz gravatar image jarvisschultz  ( 2014-12-20 11:04:27 -0500 )edit

Question Tools

Stats

Asked: 2014-12-19 21:54:12 -0500

Seen: 1,468 times

Last updated: Dec 19 '14