ROS 十三、ROS手柄通信
由于在学习过程中有使用手柄的需要,且期间也出现了一系列问题,故在此记录一下手柄在ros上的使用,以便于大家快速上手。
在此强调一下本次运行环境:
- 操作系统:ubuntu18.04
- ROS版本:melodic
- 手柄:我使用的是有线免驱的普通pc手柄
一、手柄连接
在手柄接上电脑后,在linux命令行输入下述语句:
ls /dev/input/
可以得到各种输入设备的信息。大致如下:
by-id event0 event2 event4 event6 event8 mouse0 mouse2 uinput
by-path event1 event3 event5 event7 js0 mice mouse1
在其中只要找到jsX类型的设备即为连接成功,如js0,js1等等。
查询手柄的执行权限,jsX要换成具体的设备编号,如js0:
ls -l /dev/input/jsX
可以看到如下输出:
crw-rw-r--+ 1 root input 13, 0 10月 10 21:00 /dev/input/js
为手柄添加执行权限:
sudo chmod a+rw /dev/input/js0
使用如下语句测试手柄,确保用户在使用手柄的时候,电脑能够捕获手柄输入的信息:
sudo jstest /dev/input/js0
当按下手柄按钮的时候,命令行界面能够读到数据,则证明手柄的输入是有效的。
二、下载驱动
方法一
直接下载驱动包
sudo apt install ros-melodic-joy
sudo apt install ros-melodic-joystick_driver
然后运行roscore,尝试在连接好手柄后,运行下述内容:
rosrun joy joy_node
如果没有出现任何异常,恭喜你,可以进入第三个环节。
如果你发现这个安装方式无法满足你的需求,请看方法二
方法二
https://github.com/ros-drivers/joystick_drivers
在上述代码仓下载代码包:
git clone https://github.com/ros-drivers/joystick_drivers
然后复制到/opt/ros/melodic/share/目录下:
sudo cp -r joystick_drivers /opt/ros/melodic/share/
然后在自己的工作空间进行catkin_make即可
三、代码
本次实践,采用游戏手柄,控制小海龟的运动。
本次暂时只提供c++的代码:
#include <ros/ros.h>
#include <geometry_msgs/Twist.h>
#include <sensor_msgs/Joy.h>
class TeleopTurtle
{
public:
TeleopTurtle();
private:
// 处理手柄发送过来的信息
void callback(const sensor_msgs::Joy::ConstPtr &joy);
ros::NodeHandle nh;
ros::Subscriber sub;
ros::Publisher pub;
// 用来接收launch文件中设置的参数,绑定手柄摇杆、轴的映射
int axis_linear, axis_angular;
};
TeleopTurtle::TeleopTurtle()
{
nh.param<int>("axis_linear", axis_linear, 1);
nh.param<int>("axis_angular", axis_angular, 2);
pub = nh.advertise<geometry_msgs::Twist>("/turtle1/cmd_vel", 1);
sub = nh.subscribe<sensor_msgs::Joy>("joy", 10, &TeleopTurtle::callback, this);
}
void TeleopTurtle::callback(const sensor_msgs::Joy::ConstPtr &joy)
{
geometry_msgs::Twist vel;
// 将手柄摇杆轴拨动时值的输出,赋值给乌龟的线速度和角速度
vel.linear.x = joy->axes[axis_linear];
vel.angular.z = joy->axes[axis_angular];
ROS_INFO("当前线速度为:%.3lf | 角速度为:%.3lf", vel.linear.x, vel.angular.z);
pub.publish(vel);
}
int main(int argc, char **argv)
{
setlocale(LC_ALL, "");
ros::init(argc, argv, "teleop_turtle");
TeleopTurtle teleopTurtle;
ros::spin();
return 0;
}
在cmakelist中添加编译信息:
add_executable(teleop_turtle src/teleop_turtle.cpp)
target_link_libraries(teleop_turtle
${catkin_LIBRARIES}
)
launch文件:
<launch>
<!-- 启动乌龟节点 -->
<node pkg="turtlesim" type="turtlesim_node" name="turtlesim_node"/>
<!-- 启动我们创建的手柄控制乌龟节点 -->
<node pkg="teleop_turtle" type="teleop_turtle" name="teleop_turtle" output="screen"/>
<!-- 向参数服务器写入参数 -->
<param name="axis_linear" value="1" type="int"/>
<param name="axis_angular" value="3" type="int"/>
<!-- 启动手柄节点,respawn="true"表示节点挂掉时会自动重启 -->
<node respawn="true" pkg="joy" type="joy_node" name="joystick" />
</launch>
然后进行catkin_make,如果你是使用方法二,要确保驱动包能够一并被编译,即可正常使用。