Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Adding pickling support to LowState and LowCmd #130

Open
wants to merge 4 commits into
base: go1
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 8 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,11 @@ endif()

set(EXTRA_LIBS -pthread libunitree_legged_sdk.a)
set(CMAKE_CXX_FLAGS "-O3 -fPIC")
set(CMAKE_C_FLAGS "-O3 -fPIC")
set(CMAKE_CXX_STANDARD 14)

add_compile_options(-D BOOST_BIND_GLOBAL_PLACEHOLDERS)

find_package(catkin QUIET)
if(${catkin_FOUND})
catkin_package(
Expand All @@ -34,18 +37,23 @@ set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR})

# one pc one process
add_executable(example_position example/example_position.cpp)
target_link_libraries(example_position PRIVATE "-no-pie")
target_link_libraries(example_position ${EXTRA_LIBS})

add_executable(example_velocity example/example_velocity.cpp)
target_link_libraries(example_velocity PRIVATE "-no-pie")
target_link_libraries(example_velocity ${EXTRA_LIBS})

add_executable(example_torque example/example_torque.cpp)
target_link_libraries(example_torque PRIVATE "-no-pie")
target_link_libraries(example_torque ${EXTRA_LIBS})

add_executable(example_walk example/example_walk.cpp)
target_link_libraries(example_walk PRIVATE "-no-pie")
target_link_libraries(example_walk ${EXTRA_LIBS})

add_executable(example_joystick example/example_joystick.cpp)
target_link_libraries(example_joystick PRIVATE "-no-pie")
target_link_libraries(example_joystick ${EXTRA_LIBS})


Expand Down
Binary file modified lib/python/amd64/robot_interface.cpython-38-x86_64-linux-gnu.so
Binary file not shown.
3 changes: 3 additions & 0 deletions python_wrapper/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,10 @@ if("${CMAKE_SYSTEM_PROCESSOR}" MATCHES "aarch64.*")
set(ARCH arm64)
endif()

add_compile_options(-D BOOST_BIND_GLOBAL_PLACEHOLDERS)

include_directories(${CMAKE_CURRENT_SOURCE_DIR}/../include)
include_directories(${CMAKE_CURRENT_SOURCE_DIR}/third-party/pybind11/include)
link_directories(${CMAKE_CURRENT_SOURCE_DIR}/../lib/cpp/${ARCH})
file(GLOB_RECURSE sources "cpp/*.cpp")

