Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

#include <boost_udp_driver/udp_driver.hpp>
#include <nebula_common/continental/continental_ars548.hpp>
#include <rclcpp/rclcpp.hpp>
#include <nebula_common/loggers/logger.hpp>

#include <nebula_msgs/msg/nebula_packet.hpp>

Expand All @@ -34,7 +34,7 @@ class ContinentalARS548HwInterface
{
public:
/// @brief Constructor
ContinentalARS548HwInterface();
explicit ContinentalARS548HwInterface(const std::shared_ptr<loggers::Logger> & logger);

/// @brief Starting the interface that handles UDP streams
/// @return Resulting status
Expand Down Expand Up @@ -130,10 +130,6 @@ class ContinentalARS548HwInterface
/// @return Resulting status
Status set_yaw_rate(float yaw_rate);

/// @brief Setting rclcpp::Logger
/// @param node Logger
void set_logger(std::shared_ptr<rclcpp::Logger> node);

private:
/// @brief Printing the string to RCLCPP_INFO_STREAM
/// @param info Target string
Expand All @@ -160,8 +156,7 @@ class ContinentalARS548HwInterface
std::unique_ptr<::drivers::udp_driver::UdpDriver> sensor_udp_driver_ptr_;
std::shared_ptr<const ContinentalARS548SensorConfiguration> config_ptr_;
std::function<void(std::unique_ptr<nebula_msgs::msg::NebulaPacket>)> packet_callback_;

std::shared_ptr<rclcpp::Logger> parent_node_logger_ptr_;
std::shared_ptr<loggers::Logger> logger_;
};
} // namespace nebula::drivers::continental_ars548

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include "nebula_hw_interfaces/nebula_hw_interfaces_common/nebula_hw_interface_base.hpp"

#include <nebula_common/continental/continental_srr520.hpp>
#include <rclcpp/rclcpp.hpp>
#include <nebula_common/loggers/logger.hpp>
#include <ros2_socketcan/socket_can_receiver.hpp>
#include <ros2_socketcan/socket_can_sender.hpp>

Expand All @@ -28,6 +28,7 @@
#include <memory>
#include <mutex>
#include <string>
#include <thread>
#include <vector>

namespace nebula::drivers::continental_srr520
Expand All @@ -37,7 +38,7 @@ class ContinentalSRR520HwInterface
{
public:
/// @brief Constructor
ContinentalSRR520HwInterface();
explicit ContinentalSRR520HwInterface(const std::shared_ptr<loggers::Logger> & logger);

/// @brief Starting the interface that handles UDP streams
/// @return Resulting status
Expand Down Expand Up @@ -95,10 +96,6 @@ class ContinentalSRR520HwInterface
float longitudinal_acceleration, float lateral_acceleration, float yaw_rate,
float longitudinal_velocity, bool standstill);

/// @brief Setting rclcpp::Logger
/// @param node Logger
void set_logger(std::shared_ptr<rclcpp::Logger> node);

private:
/// @brief Send a Fd frame
/// @param data a buffer containing the data to send
Expand Down Expand Up @@ -135,7 +132,7 @@ class ContinentalSRR520HwInterface
bool sync_follow_up_sent_{true};
builtin_interfaces::msg::Time last_sync_stamp_;

std::shared_ptr<rclcpp::Logger> parent_node_logger_ptr_;
std::shared_ptr<loggers::Logger> logger_;
};
} // namespace nebula::drivers::continental_srr520

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,8 @@
#endif

#include <boost_udp_driver/udp_driver.hpp>
#include <nebula_common/loggers/logger.hpp>
#include <nebula_common/robosense/robosense_common.hpp>
#include <rclcpp/rclcpp.hpp>

#include <memory>
#include <string>
Expand All @@ -54,19 +54,11 @@ class RobosenseHwInterface
scan_reception_callback_; /**This function pointer is called when the scan is complete*/
std::function<void(std::vector<uint8_t> & buffer)>
info_reception_callback_; /**This function pointer is called when DIFOP packet is received*/
std::shared_ptr<rclcpp::Logger> parent_node_logger_;

/// @brief Printing the string to RCLCPP_INFO_STREAM
/// @param info Target string
void print_info(std::string info);

/// @brief Printing the string to RCLCPP_DEBUG_STREAM
/// @param debug Target string
void print_debug(std::string debug);
std::shared_ptr<loggers::Logger> logger_;

public:
/// @brief Constructor
RobosenseHwInterface();
explicit RobosenseHwInterface(const std::shared_ptr<loggers::Logger> & logger);

/// @brief Callback function to receive the Cloud Packet data from the UDP Driver
/// @param buffer Buffer containing the data received from the UDP socket
Expand Down Expand Up @@ -99,10 +91,6 @@ class RobosenseHwInterface
/// @param scan_callback Callback function
/// @return Resulting status
Status register_info_callback(std::function<void(std::vector<uint8_t> &)> info_callback);

