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

TurtleBot ROS moving using Twist

asked 2012-11-05 04:07:49 -0500

Emordnys gravatar image

updated 2014-04-20 14:09:50 -0500

ngrennan gravatar image

I am trying to program for a TurtleBot, but there is a significant lack of tutorials for the robot and I have been unable to write my own C++ which works. I am trying to use a tutorial from another robot just to make the robot move when a key is pressed.

The source tutorial is found here: , which I only modified the publish topic to "/cmd_vel"

#include <iostream>

#include <ros/ros.h>
#include <geometry_msgs/Twist.h>

class RobotDriver
{
private:
  //! The node handle we'll be using
  ros::NodeHandle nh_;
  //! We will be publishing to the "/base_controller/command" topic to issue commands
  ros::Publisher cmd_vel_pub_;

public:
  //! ROS node initialization
  RobotDriver(ros::NodeHandle &nh)
  {
    nh_ = nh;
    //set up the publisher for the cmd_vel topic
    cmd_vel_pub_ = nh_.advertise<geometry_msgs::Twist>("/cmd_vel", 1);
  }

  //! Loop forever while sending drive commands based on keyboard input
  bool driveKeyboard()
  {
    std::cout << "Type a command and then press enter.  "
      "Use '+' to move forward, 'l' to turn left, "
      "'r' to turn right, '.' to exit.\n";

    //we will be sending commands of type "twist"
    geometry_msgs::Twist base_cmd;

    char cmd[50];
    while(nh_.ok()){

      std::cin.getline(cmd, 50);
      if(cmd[0]!='+' && cmd[0]!='l' && cmd[0]!='r' && cmd[0]!='.')
      {
        std::cout << "unknown command:" << cmd << "\n";
        continue;
      }

      base_cmd.linear.x = base_cmd.linear.y = base_cmd.angular.z = 0;   
      //move forward
      if(cmd[0]=='+'){
        base_cmd.linear.x = 0.25;
      } 
      //turn left (yaw) and drive forward at the same time
      else if(cmd[0]=='l'){
        base_cmd.angular.z = 0.75;
        base_cmd.linear.x = 0.25;
      } 
      //turn right (yaw) and drive forward at the same time
      else if(cmd[0]=='r'){
        base_cmd.angular.z = -0.75;
        base_cmd.linear.x = 0.25;
      } 
      //quit
      else if(cmd[0]=='.'){
        break;
      }

      //publish the assembled command
      cmd_vel_pub_.publish(base_cmd);
    }
    return true;
  }

};

int main(int argc, char** argv)
{
  //init the ROS node
  ros::init(argc, argv, "robot_driver");
  ros::NodeHandle nh;

  RobotDriver driver(nh);
  driver.driveKeyboard();
}

The code compiles and runs correctly, but the turtlebot does not move when commands are issued. Any ideas why?

Additional Info:

When I'm on the laptop provided with my Turtlebot messages appear to not be being sent (or are not being delivered). In separate terminals, I have:

turtlebot@turtlebot-0516:~$ sudo service turtlebot start
[sudo] password for turtlebot:
turtlebot start/running, process 1470
turtlebot@turtlebot-0516:~$ rostopic echo /cmd_vel

And

turtlebot@turtlebot-0516:~$ rostopic pub /cmd_vel geometry_msgs/Twist '[1.0, 0.0, 0.0]' '[0.0, 0.0, 0.0]'
publishing and latching message. Press ctrl-C to terminate

With info:

turtlebot@turtlebot-0516:~$ rostopic info /cmd_vel
Type: geometry_msgs/Twist

Publishers:
 * /rosttopic_2547_1352476947372 (http://turtlebot-0516:40275/)

Subscribers:
 * /turtlebot_node (http://10.143.7.81:58649/)
 * /rostopic_2278_1352476884936 (http://turtlebot-0516:39291/)

There is no output for the echo at all

edit retag flag offensive close merge delete

Comments

What's the output of rostopic echo /cmd_vel when you are sending commands? What's the output of rostopic info /cmd_vel. Please edit your question to add more information. Also please tag it correctly to make sure the right people get notified.

Lorenz gravatar image Lorenz  ( 2012-11-05 04:13:48 -0500 )edit

Hm. Weird that rostopic pub does not work. You should receive exactly one message since rostopic pub latches the topic. Can you try rostopic pub /cmd_vel geometry_msgs/Twist '{linear: {x: 1.0}}' -r 10 to repeat the message with 10 Hz? Btw. my syntax will have the same effect as yours.

Lorenz gravatar image Lorenz  ( 2012-11-09 03:28:56 -0500 )edit

if we want to move two turtle bot by rostopic pub /cmd_vel geometry_msgs/Twist what can i do ..... because by giving this command both turtle bot move in the same direction ..... i want to move one turtlebbot in one direction and other turtlebot in another direction .... thanks for the help @Lorenz

qubaish g gravatar image qubaish g  ( 2013-04-01 11:03:48 -0500 )edit

3 Answers

Sort by ยป oldest newest most voted
7

answered 2012-11-05 14:09:02 -0500

weiin gravatar image

Significant lack of tutorials for turtlebot?! That was the most complete set of tutorials I've seen in the whole list of robots! (in fact I used turtlebot's codes as the starting point for my own differential drive robot)

Teleop for turtlebot can be found here. You should also review the teleop for turtlesim. This will also show you how to do simple troubleshooting when one node does not respond to another (rxgraph). Usually when robots don't respond to topics, it is likely it is listening to the wrong thing (either topic name was wrong, or was pushed down the namespace and needs correct remapping)

edit flag offensive delete link more
1

answered 2016-11-17 06:23:56 -0500

Smed gravatar image
edit flag offensive delete link more
1

answered 2014-10-06 17:56:57 -0500

Mark Silliman gravatar image

I had the same problem last week. For anyone else that's looking to program TurtleBot using ROS & C++ and is looking for a very simple example I wrote a quick blog post: TurtleBot's Hello World

Though the teleop code is obviously superior the tutorial removes all the complexity for programmers to get their feet wet.

edit flag offensive delete link more

Comments

Link broken

arpit901 gravatar image arpit901  ( 2016-05-20 15:03:18 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2012-11-05 04:07:49 -0500

Seen: 30,387 times

Last updated: Oct 06 '14