Skip to content

Commit

Permalink
v3.8.3 B1 SDK add python arm lib
Browse files Browse the repository at this point in the history
  • Loading branch information
Bin-Ro committed Nov 21, 2022
1 parent fca009d commit bf3af88
Show file tree
Hide file tree
Showing 28 changed files with 688 additions and 1,003 deletions.
35 changes: 15 additions & 20 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,10 @@ project(unitree_legged_sdk)
include_directories(include)
include_directories(./)

link_directories(lib/cpp/amd64)

add_compile_options(-std=c++11)
# add_compile_options(-std=c++11)
add_compile_options(-std=c++14)

# check arch and os
message("-- CMAKE_SYSTEM_PROCESSOR: ${CMAKE_SYSTEM_PROCESSOR}")
if("${CMAKE_SYSTEM_PROCESSOR}" MATCHES "x86_64.*")
set(ARCH amd64)
Expand All @@ -17,31 +17,26 @@ if("${CMAKE_SYSTEM_PROCESSOR}" MATCHES "aarch64.*")
endif()

link_directories(lib/cpp/${ARCH})
set(EXTRA_LIBS -pthread libunitree_legged_sdk.so lcm)
set(EXTRA_LIBS -pthread libunitree_legged_sdk.so)

set(CMAKE_CXX_FLAGS "-O3 -fPIC")

add_executable(example_walk_aliengo examples/example_walk_aliengo_sport.cpp)
target_link_libraries(example_walk_aliengo ${EXTRA_LIBS})

add_executable(example_start_aliengo examples/example_start_aliengo_sport.cpp)
target_link_libraries(example_start_aliengo ${EXTRA_LIBS})
# one pc one process
add_executable(example_position example/example_position.cpp)
target_link_libraries(example_position ${EXTRA_LIBS})

add_executable(example_joystick_aliengo examples/example_joystick_aliengo_sport.cpp)
target_link_libraries(example_joystick_aliengo ${EXTRA_LIBS})
add_executable(example_velocity example/example_velocity.cpp)
target_link_libraries(example_velocity ${EXTRA_LIBS})

add_executable(example_recovery_aliengo examples/example_recovery_aliengo_sport.cpp)
target_link_libraries(example_recovery_aliengo ${EXTRA_LIBS})
add_executable(example_torque example/example_torque.cpp)
target_link_libraries(example_torque ${EXTRA_LIBS})

add_executable(example_position_aliengo examples/example_position_aliengo.cpp)
target_link_libraries(example_position_aliengo ${EXTRA_LIBS})
add_executable(example_walk example/example_walk.cpp)
target_link_libraries(example_walk ${EXTRA_LIBS})

add_executable(example_velocity_aliengo examples/example_velocity_aliengo.cpp)
target_link_libraries(example_velocity_aliengo ${EXTRA_LIBS})
add_executable(example_joystick example/example_joystick.cpp)
target_link_libraries(example_joystick ${EXTRA_LIBS})

add_executable(example_torque_aliengo examples/example_torque_aliengo.cpp)
target_link_libraries(example_torque_aliengo ${EXTRA_LIBS})




26 changes: 9 additions & 17 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,32 +1,24 @@
# v3.8.2
The aliengo_sdk is mainly used for communication between PC and aliengo control board.
# v3.8.1
The unitree_legged_sdk is mainly used for communication between PC and Controller board.
It also can be used in other PCs with UDP.

### Notice
support robot: Aliengo
support robot: B1

