文章目錄
- 0.參考文章
- 1. 加入joystick
-
- 1.1安裝羅技搖桿
- 1.2用小烏龜測試一下搖桿
-
- 1.2.1建立joy與turtlesim之間的通信節點
- 1.2.2修改package.xml檔案
- 1.2.3修改CMakeLists.txt檔案,讓chanel.cpp單獨成為一個節點
- 1.2.4建立并修改launch檔案
- 1.2.4 編譯加roslaunch
- 1.2.5 出現未識别/dev/input/js0時
- 2.把joy加到cmd_vel_mux裡
-
- 2.1在turtlesim檔案裡建立launch
- 2.2添加搖桿搖桿
- 2.3把搖桿加入mux映射檔案裡打開joy_key_test.launch修改成:
- 2.4最後一步修改一下配置檔案example.ymal
- 2.5運作joy_key_test.launch檔案就可以實作
0.參考文章
ros:遊戲搖桿控制海龜
使用yocs_cmd_vel_mux進行機器人速度控制切換
yocs_cmd_vel_mux
1. 加入joystick
1.1安裝羅技搖桿
教程
$sudo apt-get install ros-kinetic-joy
$sudo apt-get install ros-kinetic-joystick-drivers
$rosdep install joy
$rosmake joy
$ ls /dev/input
//應該能看到id裡多了一個js0
測試一下:
$sudo jstest /dev/input/js0
//按下搖桿收到變化
1.2用小烏龜測試一下搖桿
五個終端分别打開
$roscore
$rosrun turtlesim turtlesim_node
$rosrun turtlesim turtle_teleop_key
$rosrun joy joy_node
$rosrun rqt_graph
可以看到:
我的/joy_node 發出來的東西沒有被/turtlesim接收到
看一下兩個node的info
$ rosnode list
$ rosnode info /joy_node
$ rosnode info /turtlesim
- 可以看出 /joy_node節點pub出來的消息是: /joy [sensor_msgs/Joy];;而/turtlesim節點sub的消息是:/turtle1/cmd_vel [geometry_msgs/Twist]*
-
是以我們要在這兩個節點之間加上一個轉換節點:可接受 /turtle1/cmd_vel [geometry_msgs/Twist]
并發送/turtle1/cmd_vel [geometry_msgs/Twist];網上有teleop_twist_joy可直接用 後面再使用一下 這邊複現一下别人的程式
1.2.1建立joy與turtlesim之間的通信節點
$cd catkin_ws/src
$catkin_create_pkg joy_turtlesim roscpp rospy std_msgs
//在你的工作空間下建立一個叫joy_turtlesim的包
在該包下建立chanel.cpp檔案;;注意空格可能影響catkin_make 可以把所有空格删除了自己添加
#include <ros/ros.h>
#include <geometry_msgs/Twist.h>
#include <sensor_msgs/Joy.h>
#include <iostream>
using namespace std;
class Teleop
{
public:
Teleop();
private:
void callback(const sensor_msgs::Joy::ConstPtr& Joy);
ros::NodeHandle n; //執行個體化節點
ros::Subscriber sub ;
ros::Publisher pub ;
double vlinear,vangular;//我們控制烏龜的速度,是通過這兩個變量調整
int axis_ang,axis_lin; //axes[]的鍵
};
Teleop::Teleop()
{
//我們将這幾個變量加上參數,可以在參數伺服器友善修改
n.param<int>("axis_linear",axis_lin,1); //預設axes[1]接收速度
n.param<int>("axis_angular",axis_ang,0);//預設axes[0]接收角度
n.param<double>("vel_linear",vlinear,1);//預設線速度1 m/s
n.param<double>("vel_angular",vangular,1);//預設角速度1 機關rad/s
pub = n.advertise<geometry_msgs::Twist>("/turtle1/cmd_vel",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;
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, "joy_to_turtlesim");
Teleop teleop_turtle;
ros::spin();
return 0;
}
1.2.2修改package.xml檔案
<exec_depend>message_runtime</exec_depend>
1.2.3修改CMakeLists.txt檔案,讓chanel.cpp單獨成為一個節點
add_executable( chanel src/chanel.cpp)
add_dependencies(chanel ${${PROJECT_NAME}_EXPORTED_TARGETS}${catkin_EXPORTED_TARGETS})
target_link_libraries(chanel ${catkin_LIBRARIES})
1.2.4建立并修改launch檔案
$ cd catkin_ws/src/joy_turtlesim/
$ mkdir -p launch
$ cd launch
$ touch joy_turtlesim.launch
$ gedit joy_turtlesim.launch
添加以下内容
<launch>
<include file="$(find turtlesim)/launch/joy_test.launch" />
<node pkg="joy_turtlesim" type="chanel" name="joy_to_turtlesim" output="screen">
<!--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>
<node respawn="true" pkg="joy" type="joy_node" name="joystick" >
</node>
</launch>
這邊照着參考的寫的話建立的pkg需要放在turtlesim包裡 不然的話就打不開turtlesim
是以在turtlesim包裡建立一個joy_test.launch檔案 裡面寫上打開turtlesim的節點,然後引用就可以了,例如:
<launch>
<node pkg="turtlesim" type="turtlesim_node" name="turtlesim_node" output="screen" />
</launch>
1.2.4 編譯加roslaunch
$cd catkin_ws
$catkin_make -DCATKIN_WHITELIST_PACKAGES="joy_turtlesim"
$roslaunch joy_turtlesim joy_turtlesim.launch
1.2.5 出現未識别/dev/input/js0時
- 可能時在你的 “虛拟機-可移動裝置”裡面沒有選擇連接配接羅技滑鼠
2.把joy加到cmd_vel_mux裡
參考修改
2.1在turtlesim檔案裡建立launch
$cd catkin_ws/src/turtlesim/src
$gedit joy_key_test.launch
加入以下内容
<launch>
<include file="$(find yocs_cmd_vel_mux)/launch/standalone.launch"/>
<node pkg="turtlesim" type="turtlesim_node" name="turtlesim_node" >
<remap from="/turtle1/cmd_vel" to="/yocs_cmd_vel_mux/output/cmd_vel" />
</node>
<node pkg="turtlesim" type="turtle_teleop_key" name="turtle_teleop_key" output="screen">
<remap from="/turtle1/cmd_vel" to="/yocs_cmd_vel_mux/input/keyop" />
</node>
</launch>
2.2添加搖桿搖桿
在joy_turtlesim包裡建立一個no_turtlesim.launch檔案,裡面有teleop+joy
<launch>
<node pkg="joy_turtlesim" type="chanel" name="joy_to_turtlesim" output="screen">
<!--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"/>
<remap from="/turtle1/cmd_vel" to="/yocs_cmd_vel_mux/input/joystick" />
</node>
<node respawn="true" pkg="joy" type="joy_node" name="joystick" >
</node>
</launch>
2.3把搖桿加入mux映射檔案裡打開joy_key_test.launch修改成:
<launch>
<include file="$(find yocs_cmd_vel_mux)/launch/standalone.launch"/>
<node pkg="turtlesim" type="turtlesim_node" name="turtlesim_node" >
<remap from="/turtle1/cmd_vel" to="/yocs_cmd_vel_mux/output/cmd_vel" />
</node>
<node pkg="turtlesim" type="turtle_teleop_key" name="turtle_teleop_key" output="screen">
<remap from="/turtle1/cmd_vel" to="/yocs_cmd_vel_mux/input/keyop" />
</node>
<include file="$(find joy_turtlesim)/launch/no_turtlesim.launch"/>
</launch>
2.4最後一步修改一下配置檔案example.ymal
# Individual subscriber configuration:
# name: Source name
# topic: The topic that provides cmd_vel messages
# timeout: Time in seconds without incoming messages to consider this topic inactive
# priority: Priority: an UNIQUE unsigned integer from 0 (lowest) to MAX_INT
# short_desc: Short description (optional)
subscribers:
- name: "Default input"
topic: "input/default"
timeout: 0.1
priority: 0
short_desc: "The default cmd_vel, controllers unaware that we are multiplexing cmd_vel should come here"
- name: "Joystick control"
topic: "input/joystick"
timeout: 0.1
priority: 1
- name: "Keyboard operation"
topic: "input/keyop"
timeout: 0.1
priority: 2
publisher: "output/cmd_vel"
設定搖桿優先級低于鍵盤 此時就可以了!
2.5運作joy_key_test.launch檔案就可以實作
也可以通過rqt_graph檢視下有沒有用到mux