Skip to content

Commit

Permalink
starting to convert ros to rclcpp
Browse files Browse the repository at this point in the history
  • Loading branch information
alexoj46 committed Jan 2, 2025
1 parent 34d4dcf commit 2d79505
Show file tree
Hide file tree
Showing 3 changed files with 30 additions and 17 deletions.
39 changes: 26 additions & 13 deletions src/mil_common/mil_passive_sonar/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,12 +1,14 @@
cmake_minimum_required(VERSION 3.5)
project(mil_passive_sonar)

find_package(ament_cmake REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(tf2 REQUIRED)
find_package(std_msgs REQUIRED)
find_package(rclpy REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(rclcpp REQUIRED)
find_package(Boost REQUIRED)

# Default to C++17
if(NOT CMAKE_CXX_STANDARD)
Expand Down Expand Up @@ -34,21 +36,32 @@ rosidl_generate_interfaces(${PROJECT_NAME}
ADD_LINTER_TESTS
)

#catkin_package(
# DEPENDS # TODO
# CATKIN_DEPENDS tf std_msgs message_runtime message_generation rospy
# INCLUDE_DIRS # TODO include
# LIBRARIES # TODO
#)
ament_export_dependencies(
rosidl_default_runtime
tf2
std_msgs
geometry_msgs
rclcpp
)

ament_package()

include_directories( ${Boost_INCLUDE_DIR} ${catkin_INCLUDE_DIRS})

# Build sylphase_ros_bridge
#add_executable(sylphase_sonar_ros_bridge src/sylphase_ros_bridge.cpp)
#target_link_libraries(sylphase_sonar_ros_bridge ${catkin_LIBRARIES})
#add_dependencies(sylphase_sonar_ros_bridge ${catkin_EXPORTED_TARGETS})
#
#install(PROGRAMS scripts/ping_publisher scripts/ping_printer scripts/ping_logger scripts/ping_plotter scripts/hydrophones DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})
add_executable(sylphase_sonar_ros_bridge src/sylphase_ros_bridge.cpp)
rosidl_get_typesupport_target(cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp")
target_link_libraries(
sylphase_sonar_ros_bridge
rclcpp::rclcpp
tf2::tf2
${std_msgs_TARGETS}
${geometry_msgs_TARGETS}
${cpp_typesupport_target}
)
target_include_directories(sylphase_sonar_ros_bridge PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)

ament_package()
install(PROGRAMS scripts/ping_publisher scripts/ping_printer scripts/ping_logger scripts/ping_plotter scripts/hydrophones DESTINATION lib/${PROJECT_NAME})

4 changes: 2 additions & 2 deletions src/mil_common/mil_passive_sonar/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,9 +15,9 @@
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>tf</build_depend>
<build_depend>tf2</build_depend>
<!-- Dependencies needed after this package is compiled. -->
<exec_depend>tf</exec_depend>
<exec_depend>tf2</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>message_runtime</exec_depend>
<exec_depend>message_generation</exec_depend>
Expand Down
4 changes: 2 additions & 2 deletions src/mil_common/mil_passive_sonar/src/sylphase_ros_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,8 @@
* and publish it to ROS as a mil_passive_sonar/HydrophoneSamples message
*/
#include <arpa/inet.h>
#include <mil_passive_sonar/HydrophoneSamplesStamped.h>
#include <ros/ros.h>
#include "mil_passive_sonar/msg/hydrophone_samples_stamped.hpp"
#include "rclcpp/rclcpp.hpp"

#include <boost/asio.hpp>

Expand Down

0 comments on commit 2d79505

Please sign in to comment.