Skip to content

Commit

Permalink
A few more minor style updates. (#308)
Browse files Browse the repository at this point in the history
- Get rid of the last users of new in the codebase
- Get rid of the users of 'using' in the codebase
- Rename 'calibrationFile' -> 'calibration_file'

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>
  • Loading branch information
clalancette committed Nov 7, 2019
1 parent 80777a1 commit d67bbe2
Show file tree
Hide file tree
Showing 5 changed files with 31 additions and 39 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ class Convert final
diagnostic_updater::Updater diagnostics_;
double diag_min_freq_;
double diag_max_freq_;
std::shared_ptr<diagnostic_updater::TopicDiagnostic> diag_topic_;
std::unique_ptr<diagnostic_updater::TopicDiagnostic> diag_topic_;
};
} // namespace velodyne_pointcloud

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ class Transform final
diagnostic_updater::Updater diagnostics_;
double diag_min_freq_;
double diag_max_freq_;
std::shared_ptr<diagnostic_updater::TopicDiagnostic> diag_topic_;
std::unique_ptr<diagnostic_updater::TopicDiagnostic> diag_topic_;
};
} // namespace velodyne_pointcloud

Expand Down
32 changes: 14 additions & 18 deletions velodyne_pointcloud/src/conversions/convert.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ Convert::Convert(const rclcpp::NodeOptions & options)
diagnostics_(this)
{
// get path to angles.config file for this device
std::string calibrationFile = this->declare_parameter("calibration", "");
std::string calibration_file = this->declare_parameter("calibration", "");

rcl_interfaces::msg::ParameterDescriptor min_range_desc;
min_range_desc.name = "min_range";
Expand Down Expand Up @@ -104,20 +104,18 @@ Convert::Convert(const rclcpp::NodeOptions & options)
std::string target_frame = this->declare_parameter("target_frame", "");
std::string fixed_frame = this->declare_parameter("fixed_frame", "");

RCLCPP_INFO(this->get_logger(), "correction angles: %s", calibrationFile.c_str());
RCLCPP_INFO(this->get_logger(), "correction angles: %s", calibration_file.c_str());

data_ = std::make_unique<velodyne_rawdata::RawData>(calibrationFile);
data_ = std::make_unique<velodyne_rawdata::RawData>(calibration_file);

if (organize_cloud) {
container_ptr_ = std::unique_ptr<OrganizedCloudXYZIR>(
new OrganizedCloudXYZIR(
min_range, max_range, target_frame, fixed_frame,
data_->numLasers(), data_->scansPerPacket(), tf_buffer_));
container_ptr_ = std::make_unique<OrganizedCloudXYZIR>(
min_range, max_range, target_frame, fixed_frame,
data_->numLasers(), data_->scansPerPacket(), tf_buffer_);
} else {
container_ptr_ = std::unique_ptr<PointcloudXYZIR>(
new PointcloudXYZIR(
min_range, max_range, target_frame, fixed_frame,
data_->scansPerPacket(), tf_buffer_));
container_ptr_ = std::make_unique<PointcloudXYZIR>(
min_range, max_range, target_frame, fixed_frame,
data_->scansPerPacket(), tf_buffer_);
}

// advertise output point cloud (before subscribing to input data)
Expand All @@ -136,13 +134,11 @@ Convert::Convert(const rclcpp::NodeOptions & options)
// concerned about monitoring the frequency.
diag_min_freq_ = 2.0;
diag_max_freq_ = 20.0;
namespace du = diagnostic_updater;
diag_topic_.reset(
new du::TopicDiagnostic(
"velodyne_points", diagnostics_,
du::FrequencyStatusParam(
&diag_min_freq_, &diag_max_freq_, 0.1, 10),
du::TimeStampStatusParam()));
diag_topic_ = std::make_unique<diagnostic_updater::TopicDiagnostic>(
"velodyne_points", diagnostics_,
diagnostic_updater::FrequencyStatusParam(
&diag_min_freq_, &diag_max_freq_, 0.1, 10),
diagnostic_updater::TimeStampStatusParam());

data_->setParameters(min_range, max_range, view_direction, view_width);
container_ptr_->configure(min_range, max_range, target_frame, fixed_frame);
Expand Down
30 changes: 13 additions & 17 deletions velodyne_pointcloud/src/conversions/transform.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ Transform::Transform(const rclcpp::NodeOptions & options)
velodyne_scan_(this, "velodyne_packets"), tf_buffer_(this->get_clock()),
diagnostics_(this)
{
std::string calibrationFile = this->declare_parameter("calibration", "");
std::string calibration_file = this->declare_parameter("calibration", "");

rcl_interfaces::msg::ParameterDescriptor min_range_desc;
min_range_desc.name = "min_range";
Expand Down Expand Up @@ -102,20 +102,18 @@ Transform::Transform(const rclcpp::NodeOptions & options)
std::string fixed_frame = this->declare_parameter("fixed_frame", "odom");
bool organize_cloud = this->declare_parameter("organize_cloud", true);

RCLCPP_INFO(this->get_logger(), "correction angles: %s", calibrationFile.c_str());
RCLCPP_INFO(this->get_logger(), "correction angles: %s", calibration_file.c_str());

data_ = std::make_unique<velodyne_rawdata::RawData>(calibrationFile);
data_ = std::make_unique<velodyne_rawdata::RawData>(calibration_file);

if (organize_cloud) {
container_ptr_ = std::unique_ptr<OrganizedCloudXYZIR>(
new OrganizedCloudXYZIR(
min_range, max_range, target_frame, fixed_frame, data_->numLasers(),
data_->scansPerPacket(), tf_buffer_));
container_ptr_ = std::make_unique<OrganizedCloudXYZIR>(
min_range, max_range, target_frame, fixed_frame, data_->numLasers(),
data_->scansPerPacket(), tf_buffer_);
} else {
container_ptr_ = std::unique_ptr<PointcloudXYZIR>(
new PointcloudXYZIR(
min_range, max_range, target_frame, fixed_frame,
data_->scansPerPacket(), tf_buffer_));
container_ptr_ = std::make_unique<PointcloudXYZIR>(
min_range, max_range, target_frame, fixed_frame,
data_->scansPerPacket(), tf_buffer_);
}

// advertise output point cloud (before subscribing to input data)
Expand All @@ -135,12 +133,10 @@ Transform::Transform(const rclcpp::NodeOptions & options)
// concerned about monitoring the frequency.
diag_min_freq_ = 2.0;
diag_max_freq_ = 20.0;
namespace du = diagnostic_updater;
diag_topic_.reset(
new du::TopicDiagnostic(
"velodyne_points", diagnostics_, du::FrequencyStatusParam(
&diag_min_freq_, &diag_max_freq_, 0.1, 10),
du::TimeStampStatusParam()));
diag_topic_ = std::make_unique<diagnostic_updater::TopicDiagnostic>(
"velodyne_points", diagnostics_, diagnostic_updater::FrequencyStatusParam(
&diag_min_freq_, &diag_max_freq_, 0.1, 10),
diagnostic_updater::TimeStampStatusParam());

data_->setParameters(min_range, max_range, view_direction, view_width);
container_ptr_->configure(min_range, max_range, target_frame, fixed_frame);
Expand Down
4 changes: 2 additions & 2 deletions velodyne_pointcloud/src/lib/rawdata.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,6 @@ int RawData::numLasers() const
*/
void RawData::unpack(const velodyne_msgs::msg::VelodynePacket & pkt, DataContainerBase & data)
{
using velodyne_pointcloud::LaserCorrection;
// RCLCPP_DEBUG(this->get_logger(), "Received packet, time: %s", pkt.stamp);

/** special parsing for the VLP16 **/
Expand All @@ -142,7 +141,8 @@ void RawData::unpack(const velodyne_msgs::msg::VelodynePacket & pkt, DataContain
float intensity;
const uint8_t laser_number = j + bank_origin;

const LaserCorrection & corrections = calibration_->laser_corrections[laser_number];
const velodyne_pointcloud::LaserCorrection & corrections =
calibration_->laser_corrections[laser_number];

/** Position Calculation */
const raw_block_t & block = raw->blocks[i];
Expand Down

0 comments on commit d67bbe2

Please sign in to comment.