# RM-Linux-Motor-Driver **Repository Path**: dlmu-cone/rm-linux-motor-driver ## Basic Information - **Project Name**: RM-Linux-Motor-Driver - **Description**: Linux上位机电机驱动All-in-one方案 封装CAN通信接口,适配多种常用电机,让你专注宏观功能的实现和开发。 - **Primary Language**: C++ - **License**: MIT - **Default Branch**: main - **Homepage**: None - **GVP Project**: No ## Statistics - **Stars**: 2 - **Forks**: 0 - **Created**: 2024-05-06 - **Last Updated**: 2025-05-23 ## Categories & Tags **Categories**: Uncategorized **Tags**: None ## README # Linux-Motor-Drivers Linux上位机电机驱动All-in-one方案 封装CAN通信接口,适配多种常用电机,让你专注宏观功能的实现和开发。 ## 亮点功能 - 开箱即用的CAN通信 - 开箱即用的电机类 - 通过依赖注入轻松适配自定义通信接口 - 丰富的测试文件,编译运行就能让电机跑起来 ## 适配进度 ### 电机类 - [x] DJI M2006(C610电调) & DJI M3508(C620电调) 支持位置串级PID或速度PID模式 - [x] DM J4310关节电机 支持电机内置的所有模式,需要提前使用官方调试软件进行模式切换及校准 ### 接口类 - [x] 原生CAN接口,在Linux系统中显示为`can0`或`can1`。 - [ ] USB接口的驱动尚在开发中。 ## 设计结构 ![Class Diagram](class.svg) ## 使用方法 ### 配合Jetson AGX Xavier/NX/TX2 或 DJI 妙算 2-G 等支持原生CAN接口的Linux上位机 本仓库已经实现了原生CAN接口的开箱即用。假设您将在上位机上运行ros2_control,您可以: 1. 使用CMake编译并安装驱动: ```bash mkdir build cd build cmake .. make sudo make install ``` 2. 在ros2_control包下的CMakeFile.txt中链接静态库: ```cmake # Link the static library target_link_libraries( arm #The ros2 package name /usr/lib/libmotor_driver_lib.a ) ``` 3. 在源文件中包含motor_drivers.hpp和can_socket.hpp。此处假设您在某ros2_control包的hardware_interface.cpp中: ```cpp #include #include ``` 4. 参考test目录下的xxx_text.cpp,初始化电机对象。例如: ```cpp namespace arm { hardware_interface::CallbackReturn ArmHW::on_init( const hardware_interface::HardwareInfo & info) { if (hardware_interface::SystemInterface::on_init(info) != CallbackReturn::SUCCESS) { return CallbackReturn::ERROR; } /* ------自定义硬件实现------ */ /// 新建电机要使用的CAN硬件接口 MotorDrivers::CANSocket dm4310_s1("can0",0x201, 0x200, 8); /// 新建达妙电机对象 MotorDrivers::MotorDM dm4310_m1(&dm4310_s1); dm4310.motor_Init(); /* ------- ------- */ hw_states_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN()); hw_commands_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN()); return CallbackReturn::SUCCESS; } ``` 5. 使用对象motor_Setxxx()方法设定目标位置/PID等参数,使用motor_Update()方法更新并输出Can帧,使用motor_GetHWInfo()方法更新当前电机信息,使用motor_Getxxx()方法读取当前电机速度/角度/扭矩信息。编写代码过程中,您可自行参考xxx_test.cpp。 ### 使用自定义套接口驱动 本仓库的Inc/motor_sockets目录下存放了可用的套接口驱动。如: - `can_socket.hpp` : 原生CAN接口 - `c_board_usb_socket.hpp` : 大疆开发板C型的USB接口 面对不同的开发场景和套接口,您仅需要包含不同的头文件,创建不同的接口以供电机类使用。 各种套接口的驱动均有开发文档可供参考。直接参考test目录下的测试程序也是很好的选择。 ### 开发自定义套接口驱动 详细的开发过程请参照开发文档,此处简单概述自定义驱动类的开发过程。 假设您需要开发UART转CAN的套接口驱动: - 首先创建继承于`MotorDrivers::HWSocket`类的套接口驱动类,如: ```cpp namespace MotorDrivers{ class CANSocket : public MotorDrivers::HWSocket{} } ``` 接下来实现四个成员方法: - `UARTSocket(const std::string& socketName, uint16_t recvID, uint16_t sendID, uint8_t canDLC)` 驱动类的构造函数。您可以自行决定传入并初始化任意类型的参数; - `bool UARTSocket::socket_Init()` 驱动类的初始化函数,会在电机类被初始化时被同步运行; - `MotorDrivers::SocketFrame UARTSocket::socket_Read()` 驱动类的读取函数,读取电机通讯总线上最近一帧的数据; - `bool UARTSocket::socket_Send(uint8_t* data)` 驱动类的写函数,将data数组发送至通讯总线 测试无误后即开发完毕。 ## Todo - [x] 大疆电机的串级PID调参 - [ ] USB转CAN通信接口的开发 - [ ] 开发文档及网站 - [ ] 更高效的日志类 ## 备忘 m2006伸出:68mm 横移: