Skip to content

Commit

Permalink
improved namespace and class hierarchy. Should build with warnings, d…
Browse files Browse the repository at this point in the history
…oes not yet do anything useful
  • Loading branch information
DingoOz committed Dec 18, 2024
1 parent 3fc311b commit 6cfdee8
Show file tree
Hide file tree
Showing 8 changed files with 396 additions and 371 deletions.
58 changes: 20 additions & 38 deletions software/ros_ws/src/sensors/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
# File: CMakeLists.txt

cmake_minimum_required(VERSION 3.8)
project(sensors)

Expand All @@ -10,59 +12,39 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
# Add -Werror flag for release builds
set(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} -Werror")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# Set the C++ standard
set(CMAKE_CXX_STANDARD 20)
set(CMAKE_CXX_STANDARD_REQUIRED ON)

# Find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(std_msgs REQUIRED)

#incldue dirs
# Include directories
include_directories(include)

# Add the m2m2_lidar executable
add_executable(m2m2_lidar
src/m2m2_lidar/main.cpp
src/m2m2_lidar/communication.cpp
src/m2m2_lidar/protocol.cpp
)

#add_executable(m2m2_lidar src/m2m2_lidar.cpp)
#target_include_directories(m2m2_lidar PUBLIC
# $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
# $<INSTALL_INTERFACE:include>)
#target_compile_features(m2m2_lidar PUBLIC c_std_99 cxx_std_17) # Require C99 and C++17


ament_target_dependencies(
m2m2_lidar
"rclcpp"
"sensor_msgs"
"std_msgs"
)
add_executable(m2m2_lidar src/m2m2_lidar/m2m2_lidar.cpp)

#install targets
install(TARGETS m2m2_lidar
DESTINATION lib/${PROJECT_NAME})
ament_target_dependencies(m2m2_lidar rclcpp sensor_msgs std_msgs)

#install include directory
install(DIRECTORY include/
DESTINATION include/
)
# Install targets
install(TARGETS m2m2_lidar DESTINATION lib/${PROJECT_NAME})

#Install launch files
install(DIRECTORY
launch
DESTINATION share/${PROJECT_NAME}
)
# Install include directory
install(DIRECTORY include/ DESTINATION include/)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# comment the line when a copyright and license is added to all source files
set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# comment the line when this package is in a git repo and when
# a copyright and license is added to all source files
set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
Expand Down

This file was deleted.

100 changes: 100 additions & 0 deletions software/ros_ws/src/sensors/include/sensors/m2m2_lidar/m2m2_lidar.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,100 @@
// File: include/sensors/m2m2_lidar/m2m2_lidar.hpp

#pragma once

#include <optional>
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/imu.hpp>
#include <sensor_msgs/msg/laser_scan.hpp>
#include <string>
#include <vector>

namespace sensors
{
namespace lidar
{
namespace m2m2
{

/**
* @brief Configuration parameters for the M2M2 Lidar
*
* Groups all sensor-specific configuration parameters in one place,
* making it easier to modify settings and extend functionality
*/
struct SensorConfig
{
double scanFrequency;
double angularResolution;
double minRange;
double maxRange;
};

/**
* @brief Main class for interfacing with the M2M2 Lidar sensor
*
* This class handles both the network communication and protocol parsing
* for the M2M2 Lidar. While this combines two responsibilities, they are
* tightly coupled for this specific sensor and the data flow between
* them is well-defined.
*/
class Lidar : public rclcpp::Node
{
public:
/**
* @brief Constructor for the M2M2 Lidar node
* @param options ROS2 node options for configuration
*/
explicit Lidar(
const rclcpp::NodeOptions& options = rclcpp::NodeOptions());

/**
* @brief Destructor ensures proper cleanup of resources
*/
~Lidar();

/**
* @brief Initialize the lidar connection and start data processing
* @return true if initialization successful
*/
bool initialize();

private:
// Network communication methods
bool connectToSensor();
bool sendCommand(const std::vector<uint8_t>& command);
std::optional<std::vector<uint8_t>> receiveData();
void disconnect();

// Protocol handling methods
std::vector<uint8_t> createConfigCommand(const SensorConfig& config);
std::optional<sensor_msgs::msg::LaserScan> parseLaserScanData(
const std::vector<uint8_t>& data);
std::optional<sensor_msgs::msg::Imu> parseImuData(
const std::vector<uint8_t>& data);

// ROS2 interface methods
void initializePublishers();
void publishData();
void readSensorData();

// Member variables
std::string _sensorAddress;
uint16_t _sensorPort;
int _socket;
bool _isConnected;
SensorConfig _config;

// Protocol-related constants
static constexpr uint8_t PROTOCOL_HEADER = 0xAA;
static constexpr uint8_t PROTOCOL_FOOTER = 0x55;

// ROS2 publishers
rclcpp::Publisher<sensor_msgs::msg::LaserScan>::SharedPtr _scanPublisher;
rclcpp::Publisher<sensor_msgs::msg::Imu>::SharedPtr _imuPublisher;
rclcpp::TimerBase::SharedPtr _readTimer;
};

}
}
} // namespace sensors::lidar::m2m2

This file was deleted.

76 changes: 0 additions & 76 deletions software/ros_ws/src/sensors/src/m2m2_lidar/communication.cpp

This file was deleted.

Loading

0 comments on commit 6cfdee8

Please sign in to comment.