added catkin support

This commit is contained in:
Ruixiang Du
2020-06-01 18:45:56 +08:00
parent 98c7792d43
commit d5b3da58da
3 changed files with 83 additions and 14 deletions

View File

@@ -1,6 +1,9 @@
cmake_minimum_required(VERSION 3.1.0) cmake_minimum_required(VERSION 3.1.0)
project(wrp_sdk) project(wrp_sdk)
# Find catkin
find_package(catkin REQUIRED)
# generate symbols for IDE indexer # generate symbols for IDE indexer
set(CMAKE_EXPORT_COMPILE_COMMANDS ON) set(CMAKE_EXPORT_COMPILE_COMMANDS ON)
set(RUNTIME_OUTPUT_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/devel) set(RUNTIME_OUTPUT_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/devel)
@@ -51,4 +54,46 @@ add_subdirectory(src)
if(BUILD_TESTS) if(BUILD_TESTS)
add_subdirectory(unit_tests) add_subdirectory(unit_tests)
endif() endif()
## Export catkin targets
set(EXPORTED_LIBS
asyncio
stopwatch
scout_protocol
scoutbase
hunter_protocol
hunterbase
)
set(INCLUDE_DIRS
src/common/async_io/asio
src/common/async_io/include
src/common/utilities/stopwatch/include
src/scout_sdk/scout_protocol/include
src/scout_sdk/scout_base/include
src/hunter_sdk/hunter_protocol/include
src/hunter_sdk/hunter_base/include
)
catkin_package(
LIBRARIES ${EXPORTED_LIBS}
INCLUDE_DIRS ${INCLUDE_DIRS}
# DEPENDS rt pthread
)
## Add catkin install targets
# install(TARGETS ${EXPORTED_LIBS}
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION})
# install(DIRECTORY asio/asio
# DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION})
# install(FILES asio/asio.hpp
# DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION})
# install(DIRECTORY scripts
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})

24
package.xml Normal file
View File

@@ -0,0 +1,24 @@
<?xml version="1.0"?>
<package>
<name>wrp_sdk</name>
<version>0.3.3</version>
<description>Weston Robot Platform SDK</description>
<author email="ruixiang.du@westonrobot.com">Ruixiang Du</author>
<maintainer email="ruixiang.du@westonrobot.com">Ruixiang Du</maintainer>
<license>BSD</license>
<url type="website">TODO</url>
<url type="bugtracker">TODO</url>
<url type="repository">TODO</url>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>sensor_msgs</build_depend>
<run_depend>roscpp</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>sensor_msgs</run_depend>
<export></export>
</package>

View File

@@ -23,13 +23,13 @@ int main(int argc, char **argv)
} }
else else
{ {
std::cout << "Usage: app_scout_demo <interface>" << std::endl std::cout << "Usage: app_hunter_demo <interface>" << std::endl
<< "Example 1: ./app_scout_demo can0" << std::endl; << "Example 1: ./app_hunter_demo can0" << std::endl;
return -1; return -1;
} }
HunterBase scout; HunterBase hunter;
scout.Connect(device_name); hunter.Connect(device_name);
int count = 0; int count = 0;
while (true) while (true)
@@ -38,45 +38,45 @@ int main(int argc, char **argv)
if (count < 5) if (count < 5)
{ {
std::cout << "Motor: 0.2, 0.0" << std::endl; std::cout << "Motor: 0.2, 0.0" << std::endl;
scout.SetMotionCommand(0.2, 0.0); hunter.SetMotionCommand(0.2, 0.0);
} }
else if (count < 10) else if (count < 10)
{ {
std::cout << "Motor: 0.8, 0.3" << std::endl; std::cout << "Motor: 0.8, 0.3" << std::endl;
scout.SetMotionCommand(0.8, 0.3); hunter.SetMotionCommand(0.8, 0.3);
} }
else if (count < 15) else if (count < 15)
{ {
std::cout << "Motor: 1.5, 0.5" << std::endl; std::cout << "Motor: 1.5, 0.5" << std::endl;
scout.SetMotionCommand(1.5, 0.5); hunter.SetMotionCommand(1.5, 0.5);
} }
else if (count < 20) else if (count < 20)
{ {
std::cout << "Motor: 1.0, 0.3" << std::endl; std::cout << "Motor: 1.0, 0.3" << std::endl;
scout.SetMotionCommand(1.0, 0.3); hunter.SetMotionCommand(1.0, 0.3);
} }
else if (count < 25) else if (count < 25)
{ {
std::cout << "Motor: 0.0, 0.0" << std::endl; std::cout << "Motor: 0.0, 0.0" << std::endl;
scout.SetMotionCommand(0.0, 0.0); hunter.SetMotionCommand(0.0, 0.0);
} }
else if (count < 30) else if (count < 30)
{ {
std::cout << "Motor: -0.5, -0.3" << std::endl; std::cout << "Motor: -0.5, -0.3" << std::endl;
scout.SetMotionCommand(-0.5, -0.3); hunter.SetMotionCommand(-0.5, -0.3);
} }
else if (count < 35) else if (count < 35)
{ {
std::cout << "Motor: -1.0, -0.5" << std::endl; std::cout << "Motor: -1.0, -0.5" << std::endl;
scout.SetMotionCommand(-1.0, -0.5); hunter.SetMotionCommand(-1.0, -0.5);
} }
else if (count < 40) else if (count < 40)
{ {
std::cout << "Motor: 0.0, 0.0," << std::endl; std::cout << "Motor: 0.0, 0.0," << std::endl;
scout.SetMotionCommand(0.0, 0.0); hunter.SetMotionCommand(0.0, 0.0);
} }
auto state = scout.GetHunterState(); auto state = hunter.GetHunterState();
std::cout << "-------------------------------" << std::endl; std::cout << "-------------------------------" << std::endl;
std::cout << "count: " << count << std::endl; std::cout << "count: " << count << std::endl;
std::cout << "control mode: " << static_cast<int>(state.control_mode) << " , base state: " << static_cast<int>(state.base_state) << std::endl; std::cout << "control mode: " << static_cast<int>(state.control_mode) << " , base state: " << static_cast<int>(state.base_state) << std::endl;