first commit

This commit is contained in:
liang 2022-11-24 15:18:50 +08:00
commit 9535c0a912
12 changed files with 497 additions and 0 deletions

12
CMakeLists.txt Executable file
View File

@ -0,0 +1,12 @@
cmake_minimum_required(VERSION 3.10.2)
project(UnitreeMotorSDK_M80106)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -O3")
include_directories("include/")
link_directories(
lib/
)
#example
add_executable(motorctrl example/main.cpp)
target_link_libraries(motorctrl libUnitreeMotorSDK_M80106_Linux64.so)

29
LICENSE Normal file
View File

@ -0,0 +1,29 @@
BSD 3-Clause License
Copyright (c) 2016-2022 HangZhou YuShu TECHNOLOGY CO.,LTD. ("Unitree Robotics")
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright notice, this
list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.
* Neither the name of the copyright holder nor the names of its
contributors may be used to endorse or promote products derived from
this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

21
README.md Normal file
View File

@ -0,0 +1,21 @@
# README.md
### Notice
support motor: GO-M8010-6 motor
not support motor: A1 motor、 B1 motor (Check A1B1 branch for support)
### Build
```bash
mkdir build
cd build
cmake ..
make
```
### Run
Run examples with 'sudo',e.g.
```bash
sudo ./motorctrl
```

33
example/main.cpp Normal file
View File

@ -0,0 +1,33 @@
#include "serialPort/SerialPort.h"
#include <unistd.h>
int main() {
SerialPort serial("/dev/ttyUSB0");
MotorCmd cmd;
MotorData data;
while(true) {
cmd.motorType = MotorType::GO_M8010_6;
cmd.id = 0;
cmd.mode = 1;
cmd.K_P = 0.0;
cmd.K_W = 0.05;
cmd.Pos = 0.0;
cmd.W = 6.28*6.33;
cmd.T = 0.0;
serial.sendRecv(&cmd,&data);
std::cout << std::endl;
std::cout << "motor.Pos: " << data.Pos << std::endl;
std::cout << "motor.Temp: " << data.Temp << std::endl;
std::cout << "motor.W: " << data.W << std::endl;
std::cout << "motor.T: " << data.T << std::endl;
std::cout << "motor.MError: " << data.MError << std::endl;
std::cout << std::endl;
usleep(200);
}
}

41
include/IOPort/IOPort.h Executable file
View File

@ -0,0 +1,41 @@
#ifndef __IOPORT_H
#define __IOPORT_H
#include <stdint.h>
#include <unistd.h>
#include <vector>
#include "unitreeMotor/unitreeMotor.h"
enum class BlockYN{
YES,
NO
};
class IOPort{
public:
IOPort(BlockYN blockYN, size_t recvLength, size_t timeOutUs){
resetIO(blockYN, recvLength, timeOutUs);
}
virtual ~IOPort(){}
virtual size_t send(uint8_t *sendMsg, size_t sendLength) = 0;
virtual size_t recv(uint8_t *recvMsg, size_t recvLength) = 0;
virtual size_t recv(uint8_t *recvMsg) = 0;
virtual bool sendRecv(std::vector<MotorCmd> &sendVec, std::vector<MotorData> &recvVec) = 0;
void resetIO(BlockYN blockYN, size_t recvLength, size_t timeOutUs);
protected:
BlockYN _blockYN = BlockYN::NO;
size_t _recvLength;
timeval _timeout;
timeval _timeoutSaved;
};
inline void IOPort::resetIO(BlockYN blockYN, size_t recvLength, size_t timeOutUs){
_blockYN = blockYN;
_recvLength = recvLength;
_timeout.tv_sec = timeOutUs / 1000000;
_timeout.tv_usec = timeOutUs % 1000000;
_timeoutSaved = _timeout;
}
#endif // z1_lib_IOPORT_H

67
include/crc/crc_ccitt.h Normal file
View File

