ros melodic使用罗技f710手柄控制dashgo d1

参考这个博主:https://blog.csdn.net/weixin_40367093/article/details/89848618

下载的包改为melodic

其他大多相同。

由于是差速轮结构,只用到linear.x和anglear.z

#include 
#include 
#include  
#include 

using namespace std;
 
class LogTeleop
{
public:
    LogTeleop();
 
private:
    /* data */
    void LogCallback(const sensor_msgs::Joy::ConstPtr& Joy);
    ros::NodeHandle n;
    ros::Subscriber sub ;
    ros::Publisher pub ;
    double vlinear,vangular;
    int axis_ang_z,axis_lin_x,ton;
};
 
LogTeleop::LogTeleop()
{
    n.param<int>("axis_linear_x",axis_lin_x,1);
    n.param<int>("axis_angular_z",axis_ang_z,2);
    n.param<double>("vel_linear",vlinear,0.1);
    n.param<double>("vel_angular",vangular,0.4);
    n.param<int>("button",ton,6);
    pub= n.advertise<geometry_msgs::Twist>("cmd_vel", 1, true);;
//    pub = n.advertise("/cmd_vel_mux",1);
    sub = n.subscribe<sensor_msgs::Joy>("joy",10,&LogTeleop::LogCallback,this);
}
 
void LogTeleop::LogCallback(const sensor_msgs::Joy::ConstPtr& Joy)
{
	geometry_msgs::Twist twist;

	vlinear = vlinear * (1 + (Joy->axes[5] * 0.1));
	if(vlinear>=0.2)
	   vlinear = 0.2;
	else if (vlinear<=0)
	   vlinear = 0;
	else
	   vlinear = vlinear;
	
	vangular = vangular * (1 +  (Joy->axes[4] * 0.1));
	if(vangular>=0.6)
		vangular = 0.6;
	else if(vangular<=0)
		vangular = 0;
	else
		vangular = vangular;

	if(Joy->buttons[ton])
	{
	    twist.linear.x =(Joy->axes[axis_lin_x])*vlinear;
	    twist.linear.y = 0;
	    twist.linear.z = 0;
	    
	    twist.angular.x = 0;
	    twist.angular.y = 0;
	    twist.angular.z =(Joy->axes[axis_ang_z])*vangular;
		    
		//ROS_INFO("linear_x:%.3lf angular_z:%.3lf",twist.linear.x,twist.angular.z);
		pub.publish(twist);
	}
}

int main(int argc,char** argv)
{
    ros::init(argc, argv, "f710_controller");
    LogTeleop  logteleop;
    ros::spin();
    return 0;
}

launch文件

<launch>
  <arg name="joy_dev" default="/dev/input/js0" />
 
  <node pkg="joy" type="joy_node" name="joy_node">
    <param name="dev" value="$(arg joy_dev)" />
    <param name="deadzone" value="0.05" />
    <param name="autorepeat_rate" value="10" />  <!--检测到键值时键值发送频率单位Hz,100.1m发送一次-->
  </node>
 
  <node pkg="f710_controller" type="f710_controller" name="f710_controller" output="screen">
    <!--input axis -->
      <param name="axis_linear_x" value="1" type="int"/>
      <param name="axis_angular_z" value="2" type="int"/>
    <!--input vel -->
      <param name="vel_linear" value="0.2" type="double"/>
      <param name="vel_angular" value="0.4" type="double"/>
      <param name="button" value="6" type="int"/>
  </node>
</launch>

catkin_make
roslaunch xxx xxx.launch
然后就可以控制了。主要用到了Twist和Joy,发现用ros真的好舒服,不过要学到东西还是要了解怎么写的。

你可能感兴趣的:(ros melodic使用罗技f710手柄控制dashgo d1)