用手柄logitech F310控制底盘

一开始准备制作手柄通过ros发送消息给ESP32,却发现一直发送不成功,经过长时间的测试(大约花了近20多个小时)猜测可能是因为单次发送所有值可能数据量过大,所以改为只发送有用的键值。通过python再转一次,将joy话题的值给拆分出来,一个个传输到ESP32上。

一.上位机

1.构建package

在构建package的时候,由于没有C的一些基础,所以在构建时候出了点问题,以下是正确的方法

创建软件包目录:首先,进入到你的ROS工作空间的 src 目录,并使用 catkin_create_pkg 命令创建一个新的软件包。假设你的工作空间是 ~/ros2_ws,命令可能如下所示:

cd ~/ros2_ws/src
ros2 pkg create --build-type ament_python ros_py_package_joystick

2.新建py

joy_publisher.py


import rclpy
from rclpy.node import Node
from sensor_msgs.msg import Joy
from std_msgs.msg import Float64
class JoyPublisher(Node):
    def __init__(self):
        super().__init__('joy_publisher_node')
        self.publisher_ = self.create_publisher(Float64, 'joyaxisTopic_0', 1000)
        self.subscription = self.create_subscription(
        Joy,
        'joy',
        self.joy_callback,
        100)
        self.subscription # 防止未使用的变量警告

    def joy_callback(self, msg):
        joy_message = Joy()
        self.publisher_.publish(Float64(data=msg.axes[0]))
        self.get_logger().info('Publishing Joy data to joyaxisTopic: ' + str(msg.axes[0]))


def main(args=None):
    rclpy.init(args=args)

    joy_publisher = JoyPublisher()

    try:
        rclpy.spin(joy_publisher)
    except KeyboardInterrupt:
        pass

    joy_publisher.destroy_node()
    rclpy.shutdown()

if __name__ == '__main__':
    main()

以上 构建了一个名为joy_publisher_node的节点,并且通过接受系统的Joy中的第0轴的float转发到joyaxisTopic_0上

3.更改setup.py

from setuptools import find_packages, setup

package_name = 'ros_py_package_joystick'

setup(
    name=package_name,
    version='0.0.0',
    packages=find_packages(exclude=['test']),
    data_files=[
        ('share/ament_index/resource_index/packages',
            ['resource/' + package_name]),
        ('share/' + package_name, ['package.xml']),
    ],
    install_requires=['setuptools'],
    zip_safe=True,
    maintainer='harebert',
    maintainer_email='[email protected]',
    description='TODO: Package description',
    license='TODO: License declaration',
    tests_require=['pytest'],
    entry_points={
    
    
        'console_scripts': [
        	'joyaxisNode=ros_py_package_joystick.joy_publisher:main'
        ],
    },
)

当然,这里先使用setup.py直接了当的进行单轴测试,等到多轴的时候,再用launch

4.编译

在src下进行编译,并打开该节点

colcon build
source install/setup.bash
ros2 run ros_py_package_joystick joyaxisNode

5.打开joy_node

ros2 run joy joy_node

6.检查

打开rqt_graph
如果不出意外的话应该如图所示
在这里插入图片描述
/joy_publisher_node 发送端如图所示:
在这里插入图片描述

用echo查看topic

ros2 topic echo /joyaxisTopic_0

ros2 topic echo /joyaxisTopic_0

二.下位机

一旦把里面的原理想明白了,困难也就迎刃而解了。其实只要将每个电机的速度值,或者占空比传给下位机。下位机其实只需要负责执行就可以了。

1.导入需要的库

; PlatformIO Project Configuration File
;
;   Build options: build flags, source filter
;   Upload options: custom upload port, speed and extra flags
;   Library options: dependencies, extra library storages
;   Advanced options: extra scripting
;
; Please visit documentation for the other options and examples
; https://docs.platformio.org/page/projectconf.html

[env:featheresp32]
platform = espressif32
board = featheresp32
framework = arduino
lib_deps = 
    https://gitee.com/harebert/micro_ros_platformio.git

2.main函数



#include <Arduino.h>

#include <micro_ros_platformio.h>

#include <rcl/rcl.h>
#include <rclc/rclc.h>
#include <rclc/executor.h>

#include <std_msgs/msg/float64.h>

#define AIN1 16 // 电机驱动模块AIN1引脚
#define AIN2 17 // 电机驱动模块AIN2引脚
#define KEY 0   // 按键引脚


