< >
Home » ROS与传感器教程 » ROS与传感器教程-整合G29方向盘的力反馈

ROS与传感器教程-整合G29方向盘的力反馈

ROS与传感器教程-整合G29方向盘的力反馈

说明:

  • 介绍如何通过力反馈来控制G29方向盘
  • 比如根据仿真车辆的转向同步到G29方向盘,或者ros话题来控制G29转动
  • 默认使用的方向盘是罗技G29方向盘

淘宝:

步骤:

  • 下载和安装驱动
$ cd catkin_ws/src 
$ git clone https://github.com/ncnynl/ros-g29-force-feedback.git
$ cd ../ 
$ catkin_make
  • 确认方向盘端口
cat /proc/bus/input/devices
  • 效果如下:
I: Bus=0003 Vendor=046d Product=c24f Version=0111
N: Name="Logitech G29 Driving Force Racing Wheel"
P: Phys=usb-0000:02:00.0-2.1/input0
S: Sysfs=/devices/pci0000:00/0000:00:11.0/0000:02:00.0/usb2/2-2/2-2.1/2-2.1:1.0/0003:046D:C24F.0007/input/input13
U: Uniq=
H: Handlers=event5 js0 
B: PROP=0
B: EV=20001b
B: KEY=1ff 0 0 0 0 0 0 ffff00000000 0 0 0 0
B: ABS=30027
B: MSC=10
B: FF=300040000 0
  • 说明端口为js0和event5, /dev/input/js0为方向盘控制端口,/dev/input/event5为力反馈作用端口
  • 修改配置
vim ~/catkin_ws2/src/ros-g29-force-feedback/g29_force_feedback.yaml 
  • 修改
device_name: "/dev/input/event19"
为
device_name: "/dev/input/event5"
  • 启动
$ source ~/catkin_ws2/devel/setup.bash
$ rosparam load ~/catkin_ws2/src/ros-g29-force-feedback/g29_force_feedback.yaml
$ rosrun g29_force_feedback node
  • 发送命令
rostopic pub /ff_target g29_force_feedback/ForceFeedback "
angle: 0.3 
force: 0.6"
  • 通过脚本控制
  • 新建脚本:vim talker.py
  • 内容如下:
#!/usr/bin/env python                                                                                                                 
import rospy

from std_msgs.msg import String
from g29_force_feedback.msg import ForceFeedback

def talker():
    rospy.init_node('talker')
    pub = rospy.Publisher('ff_target', ForceFeedback, queue_size=20)
#    pub = rospy.Publisher('g29test', String, queue_size=20)                                                                          

    r = rospy.Rate(0.5)
    while not rospy.is_shutdown():
      # str = "angle: 0.5 force: 0.6"                                                                                                 
      g29msg = ForceFeedback()
      g29msg.angle = 0.0
      g29msg.force = 0.6
      rospy.loginfo(g29msg)
      pub.publish(g29msg)
      #break                                                                                                                          
      r.sleep()

if __name__ == '__main__':
    try:
        talker()
    except rospy.ROSInterruptException: pass
  • 运行: python talker.py

  • 通过话题控制

  • 新建文件vim g29_callback.py

#!/usr/bin/env python                                                                                                                            
import rospy

from sensor_msgs.msg import Joy
from g29_force_feedback.msg import ForceFeedback

pub = None

def joy_callback(joy_msg):
    rospy.loginfo("recieved axes0: %s", joy_msg.axes[0])
    g29msg = ForceFeedback()
    g29msg.angle = joy_msg.axes[0] * -1.0
    g29msg.force = 0.5
    rospy.loginfo(g29msg)
    pub.publish(g29msg)
    # now = rospy.Time.now()                                                                                                                     
    # rospy.loginfo("now: %f", now.to_sec())                                                                                                     

if __name__ == '__main__':
    rospy.init_node('ps4tog29')
    rospy.Subscriber("joy", Joy, joy_callback, queue_size=1)
    pub = rospy.Publisher('ff_target', ForceFeedback, queue_size=20)
    rospy.spin()
  • 运行: python g29_callback.py
  • 发送话题到joy_callback来控制移动

纠错,疑问,交流: 请进入讨论区点击加入Q群

获取最新文章: 扫一扫右上角的二维码加入“创客智造”公众号


标签: ros与传感器教程