Skip to content

Commit

Permalink
seyond(refactor): run pre-commit on files
Browse files Browse the repository at this point in the history
Signed-off-by: David Wong <[email protected]>
  • Loading branch information
drwnz committed May 24, 2024
1 parent b8dcea8 commit e198f0e
Show file tree
Hide file tree
Showing 15 changed files with 173 additions and 205 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@ namespace seyond_packet

struct PacketFalcon : public PacketBase<8, 32, 2, 100>
{

};

#pragma pack(pop)
Expand All @@ -24,9 +23,7 @@ struct PacketFalcon : public PacketBase<8, 32, 2, 100>

class Falcon : public SeyondSensor<seyond_packet::PacketFalcon>
{


};

} // namespace drivers
} // namespace nebula
} // namespace nebula
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@ namespace seyond_packet

struct PacketRobinW : public PacketBase<8, 32, 2, 100>
{

};

#pragma pack(pop)
Expand All @@ -24,9 +23,7 @@ struct PacketRobinW : public PacketBase<8, 32, 2, 100>

class RobinW : public SeyondSensor<seyond_packet::PacketRobinW>
{


};

} // namespace drivers
} // namespace nebula
} // namespace nebula
10 changes: 4 additions & 6 deletions nebula_decoders/include/nebula_decoders/nebula_decoders_seyond/decoders/seyond_decoder.hpp
100755 → 100644
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ class SeyondDecoder : public SeyondScanDecoder
/// @brief The last decoded packet
typename SensorT::packet_t packet_;
/// @brief The last azimuth processed
int last_phase_ = -1; // Dummy value to signal last_phase_ has not been set yet
int last_phase_ = -1; // Dummy value to signal last_phase_ has not been set yet
/// @brief The timestamp of the last completed scan in nanoseconds
uint64_t output_scan_timestamp_ns_ = 0;
/// @brief The timestamp of the scan currently in progress
Expand Down Expand Up @@ -78,7 +78,8 @@ class SeyondDecoder : public SeyondScanDecoder
/// @param correction_data Calibration data for this decoder
explicit SeyondDecoder(
const std::shared_ptr<const SeyondSensorConfiguration> & sensor_configuration,
const std::shared_ptr<const typename SensorT::angle_corrector_t::correction_data_t> & correction_data)
const std::shared_ptr<const typename SensorT::angle_corrector_t::correction_data_t> &
correction_data)
: sensor_configuration_(sensor_configuration),
angle_corrector_(correction_data),
logger_(rclcpp::get_logger("SeyondDecoder"))
Expand All @@ -93,10 +94,7 @@ class SeyondDecoder : public SeyondScanDecoder
output_pc_->reserve(SensorT::MAX_SCAN_BUFFER_POINTS);
}

int unpack(const std::vector<uint8_t> & packet) override
{
return -1;
}
int unpack(const std::vector<uint8_t> & packet) override { return -1; }

bool hasScanned() override { return has_scanned_; }

Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
#ifndef NEBULA_WS_HESAI_SCAN_DECODER_HPP
#define NEBULA_WS_HESAI_SCAN_DECODER_HPP

#include "nebula_common/seyond/seyond_common.hpp"
#include "nebula_common/point_types.hpp"
#include "nebula_common/seyond/seyond_common.hpp"

#include "nebula_msgs/msg/nebula_packet.hpp"
#include "nebula_msgs/msg/nebula_packets.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@ template <typename PacketT>
class SeyondSensor
{
private:

public:
typedef PacketT packet_t;

Expand All @@ -25,4 +24,4 @@ class SeyondSensor
};

} // namespace drivers
} // namespace nebula
} // namespace nebula
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,8 @@ class SeyondHwInterface
/// @brief Printing calibration configuration
/// @param calibration_configuration CalibrationConfiguration for the checking
/// @return Resulting status
Status GetCalibrationConfiguration(const CalibrationConfigurationBase & calibration_configuration);
Status GetCalibrationConfiguration(
const CalibrationConfigurationBase & calibration_configuration);

