Skip to content
This repository has been archived by the owner on Jan 10, 2024. It is now read-only.

Commit

Permalink
Add build support for the conversor for ros1 and ros2. Add Dockerfile…
Browse files Browse the repository at this point in the history
…s to verify the build
  • Loading branch information
vinnnyr committed Nov 27, 2022
1 parent 3ff6ad4 commit 13fb913
Show file tree
Hide file tree
Showing 8 changed files with 203 additions and 72 deletions.
2 changes: 2 additions & 0 deletions .dockerignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
Dockerfile.*
README.md
131 changes: 96 additions & 35 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,43 +2,104 @@ cmake_minimum_required(VERSION 3.0.2)
project(fields2cover_ros)

set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_STANDARD_REQUIRED ON)

find_package(catkin REQUIRED
COMPONENTS
roscpp
std_msgs
geometry_msgs
sensor_msgs
dynamic_reconfigure
)

generate_dynamic_reconfigure_options(
cfg/Controls.cfg
)

catkin_package(
CATKIN_DEPENDS
roscpp
std_msgs
geometry_msgs
sensor_msgs
)
# Update the policy setting to avoid an error when loading the ament_cmake package
# at the current cmake version level
if(POLICY CMP0057)
cmake_policy(SET CMP0057 NEW)
endif()

find_package(Fields2Cover REQUIRED)

include_directories(
include
${catkin_INCLUDE_DIRS}
)

add_executable(visualizer_node
src/fields2cover_visualizer_node.cpp
src/Fields2CoverVisualizerNode.cpp
src/ros/conversor.cpp
)

target_link_libraries(visualizer_node
${catkin_LIBRARIES} Fields2Cover
)
add_dependencies(visualizer_node ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_gencfg )
find_package(ament_cmake QUIET)

if ( ament_cmake_FOUND )
set(IS_ROS2 ON)
message(STATUS "fields2cover_ros is being built using AMENT.")
set(BUILD_TOOL_INCLUDE_DIRS ${ament_INCLUDE_DIRS})

find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(nav_msgs REQUIRED)

set(dependencies
rclcpp
std_msgs
geometry_msgs
sensor_msgs
nav_msgs
)

include_directories(
include
${BUILD_TOOL_INCLUDE_DIRS}
)

add_library(${PROJECT_NAME} SHARED src/ros/conversor.cpp)
ament_target_dependencies(
${PROJECT_NAME}
${dependencies}
)
target_compile_definitions(${PROJECT_NAME} PUBLIC IS_ROS2)
target_link_libraries(${PROJECT_NAME}
Fields2Cover
)

install(DIRECTORY include/
DESTINATION include/
)
install(TARGETS ${PROJECT_NAME}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
INCLUDES DESTINATION include
)
ament_export_include_directories(include)
ament_export_libraries(${PROJECT_NAME})
ament_export_dependencies(${dependencies})

ament_package()
elseif( CATKIN_DEVEL_PREFIX OR CATKIN_BUILD_BINARY_PACKAGE )
message(STATUS "fields2cover_ros is being built using CATKIN.")
find_package(catkin REQUIRED
COMPONENTS
roscpp
std_msgs
geometry_msgs
sensor_msgs
dynamic_reconfigure
)

generate_dynamic_reconfigure_options(
cfg/Controls.cfg
)

catkin_package(
CATKIN_DEPENDS
roscpp
std_msgs
geometry_msgs
sensor_msgs
)


include_directories(
include
${catkin_INCLUDE_DIRS}
)

add_executable(visualizer_node
src/fields2cover_visualizer_node.cpp
src/Fields2CoverVisualizerNode.cpp
src/ros/conversor.cpp
)

target_link_libraries(visualizer_node
${catkin_LIBRARIES} Fields2Cover
)
add_dependencies(visualizer_node ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_gencfg )
endif()

17 changes: 17 additions & 0 deletions Dockerfile.humble
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
FROM ros:humble
RUN mkdir -p /ws/src
WORKDIR /ws
RUN apt-get update -qq && apt-get install -qqy python3-osrf-pycommon git software-properties-common

RUN add-apt-repository -y ppa:ubuntugis/ubuntugis-unstable && apt-get update -qq

# build and get deps here to help with caching
RUN git clone https://github.com/Fields2Cover/Fields2Cover.git src/fields2cover --branch main
RUN rosdep install -r --ignore-src -y --from-paths .
RUN bash -c 'source /opt/ros/*/setup.bash && colcon build'

# now build the rest
COPY . src/fields2cover_ros/.
RUN rosdep install -r --ignore-src -y --from-paths .
RUN bash -c 'source /opt/ros/*/setup.bash && colcon build'

17 changes: 17 additions & 0 deletions Dockerfile.noetic
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
FROM ros:noetic
RUN mkdir -p /ws/src
WORKDIR /ws
RUN apt-get update -qq && apt-get install -qqy python3-catkin-tools python3-osrf-pycommon git software-properties-common

