Skip to content

Commit

Permalink
[ros2] gazebo_ros_joint_state_publisher (#795)
Browse files Browse the repository at this point in the history
* Port joint_state_publisher, copyright failing checker, still need to add a test

* Fix copyright

* Tests for joint state publisher

* cleanup

* depend on sensor_msgs

* Use node's logger
  • Loading branch information
chapulina authored Aug 9, 2018
1 parent cd2a446 commit 70c2587
Show file tree
Hide file tree
Showing 11 changed files with 515 additions and 257 deletions.

This file was deleted.

158 changes: 0 additions & 158 deletions .ros1_unported/gazebo_plugins/src/gazebo_ros_joint_state_publisher.cpp

This file was deleted.

19 changes: 17 additions & 2 deletions gazebo_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -16,21 +16,35 @@ find_package(gazebo_dev REQUIRED)
find_package(gazebo_ros REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(rclcpp REQUIRED)
find_package(sensor_msgs REQUIRED)

include_directories(include
${gazebo_ros_INCLUDE_DIRS}
${geometry_msgs_INCLUDE_DIRS}
${sensor_msgs_INCLUDE_DIRS}
)

# gazebo_ros_joint_state_publisher
add_library(gazebo_ros_joint_state_publisher SHARED
src/gazebo_ros_joint_state_publisher.cpp
)
ament_target_dependencies(gazebo_ros_joint_state_publisher
"gazebo_dev"
"gazebo_ros"
"rclcpp"
"sensor_msgs"
)
ament_export_libraries(gazebo_ros_force)

# gazebo_ros_force
add_library(gazebo_ros_force SHARED
src/gazebo_ros_force.cpp
)
ament_target_dependencies(gazebo_ros_force
"rclcpp"
"gazebo_dev"
"gazebo_ros"
"geometry_msgs"
"rclcpp"
)
ament_export_libraries(gazebo_ros_force)

Expand All @@ -39,9 +53,9 @@ add_library(gazebo_ros_template SHARED
src/gazebo_ros_template.cpp
)
ament_target_dependencies(gazebo_ros_template
"rclcpp"
"gazebo_dev"
"gazebo_ros"
"rclcpp"
)
ament_export_libraries(gazebo_ros_template)

Expand All @@ -64,6 +78,7 @@ install(DIRECTORY include/
install(
TARGETS
gazebo_ros_force
gazebo_ros_joint_state_publisher
gazebo_ros_template
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
Expand Down
Loading

0 comments on commit 70c2587

Please sign in to comment.