/// @brief Setting sensor configuration
/// @param sensor_configuration SensorConfiguration for this interface
Expand All @@ -101,13 +102,11 @@ class SeyondHwInterface
/// @brief Registering callback for NebulaPackets
/// @param scan_callback Callback function
/// @return Resulting status
Status RegisterScanCallback(
std::function<void(std::vector<uint8_t> &)> scan_callback);
Status RegisterScanCallback(std::function<void(std::vector<uint8_t> &)> scan_callback);

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

};
} // namespace drivers
} // namespace nebula
Expand Down
7 changes: 2 additions & 5 deletions nebula_hw_interfaces/src/nebula_seyond_hw_interfaces/seyond_hw_interface.cpp
100755 → 100644
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,6 @@ SeyondHwInterface::SeyondHwInterface()

void SeyondHwInterface::ReceiveSensorPacketCallback(std::vector<uint8_t> & buffer)
{

}

Status SeyondHwInterface::SensorInterfaceStart()
Expand All @@ -31,7 +30,8 @@ Status SeyondHwInterface::SetSensorConfiguration(
return Status::OK;
}

Status SeyondHwInterface::GetSensorConfiguration(const SensorConfigurationBase & sensor_configuration)
Status SeyondHwInterface::GetSensorConfiguration(
const SensorConfigurationBase & sensor_configuration)
{
return Status::ERROR_1;
}
Expand All @@ -55,17 +55,14 @@ void SeyondHwInterface::SetTargetModel(int model)

void SeyondHwInterface::PrintError(std::string error)
{

}

void SeyondHwInterface::PrintDebug(std::string debug)
{

}

void SeyondHwInterface::PrintInfo(std::string info)
{

}

void SeyondHwInterface::SetLogger(std::shared_ptr<rclcpp::Logger> logger)
Expand Down
3 changes: 1 addition & 2 deletions nebula_ros/include/nebula_ros/seyond/decoder_wrapper.hpp
100755 → 100644
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,6 @@ class SeyondDecoderWrapper
nebula::Status Status();

private:

void PublishCloud(
std::unique_ptr<sensor_msgs::msg::PointCloud2> pointcloud,
const rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr & publisher);
Expand All @@ -69,4 +68,4 @@ class SeyondDecoderWrapper
std::shared_ptr<WatchdogTimer> cloud_watchdog_;
};
} // namespace ros
} // namespace nebula
} // namespace nebula
Original file line number Diff line number Diff line change
Expand Up @@ -34,4 +34,4 @@ class SeyondHwInterfaceWrapper
bool setup_sensor_;
};
} // namespace ros
} // namespace nebula
} // namespace nebula
11 changes: 5 additions & 6 deletions nebula_ros/include/nebula_ros/seyond/hw_monitor_wrapper.hpp
100755 → 100644
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@

#include <diagnostic_updater/diagnostic_updater.hpp>
#include <nebula_common/seyond/seyond_common.hpp>

#include <nebula_hw_interfaces/nebula_hw_interfaces_seyond/seyond_hw_interface.hpp>
#include <rclcpp/rclcpp.hpp>

Expand All @@ -26,9 +25,9 @@ using SeyondSensorConfiguration = nebula::drivers::SeyondSensorConfiguration;
class SeyondHwMonitorWrapper
{
public:
SeyondHwMonitorWrapper(rclcpp::Node* const parent_node,
const std::shared_ptr<SeyondHwInterface>& hw_interface,
std::shared_ptr<const SeyondSensorConfiguration>& config);
SeyondHwMonitorWrapper(
rclcpp::Node * const parent_node, const std::shared_ptr<SeyondHwInterface> & hw_interface,
std::shared_ptr<const SeyondSensorConfiguration> & config);

void OnConfigChange(const std::shared_ptr<const SeyondSensorConfiguration> & /* new_config */) {}

Expand All @@ -46,7 +45,7 @@ class SeyondHwMonitorWrapper
/// @brief Get and store diagnostic info from sensor
void FetchDiagnosticInfo();

rclcpp::Node* const parent_node_;
rclcpp::Node * const parent_node_;
rclcpp::Logger logger_;
nebula::Status status_;
uint16_t diag_span_;
Expand All @@ -62,4 +61,4 @@ class SeyondHwMonitorWrapper
std::mutex mtx_current_diag_info_;
};
} // namespace ros
} // namespace nebula
} // namespace nebula
4 changes: 1 addition & 3 deletions nebula_ros/include/nebula_ros/seyond/seyond_ros_wrapper.hpp
100755 → 100644
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,6 @@ using SeyondCalibrationConfiguration = nebula::drivers::SeyondCalibrationConfigu