rclc_executor_t executor;
rclc_support_t support;
rcl_allocator_t allocator;
rcl_node_t node;
// 声明话题订阅者
rcl_subscription_t subscriber;
// 声明消息文件
std_msgs__msg__Float64 sub_msg;
void callback_subscription_(const void *msgin)
{
    
    
  const std_msgs__msg__Float64 *msg = (const std_msgs__msg__Float64 *)msgin;

  if (msg->data > 0.0)
  {
    
    
   digitalWrite(AIN1, HIGH);
    delay(100);
    digitalWrite(AIN2, LOW);
    delay(100);
  }
  else
  {
    
    
    digitalWrite(AIN1, LOW);
    delay(100);
    digitalWrite(AIN2, HIGH);
    delay(100);
    
  }


}

int motorStatus = 0; // 电机状态变量,0-3循环变化

void setup()
{
    
    
  Serial.begin(115200);    // 初始化串口通信
  pinMode(KEY, INPUT);     // 设置按键引脚为输入模式
  pinMode(AIN1, OUTPUT);   // 设置AIN1引脚为输出模式
  pinMode(AIN2, OUTPUT);   // 设置AIN2引脚为输出模式


  // 设置通过串口进行MicroROS通信
  set_microros_serial_transports(Serial);
  // 延时时一段时间,等待设置完成
  delay(2000);
  // 初始化内存分配器
  allocator = rcl_get_default_allocator();
  // 创建初始化选项
  rclc_support_init(&support, 0, NULL, &allocator);
  // 创建节点 topic_sub_test
  rclc_node_init_default(&node, "topic_sub_test", "", &support);
  // 订阅者初始化
  rclc_subscription_init_default(
      &subscriber,
      &node,
      ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float64),
      "joyaxisTopic_0");
  // 创建执行器
  rclc_executor_init(&executor, &support.context, 1, &allocator);
  // 为执行器添加一个订阅者
  rclc_executor_add_subscription(&executor, &subscriber, &sub_msg, &callback_subscription_, ON_NEW_DATA);
}

void loop()
{
    
    
    delay(100);
  // 循环处理数据

 

     
  rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100));
}


最终的rqt如下图所示
在这里插入图片描述

3.通过手柄摇杆参数,实时控制电机转动

先用左摇杆的前后来控制小车前进和后退
我用的手柄是经典的罗技F310

在这里插入图片描述



#include <Arduino.h>

#include <micro_ros_platformio.h>

#include <rcl/rcl.h>
#include <rclc/rclc.h>
#include <rclc/executor.h>

#include <std_msgs/msg/float64.h>
#include <Esp32McpwmMotor.h>


Esp32McpwmMotor motor; // 创建一个名为motor的对象,用于控制电机

rclc_executor_t executor;
rclc_support_t support;
rcl_allocator_t allocator;
rcl_node_t node;
// 声明话题订阅者
rcl_subscription_t subscriber;
// 声明消息文件
std_msgs__msg__Float64 sub_msg;
void callback_subscription_(const void *msgin)
{
    
    
  const std_msgs__msg__Float64 *msg = (const std_msgs__msg__Float64 *)msgin;
  motor.updateMotorSpeed(0, int16_t(msg->data*100)); // 设置电机0的速度(占空比)为负70%
    motor.updateMotorSpeed(1, int16_t(msg->data*100)); // 设置电机1的速度(占空比)为正70%


}

int motorStatus = 0; // 电机状态变量,0-3循环变化

void setup()
{
    
    
  Serial.begin(115200);    // 初始化串口通信
  motor.attachMotor(0, 16, 17); // 将电机0连接到引脚23和引脚22
    motor.attachMotor(1, 12, 22); // 将电机1连接到引脚12和引脚13


  // 设置通过串口进行MicroROS通信
  set_microros_serial_transports(Serial);
  // 延时时一段时间,等待设置完成
  // delay(2000);
  // 初始化内存分配器
  allocator = rcl_get_default_allocator();
  // 创建初始化选项
  rclc_support_init(&support, 0, NULL, &allocator);
  // 创建节点 topic_sub_test
  rclc_node_init_default(&node, "topic_sub_test", "", &support);
  // 订阅者初始化
  rclc_subscription_init_default(
      &subscriber,
      &node,
      ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float64),
      "joyaxisTopic_0");
  // 创建执行器
  rclc_executor_init(&executor, &support.context, 1, &allocator);
  // 为执行器添加一个订阅者
  rclc_executor_add_subscription(&executor, &subscriber, &sub_msg, &callback_subscription_, ON_NEW_DATA);
}

void loop()
{
    
    
    // delay(100);
  // 循环处理数据

 

     
  rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100));
}