#include #include #include #include #include #include #include #include #include #include #include using namespace unitree::common; using namespace unitree::robot; #define TOPIC_LOWCMD "rt/lowcmd" #define TOPIC_LOWSTATE "rt/lowstate" constexpr double PosStopF = (2.146E+9f); constexpr double VelStopF = (16000.0f); class Bridge { public: explicit Bridge() {} ~Bridge() {} void Init(); private: void InitLowCmd(); void LowStateMessageHandler(const void* messages); void LowCmdWrite(); private: float dt = 0.002; // 0.001~0.01 unitree_go::msg::dds_::LowCmd_ low_cmd{}; // default init unitree_go::msg::dds_::LowState_ low_state{}; // default init /*publisher*/ ChannelPublisherPtr lowcmd_publisher; /*subscriber*/ ChannelSubscriberPtr lowstate_subscriber; /*LowCmd write thread*/ ThreadPtr lowCmdWriteThreadPtr; }; uint32_t crc32_core(uint32_t* ptr, uint32_t len) { unsigned int xbit = 0; unsigned int data = 0; unsigned int CRC32 = 0xFFFFFFFF; const unsigned int dwPolynomial = 0x04c11db7; for (unsigned int i = 0; i < len; i++) { xbit = 1 << 31; data = ptr[i]; for (unsigned int bits = 0; bits < 32; bits++) { if (CRC32 & 0x80000000) { CRC32 <<= 1; CRC32 ^= dwPolynomial; } else { CRC32 <<= 1; } if (data & xbit) CRC32 ^= dwPolynomial; xbit >>= 1; } } return CRC32; } void Bridge::Init() { InitLowCmd(); /*create publisher*/ lowcmd_publisher.reset(new ChannelPublisher(TOPIC_LOWCMD)); lowcmd_publisher->InitChannel(); /*create subscriber*/ lowstate_subscriber.reset(new ChannelSubscriber(TOPIC_LOWSTATE)); lowstate_subscriber->InitChannel(std::bind(&Bridge::LowStateMessageHandler, this, std::placeholders::_1), 1); /*loop publishing thread*/ lowCmdWriteThreadPtr = CreateRecurrentThreadEx("writebasiccmd", UT_CPU_ID_NONE, 2000, &Bridge::LowCmdWrite, this); } void Bridge::InitLowCmd() { low_cmd.head()[0] = 0xFE; low_cmd.head()[1] = 0xEF; low_cmd.level_flag() = 0xFF; low_cmd.gpio() = 0; for(int i=0; i<20; i++) { low_cmd.motor_cmd()[i].mode() = (0x01); // motor switch to servo (PMSM) mode low_cmd.motor_cmd()[i].q() = (PosStopF); low_cmd.motor_cmd()[i].kp() = (0); low_cmd.motor_cmd()[i].dq() = (VelStopF); low_cmd.motor_cmd()[i].kd() = (0); low_cmd.motor_cmd()[i].tau() = (0); } } void Bridge::LowStateMessageHandler(const void* message) { low_state = *(unitree_go::msg::dds_::LowState_*)message; } void Bridge::LowCmdWrite() { low_cmd.motor_cmd()[2].q() = 0; low_cmd.motor_cmd()[2].dq() = 0; low_cmd.motor_cmd()[2].kp() = 0; low_cmd.motor_cmd()[2].kd() = 0; low_cmd.motor_cmd()[2].tau() = 0; low_cmd.crc() = crc32_core((uint32_t *)&low_cmd, (sizeof(unitree_go::msg::dds_::LowCmd_)>>2)-1); lowcmd_publisher->Write(low_cmd); } int main(int argc, const char** argv) { if (argc < 2) { std::cout << "Usage: " << argv[0] << " networkInterface" << std::endl; exit(-1); } ChannelFactory::Instance()->Init(0, argv[1]); Bridge bridge; bridge.Init(); while (1) { sleep(10); } return 0; }