class SeyondRosWrapper final : public rclcpp::Node
{

public:
explicit SeyondRosWrapper(const rclcpp::NodeOptions & options);
~SeyondRosWrapper() noexcept {};
Expand All @@ -56,8 +55,7 @@ class SeyondRosWrapper final : public rclcpp::Node
rcl_interfaces::msg::SetParametersResult OnParameterChange(
const std::vector<rclcpp::Parameter> & p);

Status ValidateAndSetConfig(
std::shared_ptr<const SeyondSensorConfiguration> & new_config);
Status ValidateAndSetConfig(std::shared_ptr<const SeyondSensorConfiguration> & new_config);

Status wrapper_status_;

Expand Down
86 changes: 42 additions & 44 deletions nebula_ros/src/seyond/decoder_wrapper.cpp
100755 → 100644
Original file line number Diff line number Diff line change
Expand Up @@ -7,16 +7,15 @@ namespace ros

using namespace std::chrono_literals;

SeyondDecoderWrapper::SeyondDecoderWrapper(rclcpp::Node* const parent_node,
const std::shared_ptr<SeyondHwInterface>& hw_interface,
std::shared_ptr<const SeyondSensorConfiguration>& config)
: status_(nebula::Status::NOT_INITIALIZED)
, logger_(parent_node->get_logger().get_child("SeyondDecoder"))
, hw_interface_(hw_interface)
, sensor_cfg_(config)
SeyondDecoderWrapper::SeyondDecoderWrapper(
rclcpp::Node * const parent_node, const std::shared_ptr<SeyondHwInterface> & hw_interface,
std::shared_ptr<const SeyondSensorConfiguration> & config)
: status_(nebula::Status::NOT_INITIALIZED),
logger_(parent_node->get_logger().get_child("SeyondDecoder")),
hw_interface_(hw_interface),
sensor_cfg_(config)
{
if (!config)
{
if (!config) {
throw std::runtime_error("SeyondDecoderWrapper cannot be instantiated without a valid config!");
}

Expand All @@ -25,54 +24,56 @@ SeyondDecoderWrapper::SeyondDecoderWrapper(rclcpp::Node* const parent_node,
driver_ptr_ = std::make_shared<SeyondDriver>(config, calibration_cfg_ptr_);
status_ = driver_ptr_->GetStatus();

if (Status::OK != status_)
{
throw std::runtime_error((std::stringstream() << "Error instantiating decoder: " << status_).str());
if (Status::OK != status_) {
throw std::runtime_error(
(std::stringstream() << "Error instantiating decoder: " << status_).str());
}

// Publish packets only if HW interface is connected
if (hw_interface_)
{
if (hw_interface_) {
current_scan_msg_ = std::make_unique<nebula_msgs::msg::NebulaPackets>();
packets_pub_ =
parent_node->create_publisher<nebula_msgs::msg::NebulaPackets>("nebula_packets", rclcpp::SensorDataQoS());
packets_pub_ = parent_node->create_publisher<nebula_msgs::msg::NebulaPackets>(
"nebula_packets", rclcpp::SensorDataQoS());
}

auto qos_profile = rmw_qos_profile_sensor_data;
auto pointcloud_qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile);
auto pointcloud_qos =
rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile);

nebula_points_pub_ = parent_node->create_publisher<sensor_msgs::msg::PointCloud2>("nebula_points", pointcloud_qos);
nebula_points_pub_ =
parent_node->create_publisher<sensor_msgs::msg::PointCloud2>("nebula_points", pointcloud_qos);

RCLCPP_INFO_STREAM(logger_, ". Wrapper=" << status_);

cloud_watchdog_ = std::make_shared<WatchdogTimer>(*parent_node, 100'000us, [this, parent_node](bool ok) {
if (ok)
return;
RCLCPP_WARN_THROTTLE(logger_, *parent_node->get_clock(), 5000, "Missed pointcloud output deadline");
});
cloud_watchdog_ =
std::make_shared<WatchdogTimer>(*parent_node, 100'000us, [this, parent_node](bool ok) {
if (ok) return;
RCLCPP_WARN_THROTTLE(
logger_, *parent_node->get_clock(), 5000, "Missed pointcloud output deadline");
});
}

void SeyondDecoderWrapper::OnConfigChange(
const std::shared_ptr<const SeyondSensorConfiguration>& new_config)
const std::shared_ptr<const SeyondSensorConfiguration> & new_config)
{
std::lock_guard lock(mtx_driver_ptr_);
auto new_driver = std::make_shared<SeyondDriver>(new_config, calibration_cfg_ptr_);
driver_ptr_ = new_driver;
sensor_cfg_ = new_config;
}