Expand Down
228 changes: 221 additions & 7 deletions python_wrapper/python_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,25 @@ PYBIND11_MODULE(robot_interface, m) {
py::class_<BmsCmd>(m, "BmsCmd")
.def(py::init<>())
.def_readwrite("off", &BmsCmd::off)
.def_readwrite("reserve", &BmsCmd::reserve);
.def_readwrite("reserve", &BmsCmd::reserve)
.def(py::pickle(
[](const BmsCmd &p)
{
// __getstate__ - Return a tuple that fully encodes the state of the object
return py::make_tuple(p.off,
p.reserve);
},
[](py::tuple t)
{
// __setstate__ - Create a new C++ instance and assign state
if (t.size() != 2)
throw std::runtime_error("Invalid state!");
BmsCmd p;
p.off = (t[0].cast<uint8_t>());
p.reserve = (t[1].cast<std::array<uint8_t, 3>>());
return p;
}
));

py::class_<BmsState>(m, "BmsState")
.def(py::init<>())
Expand All @@ -80,7 +98,39 @@ PYBIND11_MODULE(robot_interface, m) {
.def_readwrite("cycle", &BmsState::cycle)
.def_readwrite("BQ_NTC", &BmsState::BQ_NTC)
.def_readwrite("MCU_NTC", &BmsState::MCU_NTC)
.def_readwrite("cell_vol", &BmsState::cell_vol);
.def_readwrite("cell_vol", &BmsState::cell_vol)
.def(py::pickle(
[](const BmsState &p)
{
// __getstate__ - Return a tuple that fully encodes the state of the object
return py::make_tuple(p.version_h,
p.version_l,
p.bms_status,
p.SOC,
p.current,
p.cycle,
p.BQ_NTC,
p.MCU_NTC,
p.cell_vol);
},
[](py::tuple t)
{
// __setstate__ - Create a new C++ instance and assign state
if (t.size() != 9)
throw std::runtime_error("Invalid state!");
BmsState p;
p.version_h = (t[0].cast<uint8_t>());
p.version_l = (t[1].cast<uint8_t>());
p.bms_status = (t[2].cast<uint8_t>());
p.SOC = (t[3].cast<uint8_t>());
p.current = (t[4].cast<int32_t>());
p.cycle = (t[5].cast<uint16_t>());
p.BQ_NTC = (t[6].cast<std::array<int8_t, 2>>());
p.MCU_NTC = (t[7].cast<std::array<int8_t, 2>>());
p.cell_vol = (t[8].cast<std::array<uint16_t, 10>>());
return p;
}
));

py::class_<Cartesian>(m, "Cartesian")
.def(py::init<>())
Expand All @@ -94,7 +144,31 @@ PYBIND11_MODULE(robot_interface, m) {
.def_readwrite("gyroscope", &IMU::gyroscope)
.def_readwrite("accelerometer", &IMU::accelerometer)
.def_readwrite("rpy", &IMU::rpy)
.def_readwrite("temperature", &IMU::temperature);
.def_readwrite("temperature", &IMU::temperature)
.def(py::pickle(
[](const IMU &p)
{
// __getstate__ - Return a tuple that fully encodes the state of the object
return py::make_tuple(p.quaternion,
p.gyroscope,
p.accelerometer,
p.rpy,
p.temperature);
},
[](py::tuple t)
{
// __setstate__ - Create a new C++ instance and assign state
if (t.size() != 5)
throw std::runtime_error("Invalid state!");
IMU p;
p.quaternion = (t[0].cast<std::array<float, 4>>());
p.gyroscope = (t[1].cast<std::array<float, 3>>());
p.accelerometer = (t[2].cast<std::array<float, 3>>());
p.rpy = (t[3].cast<std::array<float, 3>>());
p.temperature = (t[4].cast<int8_t>());
return p;
}
));

py::class_<LED>(m, "LED")
.def(py::init<>())
Expand All @@ -113,7 +187,39 @@ PYBIND11_MODULE(robot_interface, m) {
.def_readwrite("dq_raw", &MotorState::dq_raw)
.def_readwrite("ddq_raw", &MotorState::ddq_raw)
.def_readwrite("temperature", &MotorState::temperature)
.def_readwrite("reserve", &MotorState::reserve);
.def_readwrite("reserve", &MotorState::reserve)
.def(py::pickle(
[](const MotorState &p) {
// __getstate__ - Return a tuple that fully encodes the state of the object
return py::make_tuple(p.mode,
p.q,
p.dq,
p.ddq,
p.tauEst,
p.q_raw,
p.dq_raw,
p.ddq_raw,
p.temperature,
p.reserve);
},
[](py::tuple t) {
// __setstate__ - Create a new C++ instance and assign state
if (t.size() != 10)
throw std::runtime_error("Invalid state!");
MotorState p;
p.mode = (t[0].cast<uint8_t>());
p.q = (t[1].cast<float>());
p.dq = (t[2].cast<float>());
p.ddq = (t[3].cast<float>());
p.tauEst = (t[4].cast<float>());
p.q_raw = (t[5].cast<float>());
p.dq_raw = (t[6].cast<float>());
p.ddq_raw = (t[7].cast<float>());
p.temperature = (t[8].cast<int8_t>());
p.reserve = (t[9].cast<std::array<uint32_t, 2>>());
return p;
}
));

py::class_<MotorCmd>(m, "MotorCmd")
.def(py::init<>())
Expand All @@ -123,7 +229,35 @@ PYBIND11_MODULE(robot_interface, m) {
.def_readwrite("tau", &MotorCmd::tau)
.def_readwrite("Kp", &MotorCmd::Kp)
.def_readwrite("Kd", &MotorCmd::Kd)
.def_readwrite("reserve", &MotorCmd::reserve);
.def_readwrite("reserve", &MotorCmd::reserve)
.def(py::pickle(
[](const MotorCmd &p)
{
// __getstate__ - Return a tuple that fully encodes the state of the object
return py::make_tuple(p.mode,
p.q,
p.dq,
p.tau,
p.Kp,
p.Kd,
p.reserve);
},
[](py::tuple t)
{
// __setstate__ - Create a new C++ instance and assign state
if (t.size() != 7)
throw std::runtime_error("Invalid state!");
MotorCmd p;
p.mode = (t[0].cast<uint8_t>());
p.q = (t[1].cast<float>());
p.dq = (t[2].cast<float>());
p.tau = (t[3].cast<float>());
p.Kp = (t[4].cast<float>());
p.Kd = (t[5].cast<float>());
p.reserve = (t[6].cast<std::array<uint32_t, 3>>());
return p;
}
));

py::class_<LowState>(m, "LowState")
.def(py::init<>())
Expand All @@ -141,7 +275,51 @@ PYBIND11_MODULE(robot_interface, m) {
.def_readwrite("tick", &LowState::tick)
.def_readwrite("wirelessRemote", &LowState::wirelessRemote)
.def_readwrite("reserve", &LowState::reserve)
.def_readwrite("crc", &LowState::crc);
.def_readwrite("crc", &LowState::crc)
.def(py::pickle(
[](const LowState &p)
{
// __getstate__ - Return a tuple that fully encodes the state of the object
return py::make_tuple(p.head,
p.levelFlag,
p.frameReserve,
p.SN,
p.version,
p.bandWidth,
p.imu,
p.motorState,
p.bms,
p.footForce,
p.footForceEst,
p.tick,
p.wirelessRemote,
p.reserve,
p.crc);
},
[](py::tuple t)
{
// __setstate__ - Create a new C++ instance and assign state
if (t.size() != 15)
throw std::runtime_error("Invalid state!");
LowState p;
p.head = (t[0].cast<std::array<uint8_t, 2>>());
p.levelFlag = (t[1].cast<uint8_t>());
p.frameReserve = (t[2].cast<uint8_t>());
p.SN = (t[3].cast<std::array<uint32_t, 2>>());
p.version = (t[4].cast<std::array<uint32_t, 2>>());
p.bandWidth = (t[5].cast<uint16_t>());
p.imu = (t[6].cast<IMU>());
p.motorState = (t[7].cast<std::array<MotorState, 20>>());
p.bms = (t[8].cast<BmsState>());
p.footForce = (t[9].cast<std::array<int16_t, 4>>());
p.footForceEst = (t[10].cast<std::array<int16_t, 4>>());
p.tick = (t[11].cast<uint32_t>());
p.wirelessRemote = (t[12].cast<std::array<uint8_t, 40>>());
p.reserve = (t[13].cast<uint32_t>());
p.crc = (t[14].cast<uint32_t>());
return p;
}
));

py::class_<LowCmd>(m, "LowCmd")
.def(py::init<>())
Expand All @@ -155,7 +333,43 @@ PYBIND11_MODULE(robot_interface, m) {
.def_readwrite("bms", &LowCmd::bms)
.def_readwrite("wirelessRemote", &LowCmd::wirelessRemote)
.def_readwrite("reserve", &LowCmd::reserve)
.def_readwrite("crc", &LowCmd::crc);
.def_readwrite("crc", &LowCmd::crc)
.def(py::pickle(
[](const LowCmd &p)
{
// __getstate__ - Return a tuple that fully encodes the state of the object
return py::make_tuple(p.head,
p.levelFlag,
p.frameReserve,
p.SN,
p.version,
p.bandWidth,
p.motorCmd,
p.bms,
p.wirelessRemote,
p.reserve,
p.crc);
},
[](py::tuple t)
{
// __setstate__ - Create a new C++ instance and assign state
if (t.size() != 11)
throw std::runtime_error("Invalid state!");
LowCmd p;
p.head = (t[0].cast<std::array<uint8_t, 2>>());
p.levelFlag = (t[1].cast<uint8_t>());
p.frameReserve = (t[2].cast<uint8_t>());
p.SN = (t[3].cast<std::array<uint32_t, 2>>());
p.version = (t[4].cast<std::array<uint32_t, 2>>());
p.bandWidth = (t[5].cast<uint16_t>());
p.motorCmd = (t[6].cast<std::array<MotorCmd, 20>>());
p.bms = (t[7].cast<BmsCmd>());
p.wirelessRemote = (t[8].cast<std::array<uint8_t, 40>>());
p.reserve = (t[9].cast<uint32_t>());
p.crc = (t[10].cast<uint32_t>());
return p;
}
));

py::class_<HighState>(m, "HighState")
.def(py::init<>())
Expand Down