基于ArbotiX和rviz的仿真

  1. 安装ArbotiX
$ git clone  https://github.com/vanadiumlabs/arbotix_ros.git

下载完成后,在工作空间的路径下使用catkin_make命令编译
并进行source
2. 配置ArbotiX控制器
创建启动ArbotiX节点的launch文件
mrobot_description/launch/arbotix_mrobot_with_kinect.launch,代码如下:


    

    
    
    

    
    

    
        
        
    

    

    
        
    

   

该launch文件添加了arbotix_driver的内容
该节点还需加载控制器相关配置文件,该配置文件在功能包config路径下
创建配置文件mrobot_description/config/fake_mrobot_arbotix.yaml的内容如下

controllers: {
   base_controller: {type: diff_controller, base_frame_id: base_footprint, base_width: 0.26, ticks_meter: 4100, Kp: 12, Kd: 12, Ki: 0, Ko: 50, accel_limit: 1.0 }
}
  1. 创建功能包mrobot_teleop
$ cd ~/catkin_ws/src
$ catkin_create_pkg mrobot_teleop geometry_msgs rospy roscpp

再回到工作空间根目录下进行编译

$ cd ~/catkin_ws
$ catkin_make 
$ source ~/catkin_ws/devel/setup.bash

而后再在此功能包下创建两个文件夹launch和scripts
在launch文件下创建文件mrobot_teleop.launch


   
      
     
     
  
  

  1. 在launch文件下创建文件logitech.launch


  
  

  
    
    
    
  




5.在文件夹scripts下创建mrobot_teleop.py

#!/usr/bin/env python
# -*- coding: utf-8 -*-
import rospy
from geometry_msgs.msg import Twist
import sys, select, termios, tty

msg = """
Control mrobot!
---------------------------
Moving around:
   u    i    o
   j    k    l
   m    ,    .

q/z : increase/decrease max speeds by 10%
w/x : increase/decrease only linear speed by 10%
e/c : increase/decrease only angular speed by 10%
space key, k : force stop
anything else : stop smoothly

CTRL-C to quit
"""

moveBindings = {
        'i':(1,0),
        'o':(1,-1),
        'j':(0,1),
        'l':(0,-1),
        'u':(1,1),
        ',':(-1,0),
        '.':(-1,1),
        'm':(-1,-1),
         }

speedBindings={
        'q':(1.1,1.1),
        'z':(.9,.9),
        'w':(1.1,1),
        'x':(.9,1),
        'e':(1,1.1),
        'c':(1,.9),
          }

def getKey():
    tty.setraw(sys.stdin.fileno())
    rlist, _, _ = select.select([sys.stdin], [], [], 0.1)
    if rlist:
        key = sys.stdin.read(1)
    else:
        key = ''

termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
    return key

speed = .2
turn = 1

def vels(speed,turn):
    return "currently:\tspeed %s\tturn %s " % (speed,turn)

if __name__=="__main__":
    settings = termios.tcgetattr(sys.stdin)

rospy.init_node('mrobot_teleop')
    pub = rospy.Publisher('/cmd_vel', Twist, queue_size=5)

x = 0
    th = 0
    status = 0
    count = 0
    acc = 0.1
    target_speed = 0
    target_turn = 0
    control_speed = 0
    control_turn = 0
    try:
        print msg
        print vels(speed,turn)
        while(1):
            key = getKey()
            # 运动控制方向键(1:正方向,-1负方向)
            if key in moveBindings.keys():
                x = moveBindings[key][0]
                th = moveBindings[key][1]
                count = 0
            # 速度修改键
            elif key in speedBindings.keys():
                speed = speed * speedBindings[key][0]  # 线速度增加0.1倍
                turn = turn * speedBindings[key][1]    # 角速度增加0.1倍
                count = 0

print vels(speed,turn)
if (status == 14):
                    print msg
                status = (status + 1) % 15
            # 停止键
            elif key == ' ' or key == 'k' :
                x = 0
                th = 0
                control_speed = 0
                control_turn = 0
            else:
                count = count + 1
                if count > 4:
                    x = 0
                    th = 0
                if (key == '\x03'):
                    break

# 目标速度=速度值*方向值
            target_speed = speed * x
            target_turn = turn * th

# 速度限位,防止速度增减过快
            if target_speed > control_speed:
                control_speed = min( target_speed, control_speed + 0.02 )
            elif target_speed < control_speed:
                control_speed = max( target_speed, control_speed - 0.02 )
            else:
                control_speed = target_speed

if target_turn > control_turn:
                control_turn = min( target_turn, control_turn + 0.1 )
            elif target_turn < control_turn:
                control_turn = max( target_turn, control_turn - 0.1 )
            else:
                control_turn = target_turn

# 创建并发布twist消息
            twist = Twist()
            twist.linear.x = control_speed; 
            twist.linear.y = 0; 
            twist.linear.z = 0
            twist.angular.x = 0; 
            twist.angular.y = 0; 
            twist.angular.z = control_turn
            pub.publish(twist)

except:
        print e

finally:
        twist = Twist()
        twist.linear.x = 0; twist.linear.y = 0; twist.linear.z = 0
        twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = 0
        pub.publish(twist)

termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)

下载teleop_twist_keyboard

$ cd ~/catkin_ws/src
$ git clone https://github.com/ros-teleop/teleop_twist_keyboard.git
$ cd ~/catkin_ws
$ catkin_make
$ source ./devel/setup.bash
$ exportROBOT=mover
$ roslaunch mrobot_description arbotix_mrobot_with_kinect.launch
$ rosrun tf static_transform_publisher 0.0 0.0 0.0 0.0 0.0 0.0 map my_frame 100
$ roslaunch mrobot_teleop mrobot_teleop.launch

(若动不了的话:运行$ rosrun teleop_twist_keyboard teleop_twist_keyboard.py
通过采用键盘控制模拟机器人,模拟机器人开始移动。注意鼠标指针必须位于teleop_twist_keyboard终端页面,否则控制键盘模拟机器人无法移动。键盘控制各个键介绍:

U I O
J K L
M < >
K—停止I、J、<、L—前、左、后、右q/z : 最大速度增加/减少10%w/x : 仅线性速度增加10%e/c : 仅角速度增加10%)
基于ArbotiX和rviz的仿真_第1张图片
注:在启动$ roslaunch mrobot_teleop mrobot_teleop.launch时出现如下错误

ERROR: cannot launch node of type [mrobot_teleop/mrobot_teleop.py]: can’t locate node [mrobot_teleop.py] in package [mrobot_teleop]
错误:无法启动类型为[mrobot_teleop / mrobot_teleop.py]的节点:无法找到程序包[mrobot_teleop]中的节点[mrobot_teleop.py]

解决办法:把自己写的节点设置为可执行文件权限
cd 节点根目录名(进入到你存放节点代码的目录下)
chmod 777 节点代码 (把权限设置为777)
eg:(以《ROS机器人开发实践》 胡春旭著的代码为例)
转到→ mrobot_teleop
chmod 777 mrobot_teleop.py
即可。

你可能感兴趣的:(ROS学习基础)