@ -0,0 +1,67 @@
#ifndef __CRC_CCITT_H
#define __CRC_CCITT_H
/*
* This mysterious table is just the CRC of each possible byte. It can be
* computed using the standard bit-at-a-time methods. The polynomial can
* be seen in entry 128, 0x8408. This corresponds to x^0 + x^5 + x^12.
* Add the implicit x^16, and you have the standard CRC-CCITT.
* https://github.com/torvalds/linux/blob/5bfc75d92efd494db37f5c4c173d3639d4772966/lib/crc-ccitt.c
*/
uint16_t const crc_ccitt_table[256] = {
0x0000, 0x1189, 0x2312, 0x329b, 0x4624, 0x57ad, 0x6536, 0x74bf,
0x8c48, 0x9dc1, 0xaf5a, 0xbed3, 0xca6c, 0xdbe5, 0xe97e, 0xf8f7,
0x1081, 0x0108, 0x3393, 0x221a, 0x56a5, 0x472c, 0x75b7, 0x643e,
0x9cc9, 0x8d40, 0xbfdb, 0xae52, 0xdaed, 0xcb64, 0xf9ff, 0xe876,
0x2102, 0x308b, 0x0210, 0x1399, 0x6726, 0x76af, 0x4434, 0x55bd,
0xad4a, 0xbcc3, 0x8e58, 0x9fd1, 0xeb6e, 0xfae7, 0xc87c, 0xd9f5,
0x3183, 0x200a, 0x1291, 0x0318, 0x77a7, 0x662e, 0x54b5, 0x453c,
0xbdcb, 0xac42, 0x9ed9, 0x8f50, 0xfbef, 0xea66, 0xd8fd, 0xc974,
0x4204, 0x538d, 0x6116, 0x709f, 0x0420, 0x15a9, 0x2732, 0x36bb,
0xce4c, 0xdfc5, 0xed5e, 0xfcd7, 0x8868, 0x99e1, 0xab7a, 0xbaf3,
0x5285, 0x430c, 0x7197, 0x601e, 0x14a1, 0x0528, 0x37b3, 0x263a,
0xdecd, 0xcf44, 0xfddf, 0xec56, 0x98e9, 0x8960, 0xbbfb, 0xaa72,
0x6306, 0x728f, 0x4014, 0x519d, 0x2522, 0x34ab, 0x0630, 0x17b9,
0xef4e, 0xfec7, 0xcc5c, 0xddd5, 0xa96a, 0xb8e3, 0x8a78, 0x9bf1,
0x7387, 0x620e, 0x5095, 0x411c, 0x35a3, 0x242a, 0x16b1, 0x0738,
0xffcf, 0xee46, 0xdcdd, 0xcd54, 0xb9eb, 0xa862, 0x9af9, 0x8b70,
0x8408, 0x9581, 0xa71a, 0xb693, 0xc22c, 0xd3a5, 0xe13e, 0xf0b7,
0x0840, 0x19c9, 0x2b52, 0x3adb, 0x4e64, 0x5fed, 0x6d76, 0x7cff,
0x9489, 0x8500, 0xb79b, 0xa612, 0xd2ad, 0xc324, 0xf1bf, 0xe036,
0x18c1, 0x0948, 0x3bd3, 0x2a5a, 0x5ee5, 0x4f6c, 0x7df7, 0x6c7e,
0xa50a, 0xb483, 0x8618, 0x9791, 0xe32e, 0xf2a7, 0xc03c, 0xd1b5,
0x2942, 0x38cb, 0x0a50, 0x1bd9, 0x6f66, 0x7eef, 0x4c74, 0x5dfd,
0xb58b, 0xa402, 0x9699, 0x8710, 0xf3af, 0xe226, 0xd0bd, 0xc134,
0x39c3, 0x284a, 0x1ad1, 0x0b58, 0x7fe7, 0x6e6e, 0x5cf5, 0x4d7c,
0xc60c, 0xd785, 0xe51e, 0xf497, 0x8028, 0x91a1, 0xa33a, 0xb2b3,
0x4a44, 0x5bcd, 0x6956, 0x78df, 0x0c60, 0x1de9, 0x2f72, 0x3efb,
0xd68d, 0xc704, 0xf59f, 0xe416, 0x90a9, 0x8120, 0xb3bb, 0xa232,
0x5ac5, 0x4b4c, 0x79d7, 0x685e, 0x1ce1, 0x0d68, 0x3ff3, 0x2e7a,
0xe70e, 0xf687, 0xc41c, 0xd595, 0xa12a, 0xb0a3, 0x8238, 0x93b1,
0x6b46, 0x7acf, 0x4854, 0x59dd, 0x2d62, 0x3ceb, 0x0e70, 0x1ff9,
0xf78f, 0xe606, 0xd49d, 0xc514, 0xb1ab, 0xa022, 0x92b9, 0x8330,
0x7bc7, 0x6a4e, 0x58d5, 0x495c, 0x3de3, 0x2c6a, 0x1ef1, 0x0f78
};
static uint16_t crc_ccitt_byte(uint16_t crc, const uint8_t c)
{
return (crc >> 8) ^ crc_ccitt_table[(crc ^ c) & 0xff];
}
/**
* crc_ccitt - recompute the CRC (CRC-CCITT variant) for the data
* buffer
* @crc: previous CRC value
* @buffer: data pointer
* @len: number of bytes in the buffer
*/
inline uint16_t crc_ccitt(uint16_t crc, uint8_t const *buffer, size_t len)
{
while (len--)
crc = crc_ccitt_byte(crc, *buffer++);
return crc;
}
#endif

