Ros GamePad controls Turtles and robots

Source: Internet
Author: User

The tutor bought a gamepad and studied how to use the GamePad to control the robot. Unexpectedly a bit simple, write a break code can, at the same time I this two days study of review.

Start the tutorial.

(1) GamePad control turtle.

Rosrun Turtlesim turtlesim_node
rosrun Turtlesim Turtle_teleop_key
When we run the above two sentences, we find that the keyboard's arrow keys can be moved by the turtle, and both of them are communicated through the topic.

/turtle1/cmd_vel[geometry_msgs/twist]
Geometry_msgs/twist is the type of the topic, that is, the type of message, we look at the internal structure
Rosmsg Show Geometry_msgs/twist
Geometry_msgs/vector3 linear
  float64 x
  float64 y
  float64 z
geometry_msgs/vector3 Angular
  Float64 x
  float64 y
  float64 Z
We only use linear.x this to control the speed, Angular.z to control the direction.

Idea: We know the turtle will subscribe to this topic, so we're going to write a code that has subscribers, publishers. Subscribe to the instructions of the gamepad and then release the speed to the/turtle1/cmd_vel topic so the turtle can subscribe.

Now we want to understand the type of data sent by the GamePad, and then go through the subscription process to send the desired speed.

First run at the terminal:

ls/dev/input/
To see what ports there are, which will have js0 this port, we will use this port to receive data from the GamePad. And then
sudo jstest/dev/input/js0
Will find
axes:0:0  1:0  2:0
... buttons:0:0 1:0 2:0 3:0 4:0 ...

Next, we run the node that receives the game handle data

Rosrun Joy Joy_node
The data transmitted by this node and the handle is communicated through the/joy topic. We need to know which keys are controlling what, so we move the handles to see the data that this topic receives
Rostopic Echo/joy
'll see
---
header: 
  seq:837
  stamp: 
    secs:1500642610
    nsecs:656011953
  frame_id: '
