Skip to content

Commit

Permalink
chore(hesai): fix clang-tidy errors
Browse files Browse the repository at this point in the history
  • Loading branch information
mojomex committed Jun 28, 2024
1 parent 6b865ef commit 3a37151
Show file tree
Hide file tree
Showing 4 changed files with 34 additions and 16 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -218,7 +218,7 @@ struct HesaiInventory
return os;
}

std::string get_str_model()
std::string get_str_model() const
{
switch (model) {
case 0:
Expand Down Expand Up @@ -400,7 +400,7 @@ struct HesaiLidarStatus
return os;
}

std::string get_str_gps_pps_lock()
[[nodiscard]] std::string get_str_gps_pps_lock() const
{
switch (gps_pps_lock) {
case 1:
Expand All @@ -411,7 +411,7 @@ struct HesaiLidarStatus
return "Unknown";
}
}
std::string get_str_gps_gprmc_status()
[[nodiscard]] std::string get_str_gps_gprmc_status() const
{
switch (gps_gprmc_status) {
case 1:
Expand All @@ -422,7 +422,7 @@ struct HesaiLidarStatus
return "Unknown";
}
}
std::string get_str_ptp_clock_status()
[[nodiscard]] std::string get_str_ptp_clock_status() const
{
switch (ptp_clock_status) {
case 0:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -122,10 +122,10 @@ class HesaiHwInterface
uint8_t error_flags = 0;
uint8_t ptc_error_code = 0;

bool ok() { return !error_flags && !ptc_error_code; }
[[nodiscard]] bool ok() const { return !error_flags && !ptc_error_code; }
};

typedef nebula::util::expected<std::vector<uint8_t>, ptc_error_t> ptc_cmd_result_t;
using ptc_cmd_result_t = nebula::util::expected<std::vector<uint8_t>, ptc_error_t>;

std::unique_ptr<::drivers::common::IoContext> cloud_io_context_;
std::shared_ptr<boost::asio::io_context> m_owned_ctx;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,9 +11,7 @@

#include <boost/asio.hpp>

namespace nebula
{
namespace drivers
namespace nebula::drivers
{
HesaiHwInterface::HesaiHwInterface()
: cloud_io_context_{new ::drivers::common::IoContext(1)},
Expand Down Expand Up @@ -1266,16 +1264,16 @@ std::string HesaiHwInterface::PrettyPrintPTCError(ptc_error_t error_code)
std::vector<std::string> nebula_errors;

if (error_flags & TCP_ERROR_INCOMPLETE_RESPONSE) {
nebula_errors.push_back("Incomplete response payload");
nebula_errors.emplace_back("Incomplete response payload");
}
if (error_flags & TCP_ERROR_TIMEOUT) {
nebula_errors.push_back("Request timeout");
nebula_errors.emplace_back("Request timeout");
}
if (error_flags & TCP_ERROR_UNEXPECTED_PAYLOAD) {
nebula_errors.push_back("Received payload but expected payload length 0");
nebula_errors.emplace_back("Received payload but expected payload length 0");
}
if (error_flags & TCP_ERROR_UNRELATED_RESPONSE) {
nebula_errors.push_back("Received unrelated response");
nebula_errors.emplace_back("Received unrelated response");
}

ss << boost::algorithm::join(nebula_errors, ", ");
Expand All @@ -1297,5 +1295,4 @@ T HesaiHwInterface::CheckSizeAndParse(const std::vector<uint8_t> & data)
return parsed;
}

} // namespace drivers
} // namespace nebula
} // namespace nebula::drivers
23 changes: 22 additions & 1 deletion nebula_ros/src/hesai/hesai_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@ namespace nebula
{
namespace ros
{
using std::get;

HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options)
: rclcpp::Node("hesai_ros_wrapper", rclcpp::NodeOptions(options).use_intra_process_comms(true)),
wrapper_status_(Status::NOT_INITIALIZED),
Expand Down Expand Up @@ -50,6 +52,25 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options)
(std::stringstream() << "No valid calibration found: " << calibration_result.error()).str());
}

if (hw_interface_wrapper_) {
auto cloud_min = sensor_cfg_ptr_->cloud_min_angle / 10.f;
auto cloud_max = sensor_cfg_ptr_->cloud_max_angle / 10.f;

auto padding = calibration_result.value()->getFovPadding();
cloud_min += get<0>(padding);
cloud_max += get<1>(padding);

if (cloud_min < 0) {
cloud_min += 360;
}

if (cloud_max > 360) {
cloud_max -= 360;
}

hw_interface_wrapper_->HwInterface()->setHardwareFov(cloud_min, cloud_max);
}

decoder_wrapper_.emplace(this, sensor_cfg_ptr_, calibration_result.value());

RCLCPP_DEBUG(get_logger(), "Starting stream");
Expand Down Expand Up @@ -394,7 +415,7 @@ HesaiRosWrapper::get_calibration_result_t HesaiRosWrapper::GetCalibrationData(
}

// If a sensor is connected, try to download and save its calibration data
if (!ignore_others && launch_hw_) {
if (!ignore_others && hw_interface_wrapper_) {
try {
auto raw_data = hw_interface_wrapper_->HwInterface()->GetLidarCalibrationBytes();
RCLCPP_INFO(logger, "Downloaded calibration data from sensor.");
Expand Down

0 comments on commit 3a37151

Please sign in to comment.