98
include/serialPort/SerialPort.h Executable file
View File

@ -0,0 +1,98 @@
#ifndef __SERIALPORT_H
#define __SERIALPORT_H
/*
High frequency serial communication,
Not that common, but useful for motor communication.
*/
#include <termios.h>
#include <sys/select.h>
#include <string>
#include <string.h>
#include <stdint.h>
#include <fcntl.h>
#include <sys/ioctl.h>
#include <linux/serial.h>
#include <unistd.h>
#include <iostream>
#include "serialPort/include/errorClass.h"
#include "unitreeMotor/unitreeMotor.h"
#include "IOPort/IOPort.h"
enum class bytesize_t{
fivebits,
sixbits,
sevenbits,
eightbits
};
enum class parity_t{
parity_none,
parity_odd,
parity_even,
parity_mark,
parity_space
};
enum class stopbits_t{
stopbits_one,
stopbits_two,
stopbits_one_point_five
};
enum class flowcontrol_t{
flowcontrol_none,
flowcontrol_software,
flowcontrol_hardware
};
class SerialPort : public IOPort{
public:
SerialPort(const std::string &portName,
size_t recvLength = 16,
uint32_t baudrate = 4000000,
size_t timeOutUs = 20000,
BlockYN blockYN = BlockYN::NO,
bytesize_t bytesize = bytesize_t::eightbits,
parity_t parity = parity_t::parity_none,
stopbits_t stopbits = stopbits_t::stopbits_one,
flowcontrol_t flowcontrol = flowcontrol_t::flowcontrol_none);
virtual ~SerialPort();
void resetSerial(size_t recvLength = 16,
uint32_t baudrate = 4000000,
size_t timeOutUs = 20000,
BlockYN blockYN = BlockYN::NO,
bytesize_t bytesize = bytesize_t::eightbits,
parity_t parity = parity_t::parity_none,
stopbits_t stopbits = stopbits_t::stopbits_one,
flowcontrol_t flowcontrol = flowcontrol_t::flowcontrol_none);
size_t send(uint8_t *sendMsg, size_t sendLength);
size_t recv(uint8_t *recvMsg, size_t recvLength);
size_t recv(uint8_t *recvMsg);
bool sendRecv(uint8_t *sendMsg, uint8_t *recvMsg, size_t sendLength);
bool sendRecv(MotorCmd* sendMsg, MotorData* recvMsg);
bool sendRecv(std::vector<MotorCmd> &sendVec, std::vector<MotorData> &recvVec);
private:
void _open();
void _set();
void _close();
size_t _nonBlockRecv(uint8_t *recvMsg, size_t readLen);
std::string _portName;
uint32_t _baudrate;
bytesize_t _bytesize;
parity_t _parity;
stopbits_t _stopbits;
flowcontrol_t _flowcontrol;
bool _xonxoff;
bool _rtscts;
int _fd;
fd_set _rSet;
};
#endif // SERIALPORT_H

View File

@ -0,0 +1,52 @@
#ifndef __ERRORCLASS_H
#define __ERRORCLASS_H
#include <string>
#include <exception>
#include <stdexcept>
#include <sstream>
#include <cstring>
#define THROW(exceptionClass, message) throw exceptionClass(__FILE__, \
__LINE__, (message) )
class IOException : public std::exception
{
// Disable copy constructors
IOException& operator=(const IOException&);
std::string file_;
int line_;
std::string e_what_;
int errno_;
public:
explicit IOException (std::string file, int line, int errnum)
: file_(file), line_(line), errno_(errnum) {
std::stringstream ss;
#if defined(_WIN32) && !defined(__MINGW32__)
char error_str [1024];
strerror_s(error_str, 1024, errnum);
#else
char * error_str = strerror(errnum);
#endif
ss << "IO Exception (" << errno_ << "): " << error_str;
ss << ", file " << file_ << ", line " << line_ << ".";
e_what_ = ss.str();
}
explicit IOException (std::string file, int line, const char * description)
: file_(file), line_(line), errno_(0) {
std::stringstream ss;
ss << "IO Exception: " << description;
ss << ", file " << file_ << ", line " << line_ << ".";
e_what_ = ss.str();
}
virtual ~IOException() throw() {}
IOException (const IOException& other) : line_(other.line_), e_what_(other.e_what_), errno_(other.errno_) {}
int getErrorNumber () const { return errno_; }
virtual const char* what () const throw () {
return e_what_.c_str();
}
};
#endif // ERRORCLASS_H

