Skip to content
Snippets Groups Projects
Commit b1a7feaf authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

Initial commit for the arm module. Implemented the joint planning.

parent f3e03727
No related branches found
No related tags found
No related merge requests found
......@@ -93,6 +93,7 @@ generate_dynamic_reconfigure_options(
cfg/HeadModule.cfg
cfg/NavModule.cfg
cfg/TTSModule.cfg
cfg/ArmModule.cfg
)
###################################
......@@ -227,6 +228,21 @@ target_link_libraries(tts_module ${iriutils_LIBRARY})
## either from message generation or dynamic reconfigure
add_dependencies(tts_module ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Declare a C++ library
add_library(arm_module
src/arm_module.cpp
)
target_link_libraries(arm_module ${catkin_LIBRARIES})
target_link_libraries(arm_module ${iriutils_LIBRARY})
##Link to other modules
##target_link_libraries(new_module <module path>/lib<module_name>.so)
## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
add_dependencies(arm_module ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
......
......@@ -53,6 +53,7 @@
<build_depend>pal_navigation_msgs</build_depend>
<build_depend>pal_waypoint_msgs</build_depend>
<build_depend>pal_interaction_msgs</build_depend>
<build_depend>moveit_msgs</build_depend>
<build_depend>tf</build_depend>
<!-- new dependencies -->
<!--<build_depend>new build dependency</build_depend>-->
......@@ -69,6 +70,7 @@
<run_depend>pal_navigation_msgs</run_depend>
<run_depend>pal_waypoint_msgs</run_depend>
<run_depend>pal_interaction_msgs</run_depend>
<run_depend>moveit_msgs</run_depend>
<run_depend>tf</run_depend>
<!-- new dependencies -->
<!--<run_depend>new run dependency</run_depend>-->
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment