话不多说,先上视频!

最近做了个ROS小车,弯腰调车太难受,远程的话WiFi带宽又不够,真是憋屈!

所以呼,用Arduino Nano+XY双轴摇杆模块+无线模块,做了个控制器。

用的rosserial做的,直接写了个cmd_vel的节点在Arduino Nano上面,rosserial真是个好东西!

不多说废话,贴代码!

#include <ros.h>

#include <std_msgs/String.h>
#include "geometry_msgs/Twist.h"

ros::NodeHandle  nh;

geometry_msgs::Twist msg;
ros::Publisher cmd_vel("cmd_vel", &msg);

int moveBindings[2];
float control_speed = 0.5;
float control_turn = 0.5;

void setup()
{
  nh.initNode();
  nh.advertise(cmd_vel);
}

void loop()
{
  int analog_0 = analogRead(0);
  int analog_1 = analogRead(1);
  
  if(analog_0>=400 && analog_0<=600 && analog_1<=100)
  {
    //forward
    moveBindings[0] = 1;
    moveBindings[1] = 0;
  }
  else if(analog_0>=400 && analog_0<=600 && analog_1>=900)
  {
    //back
    moveBindings[0] = -1;
    moveBindings[1] = 0;
  }
  else if(analog_0>=900 && analog_1>=400 && analog_1<=600)
  {
    //left
    moveBindings[0] = 0;
    moveBindings[1] = 1;
  }
  else if(analog_0<=100 && analog_1>=400 && analog_1<=600)
  {
    //right
    moveBindings[0] = 0;
    moveBindings[1] = -1;
  }else if(analog_0>=900 && analog_1<=100)
  {
    //left_forward
    moveBindings[0] = 1;
    moveBindings[1] = 1;
  }else if(analog_0<=100 && analog_1<=100)
  {
    //right_forward
    moveBindings[0] = 1;
    moveBindings[1] = -1;
  }else if(analog_0>=900 && analog_1>=900)
  {
    //left_back
    moveBindings[0] = -1;
    moveBindings[1] = -1;
  }else if(analog_0<=100 && analog_1>=900)
  {
    //right_back
    moveBindings[0] = -1;
    moveBindings[1] = 1;
  }else{
    moveBindings[0] = 0;
    moveBindings[1] = 0;
  }
  
  float target_speed = control_speed * moveBindings[0];
  float target_turn = control_turn * moveBindings[1];
  
  msg.linear.x = target_speed;;
  msg.linear.y = 0;
  msg.linear.z = 0;
  msg.angular.x = 0;
  msg.angular.y = 0;
  msg.angular.z = target_turn;

  cmd_vel.publish( &msg );
  nh.spinOnce();
  delay(10);
}

原理很简单,抄古月老师的mbot_teleop的代码,指定线速度和角速度,通过读取摇杆模块X轴和Y轴的数值,判断摇杆推到了哪。

古月老师原版代码,两个大家可以对比参考一下!

#!/usr/bin/env python3
# -*- coding: utf-8 -*-

import rospy
from geometry_msgs.msg import Twist
import sys, select, termios, tty

msg = """
Control mbot!
---------------------------
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('mbot_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(str(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(str(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(str(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)

明个找俩按键加上去,实现调整线速度、角速度等数值,反正就是古月老师mbot_teleop的翻版!好使!!!

我做的板子,是这样的!焊武大帝登场!

接哪个引脚你们看着定义,我接的A0和A1,摇杆的SW按键我接到了D12,不过这恶按键目前还没用到,后续想想做成啥功能。老铁们也可以推荐下自己的想法!

这玩意玩古月老师的mbot仿真也没啥问题,稳如老狗!

挺好玩!

代码短小精湛!小学妹牵着无人驾驶室出去遛弯建图甚是拉风!成功捕获迷妹一枚!

找机会做个机械臂的控制板来玩玩,等我博客吧