RUN add-apt-repository -y ppa:ubuntugis/ppa && apt-get update -qq

# build and get deps here to help with caching
RUN git clone https://github.com/Fields2Cover/Fields2Cover.git src/fields2cover --branch main
RUN rosdep install -r --ignore-src -y --from-paths .
RUN bash -c 'source /opt/ros/*/setup.bash && catkin build -j$(nproc) --verbose'

# now build the rest
COPY . src/fields2cover_ros/.
RUN rosdep install -r --ignore-src -y --from-paths src
RUN bash -c 'source devel/setup.bash && catkin build -j$(nproc) --verbose'

51 changes: 36 additions & 15 deletions include/ros/conversor.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,30 +6,50 @@


#include <fields2cover.h>
#include <nav_msgs/Path.h>
// #include <visualization_msgs/Marker.h>
// #include <visualization_msgs/MarkerArray.h>
#include <geometry_msgs/Polygon.h>
#include <geometry_msgs/Pose.h>
#include <geometry_msgs/Point32.h>
#include <geometry_msgs/Point.h>
#include <vector>

#ifdef IS_ROS2
#include <nav_msgs/msg/path.hpp>
#include <geometry_msgs/msg/polygon.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <geometry_msgs/msg/point32.hpp>
#include <geometry_msgs/msg/point.h>
#else
#include <nav_msgs/Path.h>
// #include <visualization_msgs/Marker.h>
// #include <visualization_msgs/MarkerArray.h>
#include <geometry_msgs/Polygon.h>
#include <geometry_msgs/Pose.h>
#include <geometry_msgs/Point32.h>
#include <geometry_msgs/Point.h>
#endif


namespace conversor {

#ifdef IS_ROS2
namespace GeometryMsgs = geometry_msgs::msg;
namespace NavMsgs = nav_msgs::msg;
#else
namespace GeometryMsgs = geometry_msgs;
namespace NavMsgs = nav_msgs;
#endif

class ROS {
public:
static void to(const F2CPoint& _point, geometry_msgs::Point32& _p32);
static void to(const F2CPoint& _point, geometry_msgs::Point& _p64);
static void to(const F2CPoint& _point, GeometryMsgs::Point32& _p32);
static void to(const F2CPoint& _point, GeometryMsgs::Point& _p64);

template <class T>
static void to(const T& _curve, geometry_msgs::Polygon& _poly);
static void to(const T& _curve, GeometryMsgs::Polygon& _poly);

static void to(const F2CCell& _poly,
std::vector<geometry_msgs::Polygon>& _ros_poly);
std::vector<GeometryMsgs::Polygon>& _ros_poly);

static void to(const F2CCells& _polys,
std::vector<std::vector<geometry_msgs::Polygon>>& _ros_polys);
std::vector<std::vector<GeometryMsgs::Polygon>>& _ros_polys);

static void to(const F2CLineString& _line, nav_msgs::Path& _path);
static void to(const F2CLineString& _line, NavMsgs::Path& _path);

// static void to(const F2CLineString& _line,
// visualization_msgs::MarkerArray& _markers);
Expand All @@ -38,11 +58,12 @@ class ROS {
};

template <class T>
inline void ROS::to(const T& _curve, geometry_msgs::Polygon& _poly) {
geometry_msgs::Point32 p32;
inline void ROS::to(const T& _curve, GeometryMsgs::Polygon& _poly) {
GeometryMsgs::Point32 p32;
for (const auto& p : _curve) {
to(p, p32);
_poly.points.push_back(p32);
}
}

} // namespace conversor
31 changes: 21 additions & 10 deletions package.xml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<package format="2">
<package format="3">
<name>fields2cover_ros</name>
<version>1.2.0</version>
<description>The fields2cover_ros package is a wrapper of the fields2cover package</description>
Expand All @@ -8,30 +8,41 @@

<license>BSD 3-Clause license</license>

<buildtool_depend>catkin</buildtool_depend>
<buildtool_depend condition="$ROS_VERSION == 1">catkin</buildtool_depend>
<buildtool_depend condition="$ROS_VERSION == 2">ament_cmake</buildtool_depend>

<build_depend>roscpp</build_depend>
<build_depend>rostest</build_depend>
<build_depend condition="$ROS_VERSION == 1">roscpp</build_depend>
<build_depend condition="$ROS_VERSION == 1">rostest</build_depend>
<build_depend condition="$ROS_VERSION == 2">rclcpp</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>message_generation</build_depend>
<build_depend>nav_msgs</build_depend>
<build_depend condition="$ROS_VERSION == 1">message_generation</build_depend>
<build_depend>fields2cover</build_depend>

