提纲
问题陈述
原因分析
- 手柄按钮被按下或抬起时,驱动才开始向节点"joy"发布数据,进而触发回调函数;当然,若手柄一直处于按下状态,手柄将不再发布数据,无法触发回调函数。
解决方法
- 声明
ros::Publisher pub;
全局变量,在循环中调用pub.publish(v);
,这样当手柄一直按下时,仍可以读取上一次的速度,手柄抬起时,触发回调函数,速度变为0。
while (ros::ok())
{
pub.publish(v);
ros::spinOnce();
}
修改后的代码
#include <ros/ros.h>
#include <geometry_msgs/Twist.h>
#include <sensor_msgs/Joy.h>
#include <iostream>
using namespace std;
geometry_msgs::Twist v;
ros::Publisher pub;
class Teleop
{
public:
Teleop();
void callback(const sensor_msgs::Joy::ConstPtr &Joy);
ros::NodeHandle n;
ros::Subscriber sub;
double vlinear, vangular;
int axis_ang, axis_lin;
};
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);
pub = n.advertise<geometry_msgs::Twist>("/turtle1/cmd_vel", 10);
sub = n.subscribe<sensor_msgs::Joy>("joy", 10, &Teleop::callback, this);
}
void Teleop::callback(const sensor_msgs::Joy::ConstPtr &Joy)
{
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);
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "logteleop");
Teleop telelog;
while (ros::ok())
{
pub.publish(v);
ros::spinOnce();
}
return 0;
}
launch文件
<launch>
<node pkg="turtlesim" type="turtlesim_node" name="turtlesim_node">
</node>
<node pkg="input_js_control" type="logitech" name="joy_to_turtle" output="screen">
</node>
<node respawn="true" pkg="joy" type="joy_node" name="joystick" >
<node>
</launch>
补充