axes: [- 0.0, -0.0, 0.0, -0.0, -0.0, 0.0, 0.0, 0.0]
buttons: [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
---
Move the rocker left and right 1, found axes[0] Change-1 to 1, we put it as an angle to the angualr.z, the front and rear shift lever 1, found axes[1] Change-1 to 1, we have it as the speed of the assignment to linear.x.

Maybe you've seen the type of/joy topic.

Rostopic Type/joy
Show
Sensor_msgs/joy
$rosmsg Show Sensor_msgs/joy
Std_msgs/header Header
  uint32 seq Time
  stamp
  string frame_id
float32[] axes
int32[] Buttons


OK, now I also know the topic of/joy and its type. Let's start writing code:


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

Iostream> using namespace std;

Class Teleop {Public:teleop ();
    Private:/* data */void callback (const sensor_msgs::joy::constptr& Joy); Ros::nodehandle N;
    Instantiate node Ros::subscriber Sub;
    Ros::P Ublisher Pub;	Double vlinear,vangular;//We control the speed of the turtle, is through the two variables to adjust the int axis_ang,axis_lin;

Axes[] 's Key}; 
Teleop::teleop () {///We add these variables to the parameters and can be easily modified in the parameter server n.param<int> ("Axis_linear", axis_lin,1);//default axes[1] receive speed N.param<int> ("Axis_angular", axis_ang,0);//default axes[0] Receive angle n.param<double> ("Vel_linear", vlinear,1);// Default line Speed 1 m/s n.param<double> ("Vel_angular", vangular,1);//default angular Speed 1 units rad/s pub = N.advertise<geometry_msgs:: Twist> ("/turtle1/cmd_vel", 1);//Send speed to Turtle sub = n.subscribe<sensor_msgs::joy> ("Joy", 10,&teleop:: Callback,this); Subscribe to the data sent by the gamepad} void Teleop::callback (const sensor_msgs::joy::constptr& Joy) {Geometry_mSgs::twist v; V.linear.x =joy->axes[axis_lin]*vlinear;
 Multiply the game handle's data by the speed you want, then send it to the turtle V.angular.z =joy->axes[axis_ang]*vangular; 
Ros_info ("Linear:%.3lf angular:%.3lf", v.linear.x,v.angular.z);
Pub.publish (v);
 } int main (int argc,char** argv) {ros::init (argc, argv, "Logteleop"); Teleop Telelog;
 Ros::spin ();
return 0; }


After that, run this node, turtle node, handle node, you can control the turtle. Now we program these three nodes to launch files and set the control buttons and speed:
<launch>
    <node pkg= "Turtlesim" type= "Turtlesim_node" name= "Sim" >
    </node>
    <node Pkg= "Action_tutorials" type= "Logteleop" name= "Logteleop" output= "screen" > 
    </node>
    <!--input Axis--
      <param name= "Axis_linear" value= "4" type= "int"/>
       <param name= "Axis_angular" value= "3" type= "int"/>
       <!--input vel--
       <param name= "Vel_linear" value= "2" type= "Double"/>
       < param name= "vel_angular" value= "1.5" type= "double"/>
    <node respawn=  "true" pkg= "Joy" type= "Joy_node" Name= "Joystick" >
  
    </node>
    
</launch>
When you start these three nodes, you can set the speed and joystick of the gamepad. I'm using Logitech game sticks.

Joystick 1 Controls Axes[0] and axes[1], joystick 2 controls axes[3]axes[4]. So at the start of the file I can arbitrarily set which joystick, if not set to take the default. This is the benefit of the parameter.


(2) Next, using the GamePad control robot, we first start the machine and

Roslaunch turtlebot_bringup minimal.launch
roslaunch turtlebot_teleop keyboard_teleop.launch
rosrun rqt_ Graph Rqt_graph

The first one is to start the total robot node, the second is to start the keyboard control robot walking node, the third is to view their communications, as shown below:



The topic of keyboard Publishing is

/cmd_vel_mux/input/teleop
Next, we'll change the above code slightly, and change the issue to the topic.

On the code:

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

Iostream> using namespace std;

Class Teleop {Public:teleop ();
    Private:/* data */void callback (const sensor_msgs::joy::constptr& Joy);
    Ros::nodehandle N;
    Ros::subscriber Sub;
    Ros::P Ublisher Pub;
    Double vlinear,vangular;
int Axis_ang,axis_lin,ton;

};
    Teleop::teleop () {n.param<int> ("axis_linear", axis_lin,1);
    N.param<int> ("Axis_angular", axis_ang,0);
    N.param<double> ("Vel_linear", vlinear,1);
    N.param<double> ("Vel_angular", vangular,1);
    N.param<int> ("button", ton,5);
    Pub = N.advertise<geometry_msgs::twist> ("/cmd_vel_mux/input/teleop", 1);
Sub = n.subscribe<sensor_msgs::joy> ("Joy", 10,&teleop::callback,this);
    } void Teleop::callback (const sensor_msgs::joy::constptr& Joy) {Geometry_msgs::twist v;
   V.linear.x =joy->axes[axis_lin]*vlinear; V.angulaR.z =joy->axes[axis_ang]*vangular;
        if (Joy->buttons[ton]) {v.linear.x = (joy->axes[axis_lin]+joy->axes[1]) *vlinear;
        V.angular.z = (joy->axes[axis_ang]+joy->axes[0]) *vangular;
        Ros_info ("Linear:%.3lf angular:%.3lf", v.linear.x,v.angular.z);
   Pub.publish (v);
    }} int main (int argc,char** argv) {ros::init (argc, argv, "Log");
    Teleop Telelog;
    Ros::spin ();
return 0; }


execution, I found that hand accidentally touched the joystick robot will go, I do not want to do so, so I added a key, buttons[5] button, it will pass over 0 or 1, when I press the time will be 1. This way, the robot will only walk if and when I press this button and move the lever. As for which key to press, I can set the parameter, default is Buttons[5].

V.linear.x = (joy->axes[axis_lin]+joy->axes[1]) *vlinear;
V.angular.z = (joy->axes[axis_ang]+joy->axes[0]) *vangular;
I can control the robot by the parameters of the joystick 2 axes[3] and axes[4], so that they can control with the joystick 11. Control process arbitrarily, you can let the rocker 1 move control speed, joystick 2 move control speed, can also be at the same time, the speed doubled oh, also can not move the Stick 2, only move the lever 1 control, so that the joystick 2 control the speed of the data for 0 Oh, is equal to only the joystick 1 in control. Both hands control the rocker more exciting OH

Suddenly found that I was also very clever.

Attach launch File

<launch>
    <include file= "$ (find Turtlebot_bringup)/launch/minimal.launch"/>
    <node pkg= " Action_tutorials "type=" Logrobt "name=" LogHandle "output=" screen ">
    </node>
    <!--input axis-- >
      <param name= "Axis_linear" value= "4" type= "int"/>
       <param name= "Axis_angular" value= "3" type= " int "/>
       <!--input vel--
       <param name=" vel_linear "value=" 0.5 "type=" double "/> <param
       Name= "Vel_angular" value= "1.5" type= "double"/> <param name=
       "button" value= "5" type= "int"/>
    < Node  respawn= "true" pkg= "Joy" type= "Joy_node" name= "Joystick" output= "screen" >
        <param name= "Dev" Value= "/dev/input/js0" type= "string"/>
        <param name= "Deadzone" value= "0.12"/>
    </node>

    
</launch>

Finally, through the diagram, look at the subscription relationship



There is no discovery, the node name has changed. Haha, you can remap through the launch file OH


Contact Us

The content source of this page is from Internet, which doesn't represent Alibaba Cloud's opinion; products and services mentioned on that page don't have any relationship with Alibaba Cloud. If the content of the page makes you feel confusing, please write us an email, we will handle the problem within 5 days after receiving your email.

If you find any instances of plagiarism from the community, please send an email to: info-contact@alibabacloud.com and provide relevant evidence. A staff member will contact you within 5 working days.

A Free Trial That Lets You Build Big!

Start building with 50+ products and up to 12 months usage for Elastic Compute Service

  • Sales Support

    1 on 1 presale consultation

  • After-Sales Support

    24/7 Technical Support 6 Free Tickets per Quarter Faster Response

  • Alibaba Cloud offers highly flexible support services tailored to meet your exact needs.