Logitech F710无线手柄控制ROS机器人

在这里插入图片描述

注:游戏手柄为罗技F710无线手柄,
系统版本:ubuntu18.04
ROS版本:Melodic
节点功能:手柄与ubuntu通讯并发布/cmd_vel话题

一、与ubuntu创建连接:

1.确保手柄接收器与电脑连接

2.检查ubuntu系统是否识别手柄

dmesg | grep Logitech

显示以下内容,说明接受器已识别
在这里插入图片描述

3.安装与手柄相关的ros依赖

sudo apt-get install ros-melodic-joystick-drivers ros-melodic-joystick-interrupt
sudo apt-get install ros-melodic-joy-listener ros-melodic-joy-mouse ros-melodic-joy-teleop 

为了检查控制信号

sudo apt-get install jstest-gtk

4.检查Ubuntu是否可以正常接收手柄控制信号

jstest-gtk

在这里插入图片描述
双击列表中的设备项
在这里插入图片描述
这个时候动一动手柄,可以看到各轴、按钮是否可以发送控制信号。到此完成硬件连接。

二、编写ROS节点,发布/cmd_vel

1.查看/joy话题内容

roscore
rosrun joy joy_node
rostopic echo /joy

即可查看/joy话题的内容(按手柄),该话题包含了手柄与ros节点通讯的信息,主要是axes和buttons这两个数组,每个成员对应了手柄上某一个键的信号,有模拟量也有数字量
(注:博主用的是手柄的默认映射,无更改,大家可根据自己的映射写节点)
(注:博主用的是F710的 D模式 (DirectlyInput Mode),手柄处于 飞行模式 下)
代码如下:

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

geometry_msgs::Twist twist;
float LinearMax,AngularMax;
float LinearMax_origin,AngularMax_origin;

const char* msg = R"(
Reading from the Logitech joy and Publishing to Twist!
---------------------------
Moving around:
   Left axis:   Front & Back
   Right axis:  Turn left & Turn right
---------------------------
Y/A : increase/decrease only linear speed by 20%
B/X : increase/decrease only angular speed by 20%
CTRL-C to quit
)";

void callback(const sensor_msgs::Joy::ConstPtr &data)
{
    // Flight mode, left -> linear, right -> angular
    twist.linear.x = data->axes[1]*LinearMax;
    twist.angular.z = data->axes[2]*AngularMax;
    // Set the LinearMax and AngularMax
    LinearMax += data->buttons[3]*0.2;
    LinearMax -= data->buttons[1]*0.2;
    AngularMax += data->buttons[2]*0.2;
    AngularMax -= data->buttons[0]*0.2;
    if(data->buttons[9]==1)
    {
        LinearMax = LinearMax_origin;
        AngularMax = AngularMax_origin;        
    }
    // printf("\rCurrent: MaxSpeed %f    MaxTurn %f \r",LinearMax,AngularMax);
}

int main(int argc,char** argv)
{
// Init rosnode
    ros::init(argc,argv,"joy2cmd");
    ros::NodeHandle nh;
    ros::Publisher cmd_pub = nh.advertise<geometry_msgs::Twist>("cmd_vel",10);
    ros::Subscriber joysub = nh.subscribe( "joy",10,callback);

// set param of maximum of linear and angular vel
    ros::param::param<float>("MaxLinear",LinearMax,1.5);
    ros::param::param<float>("MaxAngular",AngularMax,1.0);
// Save the two param to init
    LinearMax_origin = LinearMax;
    AngularMax_origin = AngularMax;
// print msg
    printf("%s", msg);
    ros::Rate r(20);
    while(ros::ok())
    {
        ros::spinOnce();
        cmd_pub.publish(twist);
        printf("Current: MaxSpeed %f    MaxTurn %f \r",LinearMax,AngularMax);
        r.sleep();
    }
    return 0;
}

launch文件如下:

<launch>
    <node pkg="joy" type="joy_node" name="joy_node" output="screen"/>
    <node pkg="gmapping_laser" type="joy2cmd" name="joy2cmd" output="screen">
        <param name="MaxLinear" value="1.0"/>
        <param name="MaxAngular" value="1.0"/>        
    </node>

</launch>

三、控制节点说明:

左摇杆:上推->前进,下推->后退,Y/A -> 增加/减少最大线速度
右摇杆:左推->左转,右推->右转,X/B -> 增加/减少最大角速度
start键:初始化最大速度

参考链接

ROS官网描述

Logo

瓜分20万奖金 获得内推名额 丰厚实物奖励 易参与易上手

更多推荐