/// @brief Setting rclcpp::Logger
/// @param node Logger
void set_logger(std::shared_ptr<rclcpp::Logger> logger);
};

} // namespace nebula::drivers
Original file line number Diff line number Diff line change
Expand Up @@ -31,15 +31,17 @@

#include <boost_tcp_driver/http_client_driver.hpp>
#include <boost_udp_driver/udp_driver.hpp>
#include <nebula_common/loggers/logger.hpp>
#include <nebula_common/velodyne/velodyne_common.hpp>
#include <nebula_common/velodyne/velodyne_status.hpp>
#include <rclcpp/rclcpp.hpp>

#include <boost/property_tree/json_parser.hpp>
#include <boost/property_tree/ptree.hpp>

#include <chrono>
#include <memory>
#include <string>
#include <thread>
#include <vector>

namespace nebula::drivers
Expand Down Expand Up @@ -136,20 +138,13 @@ class VelodyneHwInterface
std::shared_ptr<const VelodyneSensorConfiguration> sensor_configuration,
boost::property_tree::ptree tree);

std::shared_ptr<rclcpp::Logger> parent_node_logger_;
/// @brief Printing the string to RCLCPP_INFO_STREAM
/// @param info Target string
void print_info(std::string info);
/// @brief Printing the string to RCLCPP_ERROR_STREAM
/// @param error Target string
void print_error(std::string error);
/// @brief Printing the string to RCLCPP_DEBUG_STREAM
/// @param debug Target string
void print_debug(std::string debug);
std::shared_ptr<loggers::Logger> logger_;

public:
/// @brief Constructor
VelodyneHwInterface();
explicit VelodyneHwInterface(const std::shared_ptr<loggers::Logger> & logger);

virtual ~VelodyneHwInterface() = default;

/// @brief Callback function to receive the Cloud Packet data from the UDP Driver
/// @param buffer Buffer containing the data received from the UDP socket
Expand Down Expand Up @@ -261,12 +256,7 @@ class VelodyneHwInterface
/// @param use_dhcp DHCP on
/// @return Resulting status
VelodyneStatus set_net_dhcp(bool use_dhcp);

/// @brief Setting rclcpp::Logger
/// @param node Logger
void set_logger(std::shared_ptr<rclcpp::Logger> node);
};

} // namespace nebula::drivers

#endif // NEBULA_VELODYNE_HW_INTERFACE_H
Original file line number Diff line number Diff line change
Expand Up @@ -25,9 +25,11 @@

namespace nebula::drivers::continental_ars548
{
ContinentalARS548HwInterface::ContinentalARS548HwInterface()
ContinentalARS548HwInterface::ContinentalARS548HwInterface(
const std::shared_ptr<loggers::Logger> & logger)

Check warning on line 29 in nebula_hw_interfaces/src/nebula_continental_hw_interfaces/continental_ars548_hw_interface.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_hw_interfaces/src/nebula_continental_hw_interfaces/continental_ars548_hw_interface.cpp#L28-L29

Added lines #L28 - L29 were not covered by tests
: sensor_io_context_ptr_{new ::drivers::common::IoContext(1)},
sensor_udp_driver_ptr_{new ::drivers::udp_driver::UdpDriver(*sensor_io_context_ptr_)}
sensor_udp_driver_ptr_{new ::drivers::udp_driver::UdpDriver(*sensor_io_context_ptr_)},
logger_(logger)
{
}

Expand Down Expand Up @@ -64,7 +66,7 @@
}
} catch (const std::exception & ex) {
Status status = Status::UDP_CONNECTION_ERROR;
std::cerr << status << config_ptr_->sensor_ip << "," << config_ptr_->data_port << std::endl;
logger_->error("Setting sensor configuration failed");
return status;
}
return Status::OK;
Expand All @@ -87,7 +89,7 @@
void ContinentalARS548HwInterface::receive_sensor_packet_callback(std::vector<uint8_t> & buffer)
{
if (buffer.size() < sizeof(HeaderPacket)) {
print_error("Unrecognized packet. Too short");
logger_->error("Unrecognized packet. Too short");
return;
}

Expand Down Expand Up @@ -513,36 +515,4 @@
return Status::OK;
}

void ContinentalARS548HwInterface::set_logger(std::shared_ptr<rclcpp::Logger> logger)
{
parent_node_logger_ptr_ = logger;
}

void ContinentalARS548HwInterface::print_info(std::string info)
{
if (parent_node_logger_ptr_) {
RCLCPP_INFO_STREAM((*parent_node_logger_ptr_), info);
} else {
std::cout << info << std::endl;
}
}

void ContinentalARS548HwInterface::print_error(std::string error)
{
if (parent_node_logger_ptr_) {
RCLCPP_ERROR_STREAM((*parent_node_logger_ptr_), error);
} else {
std::cerr << error << std::endl;
}
}

void ContinentalARS548HwInterface::print_debug(std::string debug)
{
if (parent_node_logger_ptr_) {
RCLCPP_DEBUG_STREAM((*parent_node_logger_ptr_), debug);
} else {
std::cout << debug << std::endl;
}
}

} // namespace nebula::drivers::continental_ars548
Loading
Loading