Skip to content

Commit b8b1d63

Browse files
authored
Merge pull request #96 from petrikvladimir/devel
Fix linking to dynamic_graph_bridge_msgs and fix outdated include paths.
2 parents 8a4e335 + 115d730 commit b8b1d63

File tree

4 files changed

+25
-27
lines changed

4 files changed

+25
-27
lines changed

CMakeLists.txt

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -76,8 +76,9 @@ add_library(ros_bridge SHARED ${${PROJECT_NAME}_SOURCES}
7676
${${PROJECT_NAME}_HEADERS})
7777
target_include_directories(ros_bridge SYSTEM PUBLIC ${catkin_INCLUDE_DIRS})
7878
target_include_directories(ros_bridge PUBLIC $<INSTALL_INTERFACE:include>)
79-
target_link_libraries(ros_bridge ${catkin_LIBRARIES} sot-core::sot-core
80-
pinocchio::pinocchio)
79+
target_link_libraries(
80+
ros_bridge ${catkin_LIBRARIES} sot-core::sot-core pinocchio::pinocchio
81+
dynamic_graph_bridge_msgs::dynamic_graph_bridge_msgs)
8182

8283
if(SUFFIX_SO_VERSION)
8384
set_target_properties(ros_bridge PROPERTIES SOVERSION ${PROJECT_VERSION})

include/dynamic_graph_bridge/fwd.hh

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -9,12 +9,12 @@
99
#ifndef DYNAMIC_GRAPH_BRIDGE_FWD_HH
1010
#define DYNAMIC_GRAPH_BRIDGE_FWD_HH
1111

12-
#include <dynamic-graph/python/fwd.hh>
12+
#include <dynamic-graph/fwd.hh>
1313

1414
namespace dynamicgraph {
1515
// classes defined in sot-core
1616
class Interpreter;
17-
typedef shared_ptr<Interpreter> InterpreterPtr_t;
17+
typedef std::shared_ptr<Interpreter> InterpreterPtr_t;
1818
} // namespace dynamicgraph
1919

2020
#endif // DYNAMIC_GRAPH_PYTHON_FWD_HH

scripts/tf_publisher

Lines changed: 12 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -6,22 +6,24 @@
66
# through dynamic_graph_bridge.
77
#
88

9+
import logging
10+
911
import rospy
1012

1113
import tf
1214
import geometry_msgs.msg
1315

1416

1517
def main():
16-
rospy.init_node('tf_publisher', anonymous=True)
18+
rospy.init_node("tf_publisher", anonymous=True)
1719

18-
frame = rospy.get_param('~frame', '')
19-
childFrame = rospy.get_param('~child_frame', '')
20-
topic = rospy.get_param('~topic', '')
21-
rateSeconds = rospy.get_param('~rate', 5)
20+
frame = rospy.get_param("~frame", "")
21+
childFrame = rospy.get_param("~child_frame", "")
22+
topic = rospy.get_param("~topic", "")
23+
rateSeconds = rospy.get_param("~rate", 5)
2224

2325
if not frame or not childFrame or not topic:
24-
logpy.error("frame, childFrame and topic are required parameters")
26+
logging.error("frame, childFrame and topic are required parameters")
2527
return
2628

2729
rate = rospy.Rate(rateSeconds)
@@ -35,11 +37,10 @@ def main():
3537
ok = False
3638
while not rospy.is_shutdown() and not ok:
3739
try:
38-
tl.waitForTransform(childFrame, frame,
39-
rospy.Time(), rospy.Duration(0.1))
40+
tl.waitForTransform(childFrame, frame, rospy.Time(), rospy.Duration(0.1))
4041
ok = True
41-
except tf.Exception, e:
42-
rospy.logwarn("waiting for tf transform")
42+
except tf.Exception:
43+
logging.warning("waiting for tf transform")
4344
ok = False
4445

4546
while not rospy.is_shutdown():
@@ -60,4 +61,5 @@ def main():
6061
pub.publish(transform)
6162
rate.sleep()
6263

64+
6365
main()

src/CMakeLists.txt

Lines changed: 8 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -10,9 +10,8 @@ foreach(plugin ${plugins})
1010
${PROJECT_VERSION})
1111
endif(SUFFIX_SO_VERSION)
1212

13-
target_link_libraries(
14-
${LIBRARY_NAME} ${${LIBRARY_NAME}_deps} ${catkin_LIBRARIES} ros_bridge
15-
dynamic_graph_bridge_msgs::dynamic_graph_bridge_msgs)
13+
target_link_libraries(${LIBRARY_NAME} ${${LIBRARY_NAME}_deps}
14+
${catkin_LIBRARIES} ros_bridge)
1615

1716
if(NOT INSTALL_PYTHON_INTERFACE_ONLY)
1817
install(
@@ -46,10 +45,8 @@ if(BUILD_PYTHON_INTERFACE)
4645

4746
# ros_interperter library.
4847
add_library(ros_interpreter ros_interpreter.cpp)
49-
target_link_libraries(
50-
ros_interpreter ros_bridge ${catkin_LIBRARIES}
51-
dynamic-graph-python::dynamic-graph-python
52-
dynamic_graph_bridge_msgs::dynamic_graph_bridge_msgs)
48+
target_link_libraries(ros_interpreter ros_bridge ${catkin_LIBRARIES}
49+
dynamic-graph-python::dynamic-graph-python)
5350

5451
install(
5552
TARGETS ros_interpreter
@@ -60,16 +57,14 @@ endif(BUILD_PYTHON_INTERFACE)
6057
# Stand alone embedded intepreter with a robot controller.
6158
add_executable(geometric_simu geometric_simu.cpp sot_loader.cpp
6259
sot_loader_basic.cpp)
63-
target_link_libraries(
64-
geometric_simu Boost::program_options ${CMAKE_DL_LIBS} ${catkin_LIBRARIES}
65-
ros_bridge dynamic_graph_bridge_msgs::dynamic_graph_bridge_msgs)
60+
target_link_libraries(geometric_simu Boost::program_options ${CMAKE_DL_LIBS}
61+
${catkin_LIBRARIES} ros_bridge)
6662
install(TARGETS geometric_simu DESTINATION lib/${PROJECT_NAME})
6763

6864
# Sot loader library
6965
add_library(sot_loader sot_loader.cpp sot_loader_basic.cpp)
70-
target_link_libraries(
71-
sot_loader Boost::program_options ${catkin_LIBRARIES} ros_bridge
72-
dynamic_graph_bridge_msgs::dynamic_graph_bridge_msgs)
66+
target_link_libraries(sot_loader Boost::program_options ${catkin_LIBRARIES}
67+
ros_bridge)
7368
install(
7469
TARGETS sot_loader
7570
EXPORT ${TARGETS_EXPORT_NAME}

0 commit comments

Comments
 (0)