void SeyondDecoderWrapper::ProcessCloudPacket(std::unique_ptr<nebula_msgs::msg::NebulaPacket> packet_msg)
void SeyondDecoderWrapper::ProcessCloudPacket(
std::unique_ptr<nebula_msgs::msg::NebulaPacket> packet_msg)
{
// ////////////////////////////////////////
// Accumulate packets for recording
// ////////////////////////////////////////

// Accumulate packets for recording only if someone is subscribed to the topic (for performance)
if (hw_interface_ &&
(packets_pub_->get_subscription_count() > 0 || packets_pub_->get_intra_process_subscription_count() > 0))
{
if (current_scan_msg_->packets.size() == 0)
{
if (
hw_interface_ && (packets_pub_->get_subscription_count() > 0 ||
packets_pub_->get_intra_process_subscription_count() > 0)) {
if (current_scan_msg_->packets.size() == 0) {
current_scan_msg_->header.stamp = packet_msg->stamp;
}

Expand All @@ -91,8 +92,7 @@ void SeyondDecoderWrapper::ProcessCloudPacket(std::unique_ptr<nebula_msgs::msg::
pointcloud = std::get<0>(pointcloud_ts);
}

if (pointcloud == nullptr)
{
if (pointcloud == nullptr) {
return;
};

Expand All @@ -104,15 +104,14 @@ void SeyondDecoderWrapper::ProcessCloudPacket(std::unique_ptr<nebula_msgs::msg::
cloud_watchdog_->update();

// Publish scan message only if it has been written to
if (current_scan_msg_ && !current_scan_msg_->packets.empty())
{
if (current_scan_msg_ && !current_scan_msg_->packets.empty()) {
packets_pub_->publish(std::move(current_scan_msg_));
current_scan_msg_ = std::make_unique<nebula_msgs::msg::NebulaPackets>();
}

if (nebula_points_pub_->get_subscription_count() > 0 ||
nebula_points_pub_->get_intra_process_subscription_count() > 0)
{
if (
nebula_points_pub_->get_subscription_count() > 0 ||
nebula_points_pub_->get_intra_process_subscription_count() > 0) {
auto ros_pc_msg_ptr = std::make_unique<sensor_msgs::msg::PointCloud2>();
pcl::toROSMsg(*pointcloud, *ros_pc_msg_ptr);
auto nanoseconds = std::chrono::duration_cast<std::chrono::nanoseconds>(
Expand All @@ -123,11 +122,11 @@ void SeyondDecoderWrapper::ProcessCloudPacket(std::unique_ptr<nebula_msgs::msg::
}
}

void SeyondDecoderWrapper::PublishCloud(std::unique_ptr<sensor_msgs::msg::PointCloud2> pointcloud,
const rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr& publisher)
void SeyondDecoderWrapper::PublishCloud(
std::unique_ptr<sensor_msgs::msg::PointCloud2> pointcloud,
const rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr & publisher)
{
if (pointcloud->header.stamp.sec < 0)
{
if (pointcloud->header.stamp.sec < 0) {
RCLCPP_WARN_STREAM(logger_, "Timestamp error, verify clock source.");
}
pointcloud->header.frame_id = sensor_cfg_->frame_id;
Expand All @@ -138,12 +137,11 @@ nebula::Status SeyondDecoderWrapper::Status()
{
std::lock_guard lock(mtx_driver_ptr_);

if (!driver_ptr_)
{
if (!driver_ptr_) {
return nebula::Status::NOT_INITIALIZED;
}

return driver_ptr_->GetStatus();
}
} // namespace ros
} // namespace nebula
} // namespace nebula
Loading

0 comments on commit e198f0e

Please sign in to comment.