not support robot: Laikago, Aliengo, A1. (Check release [v3.3.1](https://github.com/unitreerobotics/unitree_legged_sdk/releases/tag/v3.3.1) for support)

### Sport Mode
```bash
Legged_sport >= v1.0.20
Legged_sport >= v3.24
firmware H0.1.7 >= v0.1.35
H0.1.9 >= v0.1.35


```

### Dependencies
* [Boost](http://www.boost.org) (version 1.5.4 or higher)
* [CMake](http://www.cmake.org) (version 2.8.3 or higher)
* [LCM](https://lcm-proj.github.io) (version 1.4.0 or higher)
```bash
cd lcm-x.x.x
mkdir build
cd build
cmake ../
make
sudo make install
```
* [Boost](http://www.boost.org) (version 1.71.0 or higher)
* [CMake](http://www.cmake.org) (version 3.16.3 or higher)
* [g++](https://gcc.gnu.org/) (version 9.4.0 or higher)


### Build
```bash
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,40 +4,36 @@ Use of this source code is governed by the MPL-2.0 license, see LICENSE.
************************************************************************/

#include "unitree_legged_sdk/unitree_legged_sdk.h"
#include "unitree_legged_sdk/joystick.h"
#include <math.h>
#include <iostream>
#include <unistd.h>
#include <string.h>

using namespace UNITREE_LEGGED_SDK;

// high cmd
constexpr uint16_t TARGET_PORT = 8082;
constexpr uint16_t LOCAL_PORT = 8081;
constexpr char TARGET_IP[] = "192.168.123.220"; // target IP address

class Custom
{
public:
Custom(uint8_t level): safe(LeggedType::Aliengo),
udp(LOCAL_PORT, TARGET_IP,TARGET_PORT, sizeof(HighCmd), sizeof(HighState))
{
Custom(uint8_t level):
safe(LeggedType::B1),
udp(level, 8090, "192.168.123.10", 8007){
udp.InitCmdData(cmd);
}
void UDPRecv();
void UDPSend();
void UDPRecv();
void RobotControl();

Safety safe;
UDP udp;
HighCmd cmd = {0};
HighState state = {0};
LowCmd cmd = {0};
LowState state = {0};
xRockerBtnDataStruct _keyData;
int motiontime = 0;
float dt = 0.002; // 0.001~0.01
};

void Custom::UDPRecv()
{
{
udp.Recv();
}

Expand All @@ -48,47 +44,28 @@ void Custom::UDPSend()

void Custom::RobotControl()
{
motiontime += 2;
motiontime++;
udp.GetRecv(state);

cmd.velocity[0] = 0.0f;
cmd.velocity[1] = 0.0f;
cmd.position[0] = 0.0f;
cmd.position[1] = 0.0f;
cmd.yawSpeed = 0.0f;;
memcpy(&_keyData, &state.wirelessRemote[0], 40);

cmd.mode = 0;
cmd.rpy[0] = 0;
cmd.rpy[1] = 0;
cmd.rpy[2] = 0;
cmd.gaitType = 0;
cmd.dBodyHeight = 0;
cmd.dFootRaiseHeight = 0;

if (motiontime == 2)
{
std::cout<<"begin sending commands."<<std::endl;
}
if (motiontime>1000 && motiontime <2000)
{
cmd.mode = 7; // mode 7: must enter damping mode before using recovery
}
if (motiontime>2000 && motiontime <3000)
{
cmd.mode = 8; // mode 8: recovery
if((int)_keyData.btn.components.A == 1){
std::cout << "The key A is pressed, and the value of lx is " << _keyData.lx << std::endl;
}

safe.PowerProtect(cmd, state, 1);
udp.SetSend(cmd);
}

int main(void)
int main(void)
{
std::cout << "Communication level is set to HIGH-level." << std::endl
<< "WARNING: Make sure the robot is standing on the ground." << std::endl
std::cout << "Communication level is set to LOW-level." << std::endl
<< "WARNING: Make sure the robot is hung up." << std::endl
<< "Press Enter to continue..." << std::endl;
std::cin.ignore();

Custom custom(HIGHLEVEL);
InitEnvironment();
Custom custom(LOWLEVEL);
// InitEnvironment();
LoopFunc loop_control("control_loop", custom.dt, boost::bind(&Custom::RobotControl, &custom));
LoopFunc loop_udpSend("udp_send", custom.dt, 3, boost::bind(&Custom::UDPSend, &custom));
LoopFunc loop_udpRecv("udp_recv", custom.dt, 3, boost::bind(&Custom::UDPRecv, &custom));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,23 +11,13 @@
using namespace std;
using namespace UNITREE_LEGGED_SDK;

// low cmd
constexpr uint16_t TARGET_PORT = 8007;
constexpr uint16_t LOCAL_PORT = 8082;
constexpr char TARGET_IP[] = "192.168.123.10"; // target IP address

const int LOW_CMD_LENGTH = 610;
const int LOW_STATE_LENGTH = 771;


class Custom
{
public:
Custom(uint8_t level) : safe(LeggedType::Aliengo),
udp(LOCAL_PORT, TARGET_IP,TARGET_PORT, LOW_CMD_LENGTH, LOW_STATE_LENGTH)
Custom(uint8_t level) : safe(LeggedType::B1),
udp(level, 8090, "192.168.123.10", 8007)
{
udp.InitCmdData(cmd);
cmd.levelFlag = LOWLEVEL;
}
void UDPRecv();
void UDPSend();
Expand Down Expand Up @@ -75,10 +65,10 @@ void Custom::RobotControl()
printf("%d %f %f\n", motiontime, state.motorState[FR_1].q, state.motorState[FR_1].dq);

// gravity compensation
cmd.motorCmd[FR_0].tau = -1.6f;
// cmd.motorCmd[FL_0].tau = +1.0f;
// cmd.motorCmd[RR_0].tau = -1.0f;
// cmd.motorCmd[RL_0].tau = +1.0f;
cmd.motorCmd[FR_0].tau = -5.0f;
// cmd.motorCmd[FL_0].tau = +0.65f;
// cmd.motorCmd[RR_0].tau = -0.65f;
// cmd.motorCmd[RL_0].tau = +0.65f;

// if( motiontime >= 100){
if (motiontime >= 0)
Expand Down Expand Up @@ -133,7 +123,7 @@ void Custom::RobotControl()
cmd.motorCmd[FR_0].dq = 0;
cmd.motorCmd[FR_0].Kp = Kp[0];
cmd.motorCmd[FR_0].Kd = Kd[0];
cmd.motorCmd[FR_0].tau = -1.6f;
cmd.motorCmd[FR_0].tau = -4.0f;

cmd.motorCmd[FR_1].q = qDes[1];
cmd.motorCmd[FR_1].dq = 0;
Expand Down
15 changes: 3 additions & 12 deletions examples/example_torque_aliengo.cpp → example/example_torque.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,22 +9,13 @@

using namespace UNITREE_LEGGED_SDK;

// low cmd
constexpr uint16_t TARGET_PORT = 8007;
constexpr uint16_t LOCAL_PORT = 8082;
constexpr char TARGET_IP[] = "192.168.123.10"; // target IP address

const int LOW_CMD_LENGTH = 610;
const int LOW_STATE_LENGTH = 771;

class Custom
{
public:
Custom(uint8_t level):
safe(LeggedType::Aliengo),
udp(LOCAL_PORT, TARGET_IP,TARGET_PORT, LOW_CMD_LENGTH, LOW_STATE_LENGTH){
safe(LeggedType::B1),
udp(level, 8090, "192.168.123.10", 8007){
udp.InitCmdData(cmd);
cmd.levelFlag = LOWLEVEL;
}
void UDPSend();
void UDPRecv();
Expand Down Expand Up @@ -55,7 +46,7 @@ void Custom::RobotControl()
udp.GetRecv(state);
printf("%d %f %f\n", motiontime, state.motorState[FR_1].q, state.motorState[FR_1].dq);
// gravity compensation
cmd.motorCmd[FR_0].tau = -1.6f;
cmd.motorCmd[FR_0].tau = -5.0f;
// cmd.motorCmd[FL_0].tau = +0.65f;
// cmd.motorCmd[RR_0].tau = -0.65f;
// cmd.motorCmd[RL_0].tau = +0.65f;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,22 +8,13 @@

using namespace UNITREE_LEGGED_SDK;

// low cmd
constexpr uint16_t TARGET_PORT = 8007;
constexpr uint16_t LOCAL_PORT = 8082;
constexpr char TARGET_IP[] = "192.168.123.10"; // target IP address

const int LOW_CMD_LENGTH = 610;
const int LOW_STATE_LENGTH = 771;

class Custom
{
public:
Custom(uint8_t level):
safe(LeggedType::Aliengo),
udp(LOCAL_PORT, TARGET_IP,TARGET_PORT, LOW_CMD_LENGTH, LOW_STATE_LENGTH){
safe(LeggedType::B1),
udp(level, 8090, "192.168.123.10", 8007){
udp.InitCmdData(cmd);
cmd.levelFlag = LOWLEVEL;
}
void UDPRecv();
void UDPSend();
Expand Down Expand Up @@ -52,6 +43,8 @@ void Custom::RobotControl()
{
motiontime++;
udp.GetRecv(state);

printf("%d %f %f\n", motiontime, state.motorState[FR_1].q, state.motorState[FR_1].dq);
// if(motiontime%50 == 0){
// printf("%ld %ld %ld\n", udp.udpState.RecvLoseError, udp.udpState.RecvCount, udp.udpState.SendCount);
// }
Expand All @@ -61,10 +54,10 @@ void Custom::RobotControl()
// state.motorState[6].q, state.motorState[7].q, state.motorState[8].q,
// state.motorState[9].q, state.motorState[10].q, state.motorState[11].q );
// gravity compensation
cmd.motorCmd[FR_0].tau = -1.6f;
// cmd.motorCmd[FL_0].tau = +0.0f;
// cmd.motorCmd[RR_0].tau = -1.0f;
// cmd.motorCmd[RL_0].tau = +1.0f;
cmd.motorCmd[FR_0].tau = -5.0f;
// cmd.motorCmd[FL_0].tau = +0.65f;
// cmd.motorCmd[RR_0].tau = -0.65f;
// cmd.motorCmd[RL_0].tau = +0.65f;

if( motiontime >= 500){
float speed = 2 * sin(3*M_PI*Tpi/2000.0);
Expand Down
Loading

0 comments on commit bf3af88

Please sign in to comment.