<build_export_depend>roscpp</build_export_depend>
<build_export_depend>rostest</build_export_depend>
<build_export_depend condition="$ROS_VERSION == 1">roscpp</build_export_depend>
<build_export_depend condition="$ROS_VERSION == 1">rostest</build_export_depend>
<build_export_depend condition="$ROS_VERSION == 2">rclcpp</build_export_depend>
<build_export_depend>std_msgs</build_export_depend>
<build_export_depend>geometry_msgs</build_export_depend>
<build_export_depend>sensor_msgs</build_export_depend>
<build_export_depend>nav_msgs</build_export_depend>
<build_export_depend>fields2cover</build_export_depend>

<exec_depend>message_runtime</exec_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>rostest</exec_depend>
<exec_depend condition="$ROS_VERSION == 1">message_runtime</exec_depend>
<exec_depend condition="$ROS_VERSION == 1">roscpp</exec_depend>
<exec_depend condition="$ROS_VERSION == 1">rostest</exec_depend>
<exec_depend condition="$ROS_VERSION == 2">rclcpp</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>sensor_msgs</exec_depend>
<exec_depend>nav_msgs</exec_depend>
<exec_depend>fields2cover</exec_depend>

<export>
<build_type condition="$ROS_VERSION == 1">catkin</build_type>
<build_type condition="$ROS_VERSION == 2">ament_cmake</build_type>
</export>

</package>
6 changes: 3 additions & 3 deletions src/Fields2CoverVisualizerNode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,14 +54,14 @@ namespace fields2cover_ros {
geometry_msgs::PolygonStamped polygon_st;
polygon_st.header.stamp = ros::Time::now();
polygon_st.header.frame_id = "base_link";
ROS::to(f.getCellBorder(0), polygon_st.polygon);
conversor::ROS::to(f.getCellBorder(0), polygon_st.polygon);
field_polygon_publisher_.publish(polygon_st);
polygon_st.polygon.points.clear();

geometry_msgs::PolygonStamped polygon_st2;
polygon_st2.header.stamp = ros::Time::now();
polygon_st2.header.frame_id = "base_link";
ROS::to(no_headlands.getGeometry(0), polygon_st2.polygon);
conversor::ROS::to(no_headlands.getGeometry(0), polygon_st2.polygon);
field_no_headlands_publisher_.publish(polygon_st2);
polygon_st2.polygon.points.clear();

Expand Down Expand Up @@ -158,7 +158,7 @@ namespace fields2cover_ros {
geometry_msgs::Point ros_p;

for (auto&& s : path.states) {
ROS::to(s.point, ros_p);
conversor::ROS::to(s.point, ros_p);
marker_swaths.points.push_back(ros_p);
}
field_swaths_publisher_.publish(marker_swaths);
Expand Down
20 changes: 11 additions & 9 deletions src/ros/conversor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,23 +7,24 @@
#include "ros/conversor.h"



void ROS::to(const F2CPoint& _point, geometry_msgs::Point32& _p32) {
namespace conversor
{
void ROS::to(const F2CPoint& _point, GeometryMsgs::Point32& _p32) {
_p32.x = static_cast<float>(_point.getX());
_p32.y = static_cast<float>(_point.getY());
_p32.z = static_cast<float>(_point.getZ());
}

void ROS::to(const F2CPoint& _point, geometry_msgs::Point& _p64) {
void ROS::to(const F2CPoint& _point, GeometryMsgs::Point& _p64) {
_p64.x = _point.getX();
_p64.y = _point.getY();
_p64.z = _point.getZ();
}


void ROS::to(const F2CCell& _poly,
std::vector<geometry_msgs::Polygon>& _ros_poly) {
geometry_msgs::Polygon ros_ring;
std::vector<GeometryMsgs::Polygon>& _ros_poly) {
GeometryMsgs::Polygon ros_ring;
to(_poly.getExteriorRing(), ros_ring);
_ros_poly.push_back(ros_ring);
const int n_in_rings = _poly.size();
Expand All @@ -35,20 +36,21 @@ void ROS::to(const F2CCell& _poly,
}

void ROS::to(const F2CCells& _polys,
std::vector<std::vector<geometry_msgs::Polygon>>& _ros_polys) {
std::vector<std::vector<GeometryMsgs::Polygon>>& _ros_polys) {
for (auto&& p : _polys) {
std::vector<geometry_msgs::Polygon> poly;
std::vector<GeometryMsgs::Polygon> poly;
to(p, poly);
_ros_polys.push_back(poly);
}
}

void ROS::to(const F2CLineString& _line, nav_msgs::Path& _path) {
geometry_msgs::PoseStamped pose;
void ROS::to(const F2CLineString& _line, NavMsgs::Path& _path) {
GeometryMsgs::PoseStamped pose;
for (auto&& p : _line) {
to(p, pose.pose.position);
_path.poses.push_back(pose);
}
}

} // namespace conversor

0 comments on commit 13fb913

Please sign in to comment.