Skip to content

Commit

Permalink
Fix linter errors.
Browse files Browse the repository at this point in the history
  • Loading branch information
JWhitleyWork committed May 28, 2023
1 parent 373ff3c commit 571758d
Show file tree
Hide file tree
Showing 22 changed files with 79 additions and 69 deletions.
8 changes: 4 additions & 4 deletions velodyne_driver/include/velodyne_driver/driver.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,14 +33,14 @@
#ifndef VELODYNE_DRIVER__DRIVER_HPP_
#define VELODYNE_DRIVER__DRIVER_HPP_

#include <diagnostic_updater/diagnostic_updater.hpp>
#include <diagnostic_updater/publisher.hpp>
#include <rclcpp/rclcpp.hpp>

#include <future>
#include <memory>
#include <string>

#include <diagnostic_updater/diagnostic_updater.hpp>
#include <diagnostic_updater/publisher.hpp>
#include <rclcpp/rclcpp.hpp>

#include "velodyne_driver/input.hpp"

namespace velodyne_driver
Expand Down
7 changes: 3 additions & 4 deletions velodyne_driver/include/velodyne_driver/input.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,16 +54,15 @@
#define VELODYNE_DRIVER__INPUT_HPP_

#include <netinet/in.h>

#include <pcap.h>

#include <memory>
#include <string>

#include <rclcpp/rclcpp.hpp>
#include <velodyne_msgs/msg/velodyne_packet.hpp>
#include <velodyne_msgs/msg/velodyne_scan.hpp>

#include <memory>
#include <string>

