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

May I control the turtlesim by sending commands to turtlesim/Pose?

asked 2015-11-02 00:45:53 -0500

pinocchio gravatar image

Hi, I am new to ROS, using ROS Indigo on Ubuntu 14.04. After coding the basic tutorial http://wiki.ros.org/ROS/Tutorials/Wri... , I am trying to control the turtle by sending the commands to turtlesim/Pose.

I program the code, CMakeLists.txt, and package.xml properly, and the catkin_make works properly. However, the turtle does not move, and there is no link between /publish_pose node (my publishing node) and /turtlesim node by executing rosrun rqt_graph rqt_graph as follows.

image description

My code of the publishing node is listed below.

#include <ros/ros.h>
#include <geometry_msgs/Twist.h>  // For geometry_msgs::Twist
#include <turtlesim/Pose.h> // rostopic type /turtle1/pose
#include <stdlib.h> // For rand() and RAND_MAX

int main(int argc, char **argv) {
  // Initialize the ROS system and become a node.
  ros::init(argc, argv, "publish_pose");
  ros::NodeHandle nh;

  // Create a publisher object.
  ros::Publisher pub = nh.advertise<turtlesim::Pose>(
    "/turtle1/pose", 1000);

  // Seed the random number generator.
  srand(time(0));

  // Loop at 2Hz until the node is shut down.
  ros::Rate rate(2);
  while(ros::ok()) {
    // Create and fill in the message.  The other four
    // fields, which are ignored by turtlesim, default to 0.
    turtlesim::Pose msg;
    msg.x = float(rand())/float(RAND_MAX);
    msg.y = float(rand())/float(RAND_MAX);
    msg.theta = 2*float(rand())/float(RAND_MAX) - 1;

    // Publish the message.
    pub.publish(msg);

    // Send a message to rosout with the details.
    ROS_INFO_STREAM("Sending random pose command:"<<" x=" << msg.x<<" y=" << msg.y<<" theta=" << msg.theta);

    // Wait until it's time for another iteration.
    rate.sleep();
  }
}
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2015-11-02 02:04:49 -0500

gvdhoorn gravatar image

Short answer: no you cannot not (at least not using that topic).


Longer: as you can see on wiki/turtlesim - Nodes - turtlesim_node - Subscribed Topics, the turtleX/pose topic is only published to by the turtlesim_node node, so no incoming messages will be expected there (it is only an output). The only subscription is a turtleX/cmd_vel (geometry_msgs/Twist) topic, which is the only way to make the turtle move in the normal manner.

To place the turtle at a certain position without it having to travel there, you should use the turtleX/teleport_* services.

edit flag offensive delete link more

Comments

thx. will try that.

pinocchio gravatar image pinocchio  ( 2015-11-02 10:32:43 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2015-11-02 00:45:53 -0500

Seen: 1,695 times

Last updated: Nov 02 '15