diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 0000000..92af353 --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,67 @@ +cmake_minimum_required(VERSION 3.8) +project(amadeus_26) + +# 使用 C++17 +set(CMAKE_CXX_STANDARD 17) +set(CMAKE_CXX_STANDARD_REQUIRED ON) + +# 查找依赖 +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(std_msgs REQUIRED) + +# 查找 serial 库 (用于 UART 节点) +find_package(serial REQUIRED) + +# 添加 SDK 库路径 +set(TRANSMITTER_SDK_PATH ${CMAKE_CURRENT_SOURCE_DIR}/lib/transmitter_sdk) +link_directories(${TRANSMITTER_SDK_PATH}/lib/linux/x64) + +# 包含目录 +include_directories( + ${CMAKE_CURRENT_SOURCE_DIR} + ${TRANSMITTER_SDK_PATH}/inc +) + +# ==================== CAN 节点 ==================== +add_executable(transmitter_test_node src/transmitter_test_node.cpp) + +set_target_properties(transmitter_test_node PROPERTIES + BUILD_WITH_INSTALL_RPATH FALSE + LINK_FLAGS "-Wl,-rpath,'${TRANSMITTER_SDK_PATH}/lib/linux/x64'" +) + +ament_target_dependencies(transmitter_test_node + rclcpp + std_msgs +) + +target_link_libraries(transmitter_test_node + dm_device + usb-1.0 + pthread +) + +# ==================== UART 节点 ==================== +add_executable(uart_transmitter_node src/uart_transmitter_node.cpp) + +ament_target_dependencies(uart_transmitter_node + rclcpp + std_msgs + serial +) + +# ==================== 安装目标 ==================== +install(TARGETS + transmitter_test_node + uart_transmitter_node + DESTINATION lib/${PROJECT_NAME} +) + +# 安装 launch 文件 +install(DIRECTORY launch + DESTINATION share/${PROJECT_NAME} + OPTIONAL +) + +ament_package() \ No newline at end of file diff --git a/docs/Transmit/ctrl_command.md b/docs/Transmit/ctrl_command.md index a1bdb81..b80bec6 100644 --- a/docs/Transmit/ctrl_command.md +++ b/docs/Transmit/ctrl_command.md @@ -1,27 +1,10 @@ # 控制指令的发送说明 -在主机外接收的控制板中的控制代码的实现是: +在主机外接收的控制板中的控制协议是: + +| 帧头1 | 帧头2 | 平动左右 | 平动前后 | 云台偏航 | 云台俯仰 | 拨弹轮 | 左拨杆 | 右拨杆 | CRC8 | 帧尾 | +| --- | --- | --- | --- | --- | --- | --- | --- | --- | --- | --- | +| 1 | 1 | 2 | 2 | 2 | 2 | 2 | 0.5 | 0.5 | 1 | 1 | -```c -// CAN 速率 1000kbps -void CToC_CANDataProcess(unit32_t ID, uint8_t *Data) -{ - // 以下所有变量有效范围为 [-660,660] - if(ID == 0x149) // 运动控制 - { - - Remote_RxData.Remote_R_RL =(int16_t)((uint16_t)Data[0]<<8 | Data[1]); // 平动 X 轴(左右) - Remote_RxData.Remote_R_UD =(int16_t)((uint16_t)Data[2]<<8 | Data[3]); // 平动 Y 轴(前后) - Remote_RxData.Remote_L_RL =(int16_t)((uint16_t)Data[4]<<8 | Data[5]); // 云台偏航 (左右) - Remote_RxData.Remote_L_UD =(int16_t)((uint16_t)Data[6]<<8 | Data[7]); // 云台俯仰 (上下) - } - else if(ID == 0x189) // 攻击控制 - { - Remote_RxData.Remote_ThumbWheel =(int16_t)((uint16_t)Data[0]<<8 | Data[1]); // 拨弹盘(进弹/退弹),660 为进弹,0 为关闭,-660 为退弹 - Remote_RxData.Remote_RS =(int16_t)((uint16_t)Data[2]<<8 | Data[3]); // 小陀螺(反自瞄)开关,置 660 为开启,0 为关闭 - Remote_RxData.Remote_LS =(int16_t)((uint16_t)Data[4]<<8 | Data[5]); // 摩擦轮开关, 置 660 为开启,0 为关闭 - } -} -``` 两个 ID 分别是云台和底盘的控制板,在处于进点/回家状态时不应开启小陀螺,发射弹丸需要**打开摩擦轮 同时 进弹**,因此只有在处于攻击状态时开启摩擦轮,此时可以将进弹视为扳机。 \ No newline at end of file diff --git a/launch/uart_transmitter.launch.py b/launch/uart_transmitter.launch.py new file mode 100644 index 0000000..9a63af6 --- /dev/null +++ b/launch/uart_transmitter.launch.py @@ -0,0 +1,102 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration + + +def generate_launch_description(): + # 声明启动参数 + serial_port_arg = DeclareLaunchArgument( + 'serial_port', + default_value='/dev/ttyUSB0', + description='CH340 串口设备路径' + ) + + baudrate_arg = DeclareLaunchArgument( + 'baudrate', + default_value='921600', + description='串口波特率' + ) + + send_frequency_arg = DeclareLaunchArgument( + 'send_frequency', + default_value='50.0', + description='发送频率 (Hz)' + ) + + # 控制参数 + x_move_arg = DeclareLaunchArgument( + 'x_move', + default_value='0', + description='平动左右 [-660, 660]' + ) + + y_move_arg = DeclareLaunchArgument( + 'y_move', + default_value='0', + description='平动前后 [-660, 660]' + ) + + yaw_arg = DeclareLaunchArgument( + 'yaw', + default_value='0', + description='云台偏航 [-660, 660]' + ) + + pitch_arg = DeclareLaunchArgument( + 'pitch', + default_value='0', + description='云台俯仰 [-660, 660]' + ) + + feed_arg = DeclareLaunchArgument( + 'feed', + default_value='0', + description='拨弹轮 [-660, 660]' + ) + + left_switch_arg = DeclareLaunchArgument( + 'left_switch', + default_value='0', + description='左拨杆 [0, 15]' + ) + + right_switch_arg = DeclareLaunchArgument( + 'right_switch', + default_value='0', + description='右拨杆 [0, 15]' + ) + + # 创建节点 + uart_transmitter_node = Node( + package='amadeus_26', + executable='uart_transmitter_node', + name='uart_transmitter_node', + output='screen', + parameters=[{ + 'serial_port': LaunchConfiguration('serial_port'), + 'baudrate': LaunchConfiguration('baudrate'), + 'send_frequency': LaunchConfiguration('send_frequency'), + 'x_move': LaunchConfiguration('x_move'), + 'y_move': LaunchConfiguration('y_move'), + 'yaw': LaunchConfiguration('yaw'), + 'pitch': LaunchConfiguration('pitch'), + 'feed': LaunchConfiguration('feed'), + 'left_switch': LaunchConfiguration('left_switch'), + 'right_switch': LaunchConfiguration('right_switch'), + }], + ) + + return LaunchDescription([ + serial_port_arg, + baudrate_arg, + send_frequency_arg, + x_move_arg, + y_move_arg, + yaw_arg, + pitch_arg, + feed_arg, + left_switch_arg, + right_switch_arg, + uart_transmitter_node, + ]) \ No newline at end of file diff --git a/src/uart_transmitter_node.cpp b/src/uart_transmitter_node.cpp new file mode 100644 index 0000000..cfc630d --- /dev/null +++ b/src/uart_transmitter_node.cpp @@ -0,0 +1,309 @@ +/** + * @file uart_transmitter_node.cpp + * @brief UART 串口收发模块测试节点 (CH340) + * + * 使用 CH340 USB 转串口模块发送控制指令 + * 波特率:921600 (与裁判系统一致) + * 协议帧格式: + * | 帧头1 | 帧头2 | 平动左右 | 平动前后 | 云台偏航 | 云台俯仰 | 拨弹轮 | 拨杆 | CRC8 | 帧尾 | + * | 0xAA | 0x55 | 2 bytes | 2 bytes | 2 bytes | 2 bytes | 2 bytes|1 byte| 1byte| 0xFF | + */ + +#include +#include +#include +#include +#include +#include + +// 帧定义 +constexpr uint8_t FRAME_HEADER_1 = 0xAA; +constexpr uint8_t FRAME_HEADER_2 = 0x55; +constexpr uint8_t FRAME_TAIL = 0xFF; +constexpr int FRAME_LENGTH = 14; // 总帧长度 + +// 默认串口设备 +constexpr const char* DEFAULT_SERIAL_PORT = "/dev/ttyUSB0"; +constexpr int DEFAULT_BAUDRATE = 115200; + +class UartTransmitterNode : public rclcpp::Node +{ +public: + UartTransmitterNode() : Node("uart_transmitter_node") + { + // 声明参数 + this->declare_parameter("serial_port", DEFAULT_SERIAL_PORT); + this->declare_parameter("baudrate", DEFAULT_BAUDRATE); + this->declare_parameter("send_frequency", 50.0); // Hz + + // 控制参数 + this->declare_parameter("x_move", 0); // 平动左右 [-660, 660] + this->declare_parameter("y_move", 0); // 平动前后 [-660, 660] + this->declare_parameter("yaw", 0); // 云台偏航 [-660, 660] + this->declare_parameter("pitch", 0); // 云台俯仰 [-660, 660] + this->declare_parameter("feed", 0); // 拨弹轮 [-660, 660] + this->declare_parameter("left_switch", 0); // 左拨杆 [0, 15] + this->declare_parameter("right_switch", 0); // 右拨杆 [0, 15] + + // 获取参数 + serial_port_ = this->get_parameter("serial_port").as_string(); + baudrate_ = this->get_parameter("baudrate").as_int(); + send_frequency_ = this->get_parameter("send_frequency").as_double(); + + RCLCPP_INFO(this->get_logger(), "================================="); + RCLCPP_INFO(this->get_logger(), "UART 收发模块测试节点启动"); + RCLCPP_INFO(this->get_logger(), "串口: %s", serial_port_.c_str()); + RCLCPP_INFO(this->get_logger(), "波特率: %d", baudrate_); + RCLCPP_INFO(this->get_logger(), "发送频率: %.1f Hz", send_frequency_); + RCLCPP_INFO(this->get_logger(), "================================="); + + // 初始化串口 + if (!initSerial()) { + RCLCPP_ERROR(this->get_logger(), "串口初始化失败,节点退出"); + rclcpp::shutdown(); + return; + } + + // 创建发布者 + connection_status_pub_ = this->create_publisher("transmitter/connection_status", 10); + + // 创建定时器 - 发送数据 + auto send_period = std::chrono::duration(1.0 / send_frequency_); + send_timer_ = this->create_wall_timer( + std::chrono::duration_cast(send_period), + std::bind(&UartTransmitterNode::sendControlFrame, this)); + + // 创建定时器 - 发布连接状态 + status_timer_ = this->create_wall_timer( + std::chrono::seconds(1), + std::bind(&UartTransmitterNode::publishStatus, this)); + + // 创建接收线程 + receive_thread_ = std::thread(&UartTransmitterNode::receiveLoop, this); + + RCLCPP_INFO(this->get_logger(), "UART 节点初始化完成"); + } + + ~UartTransmitterNode() + { + if (receive_thread_.joinable()) { + running_ = false; + receive_thread_.join(); + } + if (serial_.isOpen()) { + serial_.close(); + } + RCLCPP_INFO(this->get_logger(), "串口已关闭"); + } + +private: + bool initSerial() + { + try { + RCLCPP_INFO(this->get_logger(), "正在打开串口 %s...", serial_port_.c_str()); + + serial_.setPort(serial_port_); + serial_.setBaudrate(baudrate_); + serial::Timeout timeout = serial::Timeout::simpleTimeout(1000); + serial_.setTimeout(timeout); + serial_.setBytesize(serial::eightbits); + serial_.setParity(serial::parity_none); + serial_.setStopbits(serial::stopbits_one); + + serial_.open(); + + if (serial_.isOpen()) { + RCLCPP_INFO(this->get_logger(), "串口打开成功"); + is_connected_ = true; + return true; + } else { + RCLCPP_ERROR(this->get_logger(), "串口打开失败"); + return false; + } + } catch (const std::exception& e) { + RCLCPP_ERROR(this->get_logger(), "串口异常: %s", e.what()); + return false; + } + } + + void sendControlFrame() + { + if (!serial_.isOpen()) { + RCLCPP_WARN_THROTTLE(this->get_logger(), *this->get_clock(), 5000, "串口未打开"); + return; + } + + // 获取最新的控制参数 + int16_t x_move = static_cast(this->get_parameter("x_move").as_int()); + int16_t y_move = static_cast(this->get_parameter("y_move").as_int()); + int16_t yaw = static_cast(this->get_parameter("yaw").as_int()); + int16_t pitch = static_cast(this->get_parameter("pitch").as_int()); + int16_t feed = static_cast(this->get_parameter("feed").as_int()); + uint8_t left_switch = static_cast(this->get_parameter("left_switch").as_int()) & 0x0F; + uint8_t right_switch = static_cast(this->get_parameter("right_switch").as_int()) & 0x0F; + + // 构建数据帧 + std::vector frame; + frame.reserve(FRAME_LENGTH); + + // 帧头 + frame.push_back(FRAME_HEADER_1); + frame.push_back(FRAME_HEADER_2); + + // 平动左右 (2 bytes, int16, 大端序) + frame.push_back((x_move >> 8) & 0xFF); + frame.push_back(x_move & 0xFF); + + // 平动前后 (2 bytes) + frame.push_back((y_move >> 8) & 0xFF); + frame.push_back(y_move & 0xFF); + + // 云台偏航 (2 bytes) + frame.push_back((yaw >> 8) & 0xFF); + frame.push_back(yaw & 0xFF); + + // 云台俯仰 (2 bytes) + frame.push_back((pitch >> 8) & 0xFF); + frame.push_back(pitch & 0xFF); + + // 拨弹轮 (2 bytes) + frame.push_back((feed >> 8) & 0xFF); + frame.push_back(feed & 0xFF); + + // 拨杆 (1 byte: 高4位左拨杆,低4位右拨杆) + uint8_t switches = (left_switch << 4) | right_switch; + frame.push_back(switches); + + // CRC8 (除帧头外的所有数据) + uint8_t crc = calculateCRC8(frame.data() + 2, frame.size() - 2); + frame.push_back(crc); + + // 帧尾 + frame.push_back(FRAME_TAIL); + + // 发送数据 + try { + size_t written = serial_.write(frame.data(), frame.size()); + if (written != frame.size()) { + RCLCPP_WARN(this->get_logger(), "发送数据不完整: %zu/%d", written, FRAME_LENGTH); + } + } catch (const std::exception& e) { + RCLCPP_ERROR(this->get_logger(), "发送失败: %s", e.what()); + is_connected_ = false; + } + } + + uint8_t calculateCRC8(const uint8_t* data, size_t len) + { + uint8_t crc = 0xFF; // 初始值 + for (size_t i = 0; i < len; i++) { + crc ^= data[i]; + for (int j = 0; j < 8; j++) { + if (crc & 0x80) { + crc = (crc << 1) ^ 0x31; // CRC8-MAXIM 多项式 + } else { + crc <<= 1; + } + } + } + return crc; + } + + void receiveLoop() + { + std::vector buffer; + buffer.reserve(FRAME_LENGTH); + + while (running_ && rclcpp::ok()) { + if (!serial_.isOpen()) { + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + continue; + } + + try { + // 读取可用数据 + size_t available = serial_.available(); + if (available > 0) { + std::vector data = serial_.read(available); + + // 处理接收到的数据(简单的帧解析) + for (uint8_t byte : data) { + buffer.push_back(byte); + + // 查找帧头 + if (buffer.size() >= 2 && + buffer[0] == FRAME_HEADER_1 && + buffer[1] == FRAME_HEADER_2) { + + // 等待完整帧 + if (buffer.size() >= FRAME_LENGTH) { + // 检查帧尾 + if (buffer[FRAME_LENGTH - 1] == FRAME_TAIL) { + // 验证 CRC + uint8_t rx_crc = buffer[FRAME_LENGTH - 2]; + uint8_t calc_crc = calculateCRC8( + buffer.data() + 2, FRAME_LENGTH - 4); + + if (rx_crc == calc_crc) { + RCLCPP_INFO(this->get_logger(), + "收到有效帧,CRC 验证通过"); + } else { + RCLCPP_WARN(this->get_logger(), + "CRC 错误: 接收=%02X, 计算=%02X", + rx_crc, calc_crc); + } + } + + // 清空缓冲区,准备下一帧 + buffer.clear(); + } + } else if (buffer.size() > FRAME_LENGTH) { + // 缓冲区溢出,清空 + buffer.clear(); + } + } + } + } catch (const std::exception& e) { + RCLCPP_ERROR(this->get_logger(), "接收异常: %s", e.what()); + is_connected_ = false; + } + + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } + } + + void publishStatus() + { + auto msg = std_msgs::msg::Bool(); + msg.data = is_connected_ && serial_.isOpen(); + connection_status_pub_->publish(msg); + } + + // 成员变量 + std::string serial_port_; + int baudrate_; + double send_frequency_; + + serial::Serial serial_; + bool is_connected_ = false; + bool running_ = true; + std::thread receive_thread_; + + rclcpp::Publisher::SharedPtr connection_status_pub_; + rclcpp::TimerBase::SharedPtr send_timer_; + rclcpp::TimerBase::SharedPtr status_timer_; +}; + +int main(int argc, char* argv[]) +{ + rclcpp::init(argc, argv); + + auto node = std::make_shared(); + + if (rclcpp::ok()) { + rclcpp::spin(node); + } + + rclcpp::shutdown(); + return 0; +} \ No newline at end of file diff --git a/transmitter_sdk/example.c b/transmitter_sdk/example.c deleted file mode 100644 index e69de29..0000000 diff --git a/transmitter_sdk/inc/pub_user.h b/transmitter_sdk/inc/pub_user.h deleted file mode 100755 index 27fc139..0000000 --- a/transmitter_sdk/inc/pub_user.h +++ /dev/null @@ -1,149 +0,0 @@ -// -// Created by 93094 on 2025/12/23. -// - -#ifndef DM_DEVICE_PUB_USER_H -#define DM_DEVICE_PUB_USER_H - -#define DEVICE_EXPORTS - -#ifdef _WIN32 - #ifdef DEVICE_EXPORTS - #define DEVICE_API __declspec(dllexport) - #else - #define DEVICE_API __declspec(dllimport) - #endif -#else - #define DEVICE_API __attribute__((visibility("default"))) -#endif - -#ifdef __cplusplus - -#include - -extern "C" -{ - typedef struct damiao_handle hDamiaoUsb; - typedef struct device_handle hDevice; - -#pragma pack(push,1) - typedef struct - { - uint32_t can_id:29; //can id - uint32_t esi:1; //错误状态指示 一般不用 - uint32_t ext:1; //拓展帧 1-拓展帧 0-标准帧 - uint32_t rtr:1; //远程帧 1-远程帧 0-数据帧 - uint8_t canfd:1; //canfd 1-canfd帧 0-can2.0帧 - uint8_t brs:1; //波特率切换 1-切换 0-不切换 - uint8_t id_inc:1; //ID自增 1-自增 0-不自增 - uint8_t data_inc:1; //数据自增 1-自增 0-不自增 - uint8_t dlc:4; //数据长度 - uint8_t channel; //通道号 - uint16_t reserved; //预留字节 - uint16_t step_id; //步进ID - uint32_t stop_id; //停止ID - uint32_t interval; //发送间隔 - int32_t send_times; //发送次数 - - }usb_tx_frame_head_t; - - typedef struct - { - usb_tx_frame_head_t head; - uint8_t payload[64]; - - }usb_tx_frame_t; - - - typedef struct - { - uint32_t can_id:29; //can id - uint32_t esi:1; //错误状态指示 一般不用 - uint32_t ext:1; //类型:标准/拓展 - uint32_t rtr:1; //类型:数据/远程 - uint64_t time_stamp; //时间戳 - uint8_t channel; //发送通道 - uint8_t canfd:1; //类型:2.0/fd - uint8_t dir:1; //方向:rx/tx - uint8_t brs:1; //BRS - uint8_t ack:1; //应答标志 - uint8_t dlc:4; //长度 - uint16_t reserved; //预留字节 - }usb_rx_frame_head_t; - - typedef struct - { - usb_rx_frame_head_t head; - uint8_t payload[64]; - - }usb_rx_frame_t ; - - typedef struct - { - int can_baudrate; - int canfd_baudrate; - float can_sp; - float canfd_sp; - }device_baud_t; - - typedef enum - { - DEV_None=-1, - DEV_USB2CANFD=0, - DEV_USB2CANFD_DUAL, - DEV_ECAT2CANFD - }device_def_t; - - typedef struct - { - uint8_t channel; - uint8_t can_fd; - uint8_t can_seg1; - uint8_t can_seg2; - uint8_t can_sjw; - uint8_t can_prescaler; - uint8_t canfd_seg1; - uint8_t canfd_seg2; - uint8_t canfd_sjw; - uint8_t canfd_prescaler; - }dmcan_ch_can_config_t; - - -#pragma pack(pop) - - - typedef void (*dev_rec_callback)(usb_rx_frame_t* rec_frame); - typedef void (*dev_sent_callback)(usb_rx_frame_t* sent_frame); - typedef void (*dev_err_callback)(usb_rx_frame_t* err_frame); - - - DEVICE_API damiao_handle* damiao_handle_create(device_def_t type); - DEVICE_API void damiao_handle_destroy(damiao_handle* handle); - DEVICE_API void damiao_print_version(damiao_handle* handle); - DEVICE_API void damiao_get_sdk_version(damiao_handle* handle, char* version_buf, size_t buf_size); - DEVICE_API int damiao_handle_find_devices(damiao_handle* handle); - DEVICE_API void damiao_handle_get_devices(damiao_handle* handle,device_handle** dev_list, int* device_count); - DEVICE_API void device_get_version(device_handle* dev, char* version_buf, size_t buf_size); - DEVICE_API void device_get_pid_vid(device_handle* dev, int* pid, int* vid); - DEVICE_API void device_get_serial_number(device_handle* dev, char* serial_buf, size_t buf_size); - DEVICE_API void device_get_type(device_handle* dev, device_def_t* type); - DEVICE_API bool device_open(device_handle* dev); - DEVICE_API bool device_close(device_handle* dev); - DEVICE_API bool device_save_config(device_handle* dev); - DEVICE_API bool device_open_channel(device_handle* dev, uint8_t channel); - DEVICE_API bool device_close_channel(device_handle* dev, uint8_t channel); - DEVICE_API bool device_channel_get_baudrate(device_handle*dev ,uint8_t channel,device_baud_t* baud); - DEVICE_API bool device_channel_set_baud(device_handle*dev ,uint8_t channel,bool canfd,int bitrate,int dbitrate); - DEVICE_API bool device_channel_set_baud_with_sp(device_handle*dev ,uint8_t channel,bool canfd,int bitrate,int dbitrate,float can_sp,float canfd_sp); - DEVICE_API void device_hook_to_rec(device_handle*dev,dev_rec_callback callback); - DEVICE_API void device_hook_to_sent(device_handle*dev,dev_sent_callback callback); - DEVICE_API void device_hook_to_err(device_handle*dev,dev_err_callback callback); - DEVICE_API void device_channel_send(device_handle*dev,usb_tx_frame_t frame); - DEVICE_API void device_channel_send_fast(device_handle*dev,uint8_t ch,uint32_t can_id,int32_t cnt,bool ext,bool canfd,bool brs,uint8_t len,uint8_t* payload); - DEVICE_API void device_channel_send_advanced(device_handle*dev,uint8_t ch,uint32_t can_id,uint16_t step_id,uint32_t stop_id,int32_t cnt,bool id_inc,bool data_inc,bool ext,bool canfd,bool brs,uint8_t len,uint8_t* payload); -} - - -#endif - -#endif //DM_DEVICE_PUB_USER_H \ No newline at end of file diff --git a/transmitter_sdk/lib/linux/arm64/libdm_device.so b/transmitter_sdk/lib/linux/arm64/libdm_device.so deleted file mode 100755 index ed22cbb..0000000 Binary files a/transmitter_sdk/lib/linux/arm64/libdm_device.so and /dev/null differ diff --git a/transmitter_sdk/lib/linux/x64/libdm_device.so b/transmitter_sdk/lib/linux/x64/libdm_device.so deleted file mode 100755 index 3727af8..0000000 Binary files a/transmitter_sdk/lib/linux/x64/libdm_device.so and /dev/null differ