Skip to content
Merged
31 changes: 17 additions & 14 deletions common_interfaces_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# Define a list of ROS 2 dependencies for easy modularity
set(ros2_dependencies
rclcpp
nav_msgs
Expand All @@ -17,18 +16,16 @@ set(ros2_dependencies
ros_gz_interfaces
)

# Find ament_cmake (required for the build system itself)
find_package(ament_cmake REQUIRED)

# Loop through the list to find all specified ROS 2 packages automatically
foreach(dependency IN LISTS ros2_dependencies)
find_package(${dependency} REQUIRED)
endforeach()

# Find OpenCV explicitly (Required by Camera and Classnet for cv::Mat and cv::dnn)
find_package(OpenCV REQUIRED)
find_package(Boost REQUIRED COMPONENTS system thread)
find_package(nlohmann_json REQUIRED)

# Create the shared library from the source files matching the new structure
add_library(${PROJECT_NAME} SHARED
src/hal/bumper.cpp
src/hal/camera.cpp
Expand All @@ -38,35 +35,41 @@ add_library(${PROJECT_NAME} SHARED
src/hal/motors.cpp
src/hal/odometry.cpp
src/hal/sim_time.cpp
src/webgui/WebGUIBridge.cpp
)

# Specify the include directories so the compiler finds the .hpp files
target_include_directories(${PROJECT_NAME} PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
${OpenCV_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
)

# Link all listed ROS 2 dependencies and OpenCV to the library
ament_target_dependencies(${PROJECT_NAME} ${ros2_dependencies})
target_link_libraries(${PROJECT_NAME} ${OpenCV_LIBRARIES})

# Install the include directory so other packages can do #include
install(DIRECTORY include/
DESTINATION include
target_link_libraries(${PROJECT_NAME}
${OpenCV_LIBRARIES}
Boost::system
Boost::thread
nlohmann_json::nlohmann_json
)

# Install the library and export the target for downstream usage
install(DIRECTORY include/ DESTINATION include)

install(TARGETS ${PROJECT_NAME}
EXPORT ${PROJECT_NAME}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)

# Export include directories, targets, and dependencies
ament_export_include_directories(include)
ament_export_targets(${PROJECT_NAME} HAS_LIBRARY_TARGET)
ament_export_dependencies(${ros2_dependencies})
ament_export_dependencies(
${ros2_dependencies}
OpenCV
nlohmann_json
Boost
)

ament_package()
38 changes: 8 additions & 30 deletions common_interfaces_cpp/include/common_interfaces_cpp/hal/camera.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,64 +3,42 @@

#include <string>
#include <memory>
#include <mutex>
#include "rclcpp/rclcpp.hpp"
#include "sensor_msgs/msg/image.hpp"
#include <opencv2/opencv.hpp>
#include <cv_bridge/cv_bridge.h>

/* ### AUXILIARY FUNCTIONS ### */

const int MAXRANGE = 8; // max length received from imageD
const int MAXRANGE = 8;
const int MINRANGE = 0;

/* Represents a camera image with metadata and pixel data. */
class Image {
public:
Image();
int height; // Image height [pixels]
int width; // Image width [pixels]
double timeStamp; // Time stamp [s] */
std::string format; // Image format string (RGB8, BGR,...)
cv::Mat data; // The image data itself
int height;
int width;
double timeStamp;
std::string format;
cv::Mat data;

std::string to_string() const;
};

// Declaración de función auxiliar implícita en tu código Python
cv::Mat depthToRGB8(const cv::Mat& gray_img_buff, const std::string& encoding);

/*
* Convert a ROS Image message to a JdeRobot Image object.
*
* Args:
* img: ROS sensor_msgs/Image message.
*
* Returns:
* Image object with BGR data, or None if the message is empty.
*/
std::shared_ptr<Image> imageMsg2Image(const sensor_msgs::msg::Image& img);

/* ### HAL INTERFACE ### */

/* ROS2 node that subscribes to a camera topic and stores the latest image. */
class CameraNode : public rclcpp::Node {
public:
CameraNode(const std::string& topic);

/*
* Return the latest camera image.
*
* Returns:
* Image object with BGR data, or None if no image has been received.
*/
std::shared_ptr<Image> getImage() const;

private:
/* Store the latest image message received from the topic. */
void listener_callback(const sensor_msgs::msg::Image::SharedPtr msg);

rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr sub_;
sensor_msgs::msg::Image last_img_;
mutable std::mutex img_mutex_;
};

#endif
Original file line number Diff line number Diff line change
@@ -0,0 +1,88 @@
#ifndef WEBUI_BRIDGE_HPP_
#define WEBUI_BRIDGE_HPP_

#include <boost/beast/core.hpp>
#include <boost/beast/websocket.hpp>
#include <boost/asio/connect.hpp>
#include <boost/asio/ip/tcp.hpp>
#include <boost/asio/strand.hpp>
#include <nlohmann/json.hpp>
#include <rclcpp/rclcpp.hpp>
#include <string>
#include <thread>
#include <mutex>
#include <memory>
#include <functional>
#include <vector>
#include <cstdio>
#include <chrono>
#include <atomic>

namespace beast = boost::beast;
namespace websocket = beast::websocket;
namespace net = boost::asio;
using tcp = net::ip::tcp;
using json = nlohmann::json;

class WebSocketSession : public std::enable_shared_from_this<WebSocketSession>
{
public:
explicit WebSocketSession(net::io_context& ioc);
void run(const std::string& host, const std::string& port);
void send(const std::string& msg);
void set_message_callback(std::function<void(const std::string&)> cb);

private:
void on_resolve(beast::error_code ec, tcp::resolver::results_type results);
void on_connect(beast::error_code ec, tcp::resolver::results_type::endpoint_type ep);
void on_handshake(beast::error_code ec);
void on_write(beast::error_code ec, std::size_t bytes_transferred);
void on_read(beast::error_code ec, std::size_t bytes_transferred);

tcp::resolver resolver_;
websocket::stream<beast::tcp_stream> ws_;
beast::flat_buffer buffer_;
std::string host_;
std::vector<std::string> write_queue_;
std::mutex queue_mutex_;
bool is_writing_;
std::function<void(const std::string&)> message_callback_;
};

class BaseWebGUI : public rclcpp::Node
{
public:
BaseWebGUI(const std::string& node_name, const std::string& host, const std::string& port, double freq, const std::string& stats_topic = "/stats");
virtual ~BaseWebGUI();

virtual void process_message(const std::string& msg);
virtual json update_gui() = 0;
virtual std::vector<rclcpp::Node::SharedPtr> get_nodes();

void send_to_client(const std::string& msg);

protected:
double real_time_factor_;
bool ack_frontend_;
bool ack_;
std::mutex ack_lock_;
double brain_freq_;
double gui_freq_;
std::string stats_topic_;

private:
void gui_timer_callback();
void stats_timer_callback();

net::io_context ioc_;
std::shared_ptr<WebSocketSession> ws_session_;
std::thread ioc_thread_;

rclcpp::TimerBase::SharedPtr gui_timer_;
rclcpp::TimerBase::SharedPtr stats_timer_;

std::atomic<int> iteration_counter_;
std::chrono::time_point<std::chrono::steady_clock> last_freq_update_;
};

#endif
2 changes: 2 additions & 0 deletions common_interfaces_cpp/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,8 @@
<depend>rclcpp</depend>
<depend>cv_bridge</depend>
<depend>opencv</depend>
<depend>boost</depend>
<depend>nlohmann-json-dev</depend>

<depend>nav_msgs</depend>
<depend>sensor_msgs</depend>
Expand Down
19 changes: 13 additions & 6 deletions common_interfaces_cpp/src/hal/camera.cpp
Original file line number Diff line number Diff line change
@@ -1,15 +1,16 @@
#include "common_interfaces_cpp/hal/camera.hpp"
#include <sstream>
#include <cmath>
#include <cv_bridge/cv_bridge.h>

const double PI = M_PI;

Image::Image() {
height = 480; // Image height [pixels]
width = 640; // Image width [pixels]
timeStamp = 0; // Time stamp [s] */
format = ""; // Image format string (RGB8, BGR,...)
data = cv::Mat::zeros(height, width, CV_8UC3); // The image data itself
height = 480;
width = 640;
timeStamp = 0;
format = "";
data = cv::Mat::zeros(height, width, CV_8UC3);
}

std::string Image::to_string() const {
Expand Down Expand Up @@ -62,9 +63,15 @@ CameraNode::CameraNode(const std::string& topic)
}

void CameraNode::listener_callback(const sensor_msgs::msg::Image::SharedPtr msg) {
std::lock_guard<std::mutex> lock(img_mutex_);
last_img_ = *msg;
}

std::shared_ptr<Image> CameraNode::getImage() const {
return imageMsg2Image(last_img_);
sensor_msgs::msg::Image img_copy;
{
std::lock_guard<std::mutex> lock(img_mutex_);
img_copy = last_img_;
}
return imageMsg2Image(img_copy);
}
Loading