namespace velodyne_driver
{

Expand Down
6 changes: 3 additions & 3 deletions velodyne_driver/include/velodyne_driver/time_conversion.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,9 +72,9 @@ rclcpp::Time rosTimeFromGpsTimestamp(rclcpp::Time & time_nom, const uint8_t * co
uint32_t usecs =
static_cast<uint32_t>(
((uint32_t) data[3]) << 24 |
((uint32_t) data[2] ) << 16 |
((uint32_t) data[1] ) << 8 |
((uint32_t) data[0] ));
((uint32_t) data[2]) << 16 |
((uint32_t) data[1]) << 8 |
((uint32_t) data[0]));
uint32_t cur_hour = time_nom.nanoseconds() / 1000000000 / HOUR_TO_SEC;
auto stamp = rclcpp::Time(
(cur_hour * HOUR_TO_SEC) + (usecs / 1000000),
Expand Down
13 changes: 7 additions & 6 deletions velodyne_driver/src/driver/driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,20 +35,21 @@
* ROS driver implementation for the Velodyne 3D LIDARs
*/

#include <rcl_interfaces/msg/floating_point_range.hpp>
#include <rcl_interfaces/msg/parameter_descriptor.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_components/register_node_macro.hpp>
#include "velodyne_driver/driver.hpp"

#include <tf2_ros/transform_listener.h>
#include <velodyne_msgs/msg/velodyne_scan.hpp>

#include <chrono>
#include <cmath>
#include <memory>
#include <string>
#include <utility>

#include "velodyne_driver/driver.hpp"
#include <rcl_interfaces/msg/floating_point_range.hpp>
#include <rcl_interfaces/msg/parameter_descriptor.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_components/register_node_macro.hpp>
#include <velodyne_msgs/msg/velodyne_scan.hpp>

namespace velodyne_driver
{
Expand Down
4 changes: 2 additions & 2 deletions velodyne_driver/src/driver/velodyne_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,10 +35,10 @@
* ROS driver node for the Velodyne 3D LIDARs.
*/

#include <rclcpp/rclcpp.hpp>

#include <memory>

#include <rclcpp/rclcpp.hpp>

#include "velodyne_driver/driver.hpp"

int main(int argc, char ** argv)
Expand Down
7 changes: 4 additions & 3 deletions velodyne_driver/src/lib/input.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@
* PCAP dump
*/

#include <velodyne_msgs/msg/velodyne_packet.hpp>
#include "velodyne_driver/input.hpp"

#include <arpa/inet.h>
#include <fcntl.h>
Expand All @@ -59,7 +59,8 @@
#include <sstream>
#include <string>

#include "velodyne_driver/input.hpp"
#include <velodyne_msgs/msg/velodyne_packet.hpp>

#include "velodyne_driver/time_conversion.hpp"

namespace velodyne_driver
Expand Down Expand Up @@ -225,7 +226,7 @@ int InputSocket::getPacket(velodyne_msgs::msg::VelodynePacket * pkt, const doubl
RCLCPP_ERROR(private_nh_->get_logger(), "recvfail: %s", ::strerror(errno));
return -1;
}
} else if ((size_t) nbytes == packet_size) {
} else if (static_cast<size_t>(nbytes) == packet_size) {
// read successful,
// if packet is not from the lidar scanner we selected by IP,
// continue otherwise we are done
Expand Down
3 changes: 2 additions & 1 deletion velodyne_driver/tests/timeconversiontest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,11 +31,12 @@
// POSSIBILITY OF SUCH DAMAGE.

#include <gtest/gtest.h>
#include <rclcpp/rclcpp.hpp>

#include <cmath>
#include <memory>

#include <rclcpp/rclcpp.hpp>

#include "velodyne_driver/time_conversion.hpp"

TEST(TimeConversion, BytesToTimestamp)
Expand Down
4 changes: 2 additions & 2 deletions velodyne_laserscan/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,10 +30,10 @@
// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.

#include <rclcpp/rclcpp.hpp>

#include <memory>

#include <rclcpp/rclcpp.hpp>

#include "velodyne_laserscan/velodyne_laserscan.hpp"

int main(int argc, char ** argv)
Expand Down
10 changes: 5 additions & 5 deletions velodyne_laserscan/src/velodyne_laserscan.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,11 @@

#include "velodyne_laserscan/velodyne_laserscan.hpp"

#include <cmath>
#include <functional>
#include <memory>
#include <utility>

#include <rcl_interfaces/msg/floating_point_range.hpp>
#include <rcl_interfaces/msg/integer_range.hpp>
#include <rcl_interfaces/msg/parameter_descriptor.hpp>
Expand All @@ -42,11 +47,6 @@
#include <sensor_msgs/msg/point_field.hpp>
#include <sensor_msgs/point_cloud2_iterator.hpp>

#include <cmath>
#include <functional>
#include <memory>
#include <utility>

namespace velodyne_laserscan
{

Expand Down
12 changes: 6 additions & 6 deletions velodyne_laserscan/tests/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,7 @@ void publishXYZIR1(const PointCloud & cloud)
msg.fields[4].offset = 20;
msg.fields[4].datatype = sensor_msgs::PointField::UINT16;
msg.fields[4].count = 1;
msg.data.resize(std::max((size_t)1, cloud.points.size()) * POINT_STEP, 0x00);
msg.data.resize(std::max(static_cast<size_t>(1), cloud.points.size()) * POINT_STEP, 0x00);
msg.point_step = POINT_STEP;
msg.row_step = msg.data.size();
msg.height = 1;
Expand Down Expand Up @@ -172,7 +172,7 @@ void publishXYZIR2(const PointCloud & cloud)
msg.fields[4].offset = 16;
msg.fields[4].datatype = sensor_msgs::PointField::UINT16;
msg.fields[4].count = 1;
msg.data.resize(std::max((size_t)1, cloud.points.size()) * POINT_STEP, 0x00);
msg.data.resize(std::max(static_cast<size_t>(1), cloud.points.size()) * POINT_STEP, 0x00);
msg.point_step = POINT_STEP;
msg.row_step = msg.data.size();
msg.height = 1;
Expand Down Expand Up @@ -217,7 +217,7 @@ void publishXYZR(const PointCloud & cloud)
msg.fields[3].offset = 12;
msg.fields[3].datatype = sensor_msgs::PointField::UINT16;
msg.fields[3].count = 1;
msg.data.resize(std::max((size_t)1, cloud.points.size()) * POINT_STEP, 0x00);
msg.data.resize(std::max(static_cast<size_t>(1), cloud.points.size()) * POINT_STEP, 0x00);
msg.point_step = POINT_STEP;
msg.row_step = msg.data.size();
msg.height = 1;
Expand Down Expand Up @@ -248,7 +248,7 @@ void publishR(const PointCloud & cloud)
msg.fields[0].offset = 0;
msg.fields[0].datatype = sensor_msgs::PointField::UINT16;
msg.fields[0].count = 1;
msg.data.resize(std::max((size_t)1, cloud.points.size()) * POINT_STEP, 0x00);
msg.data.resize(std::max(static_cast<size_t>(1), cloud.points.size()) * POINT_STEP, 0x00);
msg.point_step = POINT_STEP;
msg.row_step = msg.data.size();
msg.height = 1;
Expand Down Expand Up @@ -287,7 +287,7 @@ void publishXYZR32(const PointCloud & cloud)
msg.fields[3].offset = 12;
msg.fields[3].datatype = sensor_msgs::PointField::UINT32;
msg.fields[3].count = 1;
msg.data.resize(std::max((size_t)1, cloud.points.size()) * POINT_STEP, 0x00);
msg.data.resize(std::max(static_cast<size_t>(1), cloud.points.size()) * POINT_STEP, 0x00);
msg.point_step = POINT_STEP;
msg.row_step = msg.data.size();
msg.height = 1;
Expand Down Expand Up @@ -326,7 +326,7 @@ void publishXYZ(const PointCloud & cloud)
msg.fields[2].offset = 8;
msg.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
msg.fields[2].count = 1;
msg.data.resize(std::max((size_t)1, cloud.points.size()) * POINT_STEP, 0x00);
msg.data.resize(std::max(static_cast<size_t>(1), cloud.points.size()) * POINT_STEP, 0x00);
msg.point_step = POINT_STEP;
msg.row_step = msg.data.size();
msg.height = 1;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,17 +33,12 @@
#ifndef VELODYNE_POINTCLOUD__DATACONTAINERBASE_HPP_
#define VELODYNE_POINTCLOUD__DATACONTAINERBASE_HPP_

#include <rclcpp/time.hpp>
#include <geometry_msgs/msg/transform_stamped.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <sensor_msgs/point_cloud2_iterator.hpp>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2/LinearMath/Vector3.h>
#include <tf2/buffer_core.h>
#include <tf2/exceptions.h>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>
#include <velodyne_msgs/msg/velodyne_scan.hpp>

#include <Eigen/Core>
#include <Eigen/Geometry>
Expand All @@ -53,6 +48,13 @@
#include <memory>
#include <string>

#include <rclcpp/time.hpp>
#include <geometry_msgs/msg/transform_stamped.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <sensor_msgs/point_cloud2_iterator.hpp>

#include <velodyne_msgs/msg/velodyne_scan.hpp>

namespace velodyne_rawdata
{
class DataContainerBase
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,13 +33,14 @@
#ifndef VELODYNE_POINTCLOUD__ORGANIZED_CLOUDXYZIRT_HPP_
#define VELODYNE_POINTCLOUD__ORGANIZED_CLOUDXYZIRT_HPP_

#include <sensor_msgs/point_cloud2_iterator.hpp>
#include <tf2/buffer_core.h>
#include <velodyne_msgs/msg/velodyne_scan.hpp>

#include <memory>
#include <string>

#include <sensor_msgs/point_cloud2_iterator.hpp>
#include <velodyne_msgs/msg/velodyne_scan.hpp>

#include "velodyne_pointcloud/datacontainerbase.hpp"

namespace velodyne_pointcloud
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,13 +33,14 @@
#ifndef VELODYNE_POINTCLOUD__POINTCLOUDXYZIRT_HPP_
#define VELODYNE_POINTCLOUD__POINTCLOUDXYZIRT_HPP_

#include <sensor_msgs/point_cloud2_iterator.hpp>
#include <tf2/buffer_core.h>
#include <velodyne_msgs/msg/velodyne_scan.hpp>

#include <memory>
#include <string>

#include <sensor_msgs/point_cloud2_iterator.hpp>
#include <velodyne_msgs/msg/velodyne_scan.hpp>

#include "velodyne_pointcloud/datacontainerbase.hpp"

namespace velodyne_pointcloud
Expand Down
6 changes: 3 additions & 3 deletions velodyne_pointcloud/include/velodyne_pointcloud/rawdata.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,13 +35,13 @@

#include <pcl/point_cloud.h>

#include <rclcpp/rclcpp.hpp>
#include <velodyne_msgs/msg/velodyne_packet.hpp>

#include <memory>
#include <string>
#include <vector>

#include <rclcpp/rclcpp.hpp>
#include <velodyne_msgs/msg/velodyne_packet.hpp>

#include "velodyne_pointcloud/calibration.hpp"
#include "velodyne_pointcloud/datacontainerbase.hpp"

Expand Down
11 changes: 6 additions & 5 deletions velodyne_pointcloud/include/velodyne_pointcloud/transform.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,19 +33,20 @@
#ifndef VELODYNE_POINTCLOUD__TRANSFORM_HPP_
#define VELODYNE_POINTCLOUD__TRANSFORM_HPP_

#include <diagnostic_updater/diagnostic_updater.hpp>
#include <diagnostic_updater/publisher.hpp>
#include <message_filters/subscriber.h>
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <tf2_ros/buffer.h>
#include <tf2_ros/message_filter.h>
#include <tf2_ros/transform_listener.h>
#include <velodyne_msgs/msg/velodyne_scan.hpp>

#include <memory>
#include <string>

#include <diagnostic_updater/diagnostic_updater.hpp>
#include <diagnostic_updater/publisher.hpp>
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <velodyne_msgs/msg/velodyne_scan.hpp>

#include "velodyne_pointcloud/pointcloudXYZIRT.hpp"
#include "velodyne_pointcloud/rawdata.hpp"

Expand Down
9 changes: 5 additions & 4 deletions velodyne_pointcloud/src/conversions/transform.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,10 +32,6 @@

#include "velodyne_pointcloud/transform.hpp"

#include <rcl_interfaces/msg/floating_point_range.hpp>
#include <rcl_interfaces/msg/parameter_descriptor.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_components/register_node_macro.hpp>
#include <tf2_ros/message_filter.h>
#include <tf2_ros/transform_listener.h>

Expand All @@ -44,6 +40,11 @@
#include <memory>
#include <string>

#include <rcl_interfaces/msg/floating_point_range.hpp>
#include <rcl_interfaces/msg/parameter_descriptor.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_components/register_node_macro.hpp>

#include "velodyne_pointcloud/organized_cloudXYZIRT.hpp"
#include "velodyne_pointcloud/pointcloudXYZIRT.hpp"
#include "velodyne_pointcloud/rawdata.hpp"
Expand Down
4 changes: 2 additions & 2 deletions velodyne_pointcloud/src/conversions/transform_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,10 +30,10 @@
// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.

#include <rclcpp/rclcpp.hpp>

#include <memory>

#include <rclcpp/rclcpp.hpp>

#include "velodyne_pointcloud/transform.hpp"

/** Main node entry point. */
Expand Down
4 changes: 2 additions & 2 deletions velodyne_pointcloud/src/lib/calibration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,6 @@

#include <yaml-cpp/yaml.h>

#include <rclcpp/rclcpp.hpp>

#include <cmath>
#include <fstream>
#include <iostream>
Expand All @@ -42,6 +40,8 @@
#include <string>
#include <utility>

#include <rclcpp/rclcpp.hpp>

#include "velodyne_pointcloud/calibration.hpp"

#ifdef HAVE_NEW_YAMLCPP
Expand Down
Loading

0 comments on commit 571758d

Please sign in to comment.