作者:Sam (甄峰) sam_code@hotmail.com
察看node:
$rosnode list
/joy_node
/rosout
看到对应Node是/joy_node
察看此node详细信息:
$rosnode info /joy_node
--------------------------------------------------------------------------------
Node [/joy_node]
Publications:
* /diagnostics [diagnostic_msgs/DiagnosticArray]
* /joy [sensor_msgs/Joy]
* /rosout [rosgraph_msgs/Log]
Subscriptions: None
Services:
* /joy_node/get_loggers
* /joy_node/set_logger_level
contacting node http://ubuntu:43877/ ...
Pid: 10153
Connections:
* topic: /rosout
* to: /rosout
* direction: outbound
* transport: TCPROS
可以看到,这个Node发布着/joy Topic
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
#include "ros/ros.h"
#include "sensor_msgs/Joy.h"
#include "geometry_msgs/Twist.h"
ros::Publisher pub;
geometry_msgs::Twist msg_twist;
void messageCallback(const sensor_msgs::Joy::ConstPtr& msg);
void messageCallback(const sensor_msgs::Joy::ConstPtr& msg)
{
ROS_INFO("Key: %f. %f. %f. %f. %f. %f", msg->axes[0], msg->axes[1], msg->axes[2], msg->axes[3], msg->axes[4],msg->axes[5]);
msg_twist.linear.x = (int) msg->axes[5];
msg_twist.linear.y = 0;
msg_twist.linear.z = 0;
msg_twist.angular.x = 0;
msg_twist.angular.y = 0;
msg_twist.angular.z = (int) msg->axes[4];
pub.publish(msg_twist);
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "x9_turtlesim");
ros::NodeHandle n_sub;
ros::NodeHandle n_advert;
pub = n_advert.advertise("turtle1/cmd_vel", 1000);
ros::Subscriber sub = n_sub.subscribe("joy", 1000, messageCallback);
ros::spin();
return 0;
}
这次学习如何将ROS所支持的外设与我们本身的程序结合在一起使用。
例如:已经有底盘,或者使用turtlesim小乌龟程序。
如何使用游戏手柄来控制底盘或小乌龟。如何使用使用激光雷达等。
1.
使用游戏手柄控制Turtlesim小乌龟:
1.1:相关包的安装:
在使用游戏手柄前,需要先安装joystick, ros-indigo-joy,
ros-indigo-joystick-drivers等包。
1.2: 硬件设别:
把USB插口或USB Dongle插入系统。 察看/dev/input/中是否创建了js0 这个node.
如果建立,说明硬件设备被识别。
此时, cat /dev/input/js0
按下手柄按键,会看到一些乱码。他们是按照input数据格式发送的。这也说明,硬件连接成功了。
1.3: 察看和解析硬件数据:
硬件数据发出了,通过/dev/input/js0 或者 /dev/hidrawX在Linux层面显现出来。
但它的ROS Driver是如何解析这些数据的呢?
又是通过何种途径(Topic)把解析后的数据发送出来的呢?下面就分析这个问题。
1.3.1:
$roscore
先运行 ROS Package Joy
中的joy_node.来分析它如何把数据发送成何种Topic,里面消息类型是怎样:
$rosrun joy joy_node
[ INFO] [1478056976.955143122]: Opened joystick: /dev/input/js0. deadzone_: 0.050000.
[ INFO] [1478056976.955143122]: Opened joystick: /dev/input/js0. deadzone_: 0.050000.
显示正常打开了JoySticks。
察看node:
$rosnode list
/joy_node
/rosout
看到对应Node是/joy_node
察看此node详细信息:
$rosnode info /joy_node
--------------------------------------------------------------------------------
Node [/joy_node]
Publications:
* /diagnostics [diagnostic_msgs/DiagnosticArray]
* /joy [sensor_msgs/Joy]
* /rosout [rosgraph_msgs/Log]
Subscriptions: None
Services:
* /joy_node/get_loggers
* /joy_node/set_logger_level
contacting node http://ubuntu:43877/ ...
Pid: 10153
Connections:
* topic: /rosout
* to: /rosout
* direction: outbound
* transport: TCPROS
可以看到,这个Node发布着/joy Topic
看Topic具体数据
$rostopic echo /joy
header:
seq: 388
stamp:
secs: 1478057805
nsecs: 210471365
frame_id: ''
axes: [-0.0, -0.0, -0.0, -0.0, -0.0, -1.0]
buttons: [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
---
header:
seq: 389
stamp:
secs: 1478057805
nsecs: 274450075
frame_id: ''
axes: [-0.0, -0.0, -0.0, -0.0, -0.0, -0.0]
buttons: [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
看此Topic类型:
rostopic type /joy
sensor_msgs/Joy
看消息具体数据:
rosmsg show sensor_msgs/Joy
std_msgs/Header header
uint32 seq
time stamp
string frame_id
float32[] axes
int32[] buttons
$rostopic echo /joy
header:
seq: 388
stamp:
secs: 1478057805
nsecs: 210471365
frame_id: ''
axes: [-0.0, -0.0, -0.0, -0.0, -0.0, -1.0]
buttons: [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
---
header:
seq: 389
stamp:
secs: 1478057805
nsecs: 274450075
frame_id: ''
axes: [-0.0, -0.0, -0.0, -0.0, -0.0, -0.0]
buttons: [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
看此Topic类型:
rostopic type /joy
sensor_msgs/Joy
看消息具体数据:
rosmsg show sensor_msgs/Joy
std_msgs/Header header
uint32 seq
time stamp
string frame_id
float32[] axes
int32[] buttons
这最终就看出了,Joy_Node是通过/Joy Topic来发布数据,类型为sensor_msgs/Joy.
数据包括Axes和Button数据各几个。
1.4: 分析小乌龟需要什么数据:
1.4.1: 运行小乌龟:
$rosrun turtlesim turtlesim_node
1.4.2: 察看Node,小乌龟Node是/turtlesim
$rosnode list
/rosout
/turtlesim
1.4.3:
$rosrun turtlesim turtlesim_node
1.4.2: 察看Node,小乌龟Node是/turtlesim
$rosnode list
/rosout
/turtlesim
1.4.3:
察看此node具体信息:
$rosnode info /turtlesim
--------------------------------------------------------------------------------
Node [/turtlesim]
Publications:
* /turtle1/color_sensor [turtlesim/Color]
* /rosout [rosgraph_msgs/Log]
* /turtle1/pose [turtlesim/Pose]
Subscriptions:
* /turtle1/cmd_vel [unknown type]
Services:
* /turtle1/teleport_absolute
* /turtlesim/get_loggers
* /turtlesim/set_logger_level
* /reset
* /spawn
* /clear
* /turtle1/set_pen
* /turtle1/teleport_relative
* /kill
contacting node http://ubuntu:37852/ ...
Pid: 15512
Connections:
* topic: /rosout
* to: /rosout
* direction: outbound
* transport: TCPROS
1.4.4: 察看Topic Type:
rostopic type /turtle1/cmd_vel
geometry_msgs/Twist
1.4.5: 此Message格式:
$rosnode info /turtlesim
--------------------------------------------------------------------------------
Node [/turtlesim]
Publications:
* /turtle1/color_sensor [turtlesim/Color]
* /rosout [rosgraph_msgs/Log]
* /turtle1/pose [turtlesim/Pose]
Subscriptions:
* /turtle1/cmd_vel [unknown type]
Services:
* /turtle1/teleport_absolute
* /turtlesim/get_loggers
* /turtlesim/set_logger_level
* /reset
* /spawn
* /clear
* /turtle1/set_pen
* /turtle1/teleport_relative
* /kill
contacting node http://ubuntu:37852/ ...
Pid: 15512
Connections:
* topic: /rosout
* to: /rosout
* direction: outbound
* transport: TCPROS
1.4.4: 察看Topic Type:
rostopic type /turtle1/cmd_vel
geometry_msgs/Twist
1.4.5: 此Message格式:
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
结合以上信息,就可以得出结论:
当前需要一个Node, 它接收/joy
Topic,/Joy Topic中的数据类型是sensor_msgs/Joy,
把其中的数据转换,发送/turtle1/cmd_vel ,数据类型是:geometry_msgs/Twist
就可以把手柄数据和小乌龟所需数据连接起来了。
#include "ros/ros.h"
#include "sensor_msgs/Joy.h"
#include "geometry_msgs/Twist.h"
ros::Publisher pub;
geometry_msgs::Twist msg_twist;
void messageCallback(const sensor_msgs::Joy::ConstPtr& msg);
void messageCallback(const sensor_msgs::Joy::ConstPtr& msg)
{
ROS_INFO("Key: %f. %f. %f. %f. %f. %f", msg->axes[0], msg->axes[1], msg->axes[2], msg->axes[3], msg->axes[4],msg->axes[5]);
msg_twist.linear.x = (int) msg->axes[5];
msg_twist.linear.y = 0;
msg_twist.linear.z = 0;
msg_twist.angular.x = 0;
msg_twist.angular.y = 0;
msg_twist.angular.z = (int) msg->axes[4];
pub.publish(msg_twist);
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "x9_turtlesim");
ros::NodeHandle n_sub;
ros::NodeHandle n_advert;
pub = n_advert.advertise("turtle1/cmd_vel", 1000);
ros::Subscriber sub = n_sub.subscribe("joy", 1000, messageCallback);
ros::spin();
return 0;
}