树莓派4B使用ROS2系统驱动无人船(无刷电机)

ROS2作为常用的机器人开源系统,常常被部署到各种平台,本博客以树莓派4B为平台,Ubuntu22.04为系统,ROS2版本为humble。ROS2配置见前一篇博客:

Ubuntu22.04配置ROS2(2024最新)-CSDN博客

1.线路连接

无人船一般使用无刷电机,无刷电机一般有三根线,分别是正极、负极和信号线,需要用pwm信号来驱动,接线时,将电机的信号线与树莓派的PWM引脚相连,树莓派的PWM引脚分为硬件接口和软件接口,软件接口的使用很容易出现问题,因此我们使用硬件接口,即GPIO12,GPIO13,GPIO18和GPIO19,

引脚图如上,可对应树莓派4B进行参照。

2.pigpio库下载

树莓派官方有专门的库来产生PWM信号,但存在着一定延迟,因此我们采用第三方库pigpio。

如果直接下载pigpio会显示找不到库,因为我们通过github链接进行下载:

在命令行依次输入以下指令:

wget https://github.com/joan2937/pigpio/archive/master.zip
unzip master.zip

然后定位到安装的文件夹,并进行编译:

cd pigpio-master
make

之后进行安装:

sudo apt install python-setuptools python3-setuptools
sudo make install
sudo pigpiod

注意使用该库需要输入sudo pigpiod,否则会没有权限。

3.代码编写

mport rclpy
from rclpy.node import Node
from geometry_msgs.msg import Twist
from std_msgs.msg import Int32MultiArray
import pigpio
import time

class MotorController(Node):
    def __init__(self, name):
        super().__init__(name)
        self.sub_cmd_vel = self.create_subscription(Twist, '/cmd_vel', self.cmd_vel_callback, 10)
        self.pub_pwm = self.create_publisher(Int32MultiArray, '/motor_pwm', 10)

        # 初始化pigpio
        self.pi = pigpio.pi()
        if not self.pi.connected:
            raise RuntimeError("pigpio not connected!")

        self.motor1_pwm_pin = 13  # 硬件PWM GPIO12 (BCM编码)
        self.motor2_pwm_pin = 12  # 硬件PWM GPIO13 (BCM编码)

        # PWM参数
        self.pwm_center = 1500
        self.pwm_forward = 1750
        self.pwm_reverse = 1250
        self.pwm_stop = self.pwm_center

        # 确保PWM频率设置为50Hz
        self.pi.set_PWM_frequency(self.motor1_pwm_pin, 50)
        self.pi.set_PWM_frequency(self.motor2_pwm_pin, 50)


        self.pi.set_servo_pulsewidth(self.motor1_pwm_pin, 1500)
        self.pi.set_servo_pulsewidth(self.motor2_pwm_pin, 1500)
        time.sleep(3)


    def set_pwm(self, motor1_pwm_value, motor2_pwm_value):
        # 设置电机的PWM值,转化为硬件PWM接口的百分比占空比
        self.pi.set_servo_pulsewidth(self.motor1_pwm_pin, motor1_pwm_value)
        self.pi.set_servo_pulsewidth(self.motor2_pwm_pin, motor2_pwm_value)

        # 发布PWM信号
        pwm_msg = Int32MultiArray()
        pwm_msg.data = [motor1_pwm_value, motor2_pwm_value]
        self.pub_pwm.publish(pwm_msg)

    def cmd_vel_callback(self, msg):
        linear = msg.linear.x
        angular = msg.angular.z

        if linear == 0.0:
            if angular > 0.0:
                # 左转
                self.set_pwm(self.pwm_reverse, self.pwm_reverse)
            elif angular < 0.0:
                # 右转
                self.set_pwm(self.pwm_forward, self.pwm_forward)
            else:
                # 停止
                self.set_pwm(self.pwm_stop, self.pwm_stop)
        elif linear < 0.0:
                self.set_pwm(self.pwm_reverse, self.pwm_forward)
        else:
            if angular == 0.0:
                # 前进
                self.set_pwm(1650,1350)
            else:
                # 前进时左转或右转,根据角速度实现
                left_pwm = self.pwm_forward + angular * 100  # 简单计算,具体需要根据实际需求调整
                right_pwm = self.pwm_forward - angular * 100
                self.set_pwm(left_pwm, right_pwm)

    def cleanup(self):
        # 在程序停止时将电机PWM设置为1500
        self.set_pwm(self.pwm_stop, self.pwm_stop)
        self.pi.stop()

def main(args=None):
    rclpy.init(args=args)
    motor_controller = MotorController("motor_controller")
    print("Motor Controller Node Started")

    try:
        rclpy.spin(motor_controller)
    except KeyboardInterrupt:
        pass
    finally:
        motor_controller.cleanup()
        motor_controller.destroy_node()
        rclpy.shutdown()

if __name__ == '__main__':
    main()

根据自身需要修改相关参数。

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值