View File

@ -0,0 +1,90 @@
#ifndef __MOTOR_MSG_H
#define __MOTOR_MSG_H
#include <stdint.h>
#define CRC_SIZE 2
#define CTRL_DAT_SIZE sizeof(ControlData_t) - CRC_SIZE
#define DATA_DAT_SIZE sizeof(MotorData_t) - CRC_SIZE
#pragma pack(1)
/**
* @brief
*
*/
typedef struct
{
uint8_t id :4; // 电机ID: 0,1...,14 15表示向所有电机广播数据(此时无返回)
uint8_t status :3; // 工作模式: 0.锁定 1.FOC闭环 2.编码器校准 3.保留
uint8_t none :1; // 保留位
} RIS_Mode_t; // 控制模式 1Byte
/**
* @brief
*
*/
typedef struct
{
int16_t tor_des; // 期望关节输出扭矩 unit: N.m (q8)
int16_t spd_des; // 期望关节输出速度 unit: rad/s (q7)
int32_t pos_des; // 期望关节输出位置 unit: rad (q15)
uint16_t k_pos; // 期望关节刚度系数 unit: 0.0-1.0 (q15)
uint16_t k_spd; // 期望关节阻尼系数 unit: 0.0-1.0 (q15)
} RIS_Comd_t; // 控制参数 12Byte
/**
* @brief
*
*/
typedef struct
{
int16_t torque; // 实际关节输出扭矩 unit: N.m (q8)
int16_t speed; // 实际关节输出速度 unit: rad/s (q7)
int32_t pos; // 实际关节输出位置 unit: W (q15)
int8_t temp; // 电机温度: -128~127°C 90°C时触发温度保护
uint8_t MError :3; // 电机错误标识: 0.正常 1.过热 2.过流 3.过压 4.编码器故障 5-7.保留
uint16_t force :12; // 足端气压传感器数据 12bit (0-4095)
uint8_t none :1; // 保留位
} RIS_Fbk_t; // 状态数据 11Byte
#pragma pack()
#pragma pack(1)
/**
* @brief
*
*/
typedef struct
{
uint8_t head[2]; // 包头 2Byte
RIS_Mode_t mode; // 电机控制模式 1Byte
RIS_Comd_t comd; // 电机期望数据 12Byte
uint16_t CRC16; // CRC 2Byte
} ControlData_t; // 主机控制命令 17Byte
/**
* @brief
*
*/
typedef struct
{
uint8_t head[2]; // 包头 2Byte
RIS_Mode_t mode; // 电机控制模式 1Byte
RIS_Fbk_t fbk; // 电机反馈数据 11Byte
uint16_t CRC16; // CRC 2Byte
} MotorData_t; // 电机返回数据 16Byte
#pragma pack()
#endif

View File

@ -0,0 +1,54 @@
#ifndef __UNITREEMOTOR_H
#define __UNITREEMOTOR_H
#include "unitreeMotor/include/motor_msg.h" // 电机通信协议
#include <stdint.h>
#include <iostream>
enum class MotorType{
GO_M8010_6
};
struct MotorCmd{
// 定义 发送格式化数据
public:
MotorType motorType = MotorType::GO_M8010_6;
int hex_len = 17;
unsigned short id; //电机ID0xBB代表全部电机
unsigned short mode; //0:空闲, 5:开环转动, 10:闭环FOC控制
float T; //期望关节的输出力矩电机本身的力矩Nm
float W; //期望关节速度(电机本身的速度)(rad/s)
float Pos; //期望关节位置rad
float K_P; //关节刚度系数
float K_W; //关节速度系数
void modify_data(MotorCmd* motor_s);
uint8_t* get_motor_send_data();
private:
ControlData_t motor_send_data; //电机控制数据结构体详见motor_msg.h
};
struct MotorData{
// 定义 接收数据
public:
MotorType motorType = MotorType::GO_M8010_6;
int hex_len = 16; //接收的16进制命令数组长度, 78
bool correct = false; //接收数据是否完整true完整false不完整
unsigned char motor_id; //电机ID
unsigned char mode; //0:空闲, 5:开环转动, 10:闭环FOC控制
int Temp; //温度
int MError; //错误码
float T; // 当前实际电机输出力矩
float W; // 当前实际电机速度(高速)
float Pos; // 当前电机位置
int footForce;
bool extract_data(MotorData* motor_r);
uint8_t* get_motor_recv_data();
private:
MotorData_t motor_recv_data; //电机接收数据结构体详见motor_msg.h
};
#endif // UNITREEMOTOR_H

Binary file not shown.

Binary file not shown.