Skip to content

Commit

Permalink
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Revert unrelated formatting changes
Browse files Browse the repository at this point in the history
mojomex authored Nov 16, 2023
1 parent c136757 commit 602add0
Showing 3 changed files with 6 additions and 16 deletions.
4 changes: 0 additions & 4 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -29,7 +29,3 @@ site/

# qcreator stuff
CMakeLists.txt.user

# dependencies from .repos
transport_drivers/
heaphook/
Original file line number Diff line number Diff line change
@@ -29,8 +29,8 @@ class AngleCorrectorCorrectionBased : public AngleCorrector
{
// Assumes that:
// * none of the startFrames are defined as > 360 deg (< 0 not possible since they are unsigned)
// * the fields are arranged in ascending order (e.g. field 1: 20-140deg, field 2: 140-260deg
// etc.) These assumptions hold for AT128E2X.
// * the fields are arranged in ascending order (e.g. field 1: 20-140deg, field 2: 140-260deg etc.)
// These assumptions hold for AT128E2X.
int field = sensor_correction_->frameNumber - 1;
for (size_t i = 0; i < sensor_correction_->frameNumber; ++i) {
if (azimuth < sensor_correction_->startFrame[i]) return field;
14 changes: 4 additions & 10 deletions nebula_ros/src/hesai/hesai_hw_interface_ros_wrapper.cpp
Original file line number Diff line number Diff line change
@@ -147,8 +147,7 @@ HesaiHwInterfaceRosWrapper::HesaiHwInterfaceRosWrapper(const rclcpp::NodeOptions
StreamStart();
}

HesaiHwInterfaceRosWrapper::~HesaiHwInterfaceRosWrapper()
{
HesaiHwInterfaceRosWrapper::~HesaiHwInterfaceRosWrapper() {
RCLCPP_INFO_STREAM(get_logger(), "Closing TcpDriver");
hw_interface_.FinalizeTcpDriver();
}
@@ -161,14 +160,8 @@ Status HesaiHwInterfaceRosWrapper::StreamStart()
return interface_status_;
}

Status HesaiHwInterfaceRosWrapper::StreamStop()
{
return Status::OK;
}
Status HesaiHwInterfaceRosWrapper::Shutdown()
{
return Status::OK;
}
Status HesaiHwInterfaceRosWrapper::StreamStop() { return Status::OK; }
Status HesaiHwInterfaceRosWrapper::Shutdown() { return Status::OK; }

Status HesaiHwInterfaceRosWrapper::InitializeHwInterface( // todo: don't think this is needed
const drivers::SensorConfigurationBase & sensor_configuration)
@@ -268,6 +261,7 @@ Status HesaiHwInterfaceRosWrapper::GetParameters(
this->declare_parameter<uint16_t>("packet_mtu_size", 1500, descriptor);
sensor_configuration.packet_mtu_size = this->get_parameter("packet_mtu_size").as_int();
}

{
rcl_interfaces::msg::ParameterDescriptor descriptor;
descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;

0 comments on commit 602add0

Please sign in to comment.