Skip to content
Snippets Groups Projects
Unverified Commit b8b1d632 authored by Guilhem Saurel's avatar Guilhem Saurel Committed by GitHub
Browse files

Merge pull request #96 from petrikvladimir/devel

Fix linking to dynamic_graph_bridge_msgs and fix outdated include paths.
parents 8a4e335c 115d730c
No related branches found
No related tags found
No related merge requests found
Pipeline #21782 passed with warnings
......@@ -76,8 +76,9 @@ add_library(ros_bridge SHARED ${${PROJECT_NAME}_SOURCES}
${${PROJECT_NAME}_HEADERS})
target_include_directories(ros_bridge SYSTEM PUBLIC ${catkin_INCLUDE_DIRS})
target_include_directories(ros_bridge PUBLIC $<INSTALL_INTERFACE:include>)
target_link_libraries(ros_bridge ${catkin_LIBRARIES} sot-core::sot-core
pinocchio::pinocchio)
target_link_libraries(
ros_bridge ${catkin_LIBRARIES} sot-core::sot-core pinocchio::pinocchio
dynamic_graph_bridge_msgs::dynamic_graph_bridge_msgs)
if(SUFFIX_SO_VERSION)
set_target_properties(ros_bridge PROPERTIES SOVERSION ${PROJECT_VERSION})
......
......@@ -9,12 +9,12 @@
#ifndef DYNAMIC_GRAPH_BRIDGE_FWD_HH
#define DYNAMIC_GRAPH_BRIDGE_FWD_HH
#include <dynamic-graph/python/fwd.hh>
#include <dynamic-graph/fwd.hh>
namespace dynamicgraph {
// classes defined in sot-core
class Interpreter;
typedef shared_ptr<Interpreter> InterpreterPtr_t;
typedef std::shared_ptr<Interpreter> InterpreterPtr_t;
} // namespace dynamicgraph
#endif // DYNAMIC_GRAPH_PYTHON_FWD_HH
......@@ -6,6 +6,8 @@
# through dynamic_graph_bridge.
#
import logging
import rospy
import tf
......@@ -13,15 +15,15 @@ import geometry_msgs.msg
def main():
rospy.init_node('tf_publisher', anonymous=True)
rospy.init_node("tf_publisher", anonymous=True)
frame = rospy.get_param('~frame', '')
childFrame = rospy.get_param('~child_frame', '')
topic = rospy.get_param('~topic', '')
rateSeconds = rospy.get_param('~rate', 5)
frame = rospy.get_param("~frame", "")
childFrame = rospy.get_param("~child_frame", "")
topic = rospy.get_param("~topic", "")
rateSeconds = rospy.get_param("~rate", 5)
if not frame or not childFrame or not topic:
logpy.error("frame, childFrame and topic are required parameters")
logging.error("frame, childFrame and topic are required parameters")
return
rate = rospy.Rate(rateSeconds)
......@@ -35,11 +37,10 @@ def main():
ok = False
while not rospy.is_shutdown() and not ok:
try:
tl.waitForTransform(childFrame, frame,
rospy.Time(), rospy.Duration(0.1))
tl.waitForTransform(childFrame, frame, rospy.Time(), rospy.Duration(0.1))
ok = True
except tf.Exception, e:
rospy.logwarn("waiting for tf transform")
except tf.Exception:
logging.warning("waiting for tf transform")
ok = False
while not rospy.is_shutdown():
......@@ -60,4 +61,5 @@ def main():
pub.publish(transform)
rate.sleep()
main()
......@@ -10,9 +10,8 @@ foreach(plugin ${plugins})
${PROJECT_VERSION})
endif(SUFFIX_SO_VERSION)
target_link_libraries(
${LIBRARY_NAME} ${${LIBRARY_NAME}_deps} ${catkin_LIBRARIES} ros_bridge
dynamic_graph_bridge_msgs::dynamic_graph_bridge_msgs)
target_link_libraries(${LIBRARY_NAME} ${${LIBRARY_NAME}_deps}
${catkin_LIBRARIES} ros_bridge)
if(NOT INSTALL_PYTHON_INTERFACE_ONLY)
install(
......@@ -46,10 +45,8 @@ if(BUILD_PYTHON_INTERFACE)
# ros_interperter library.
add_library(ros_interpreter ros_interpreter.cpp)
target_link_libraries(
ros_interpreter ros_bridge ${catkin_LIBRARIES}
dynamic-graph-python::dynamic-graph-python
dynamic_graph_bridge_msgs::dynamic_graph_bridge_msgs)
target_link_libraries(ros_interpreter ros_bridge ${catkin_LIBRARIES}
dynamic-graph-python::dynamic-graph-python)
install(
TARGETS ros_interpreter
......@@ -60,16 +57,14 @@ endif(BUILD_PYTHON_INTERFACE)
# Stand alone embedded intepreter with a robot controller.
add_executable(geometric_simu geometric_simu.cpp sot_loader.cpp
sot_loader_basic.cpp)
target_link_libraries(
geometric_simu Boost::program_options ${CMAKE_DL_LIBS} ${catkin_LIBRARIES}
ros_bridge dynamic_graph_bridge_msgs::dynamic_graph_bridge_msgs)
target_link_libraries(geometric_simu Boost::program_options ${CMAKE_DL_LIBS}
${catkin_LIBRARIES} ros_bridge)
install(TARGETS geometric_simu DESTINATION lib/${PROJECT_NAME})
# Sot loader library
add_library(sot_loader sot_loader.cpp sot_loader_basic.cpp)
target_link_libraries(
sot_loader Boost::program_options ${catkin_LIBRARIES} ros_bridge
dynamic_graph_bridge_msgs::dynamic_graph_bridge_msgs)
target_link_libraries(sot_loader Boost::program_options ${catkin_LIBRARIES}
ros_bridge)
install(
TARGETS sot_loader
EXPORT ${TARGETS_EXPORT_NAME}
......
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