Skip to content

Commit

Permalink
Fixes pointed out by clang-tidy (#310)
Browse files Browse the repository at this point in the history
* Rearrange header includes so clang-tidy is happy.

The ament checkers are also happy with this arrangement.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Get rid of unnecessary void arguments on methods.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Properly mark methods as override where appropriate.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Initialize members and stack variables to zero before use.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Mark function implementations in header files 'inline'.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Use more efficient 'empty' method instead of empty string.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Get rid of unnecessary else statements after a continue/return.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Get rid of unnecessary == false use.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Make sure to add a virtual destructor to DataContainerBase.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Use string != comparison instead of 'compare' method.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Rename PointcloudXYZIR parameter name to match implementation.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Get rid of usage of typedef.

Also use C++-style reinterpret_cast instead of C-style cast.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Be more explicit about using floats.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Do an explicit lround to do int->float conversion.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Fix the intensity calculation.

There are a few problems.  First is that it was doing an
integer divide, which seems like it would be always 0.  Second,
the number that was being used was the raw integer, not the
distance.  Finally, the order of operations meant that it wasn't
actually implementing the algorithm shown in the VLP documentation.
This commit fixes all of those problems.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Remove the azimuth from addPoint.

None of the implementations use it.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Make sure to reset the cloud data to 0 before reusing.

We were seeing artifacts in the organize_cloud case that this removes.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Use underscores on pointcloud member variables.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Using std::lround means we don't need to add 0.5 to the result.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Slightly rearrange and simplify range checks.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Add in example launch files for VLP32C.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>
  • Loading branch information
clalancette authored and Joshua Whitley committed Nov 11, 2019
1 parent d67bbe2 commit 8091dda
Show file tree
Hide file tree
Showing 40 changed files with 722 additions and 145 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ def generate_launch_description():
driver_params = yaml.safe_load(f)['velodyne_driver_node']['ros__parameters']

convert_share_dir = ament_index_python.packages.get_package_share_directory('velodyne_pointcloud')
convert_params_file = os.path.join(convert_share_dir, 'config', 'default-velodyne_convert_node-params.yaml')
convert_params_file = os.path.join(convert_share_dir, 'config', 'VLP16-velodyne_convert_node-params.yaml')
with open(convert_params_file, 'r') as f:
convert_params = yaml.safe_load(f)['velodyne_convert_node']['ros__parameters']
convert_params['calibration'] = os.path.join(convert_share_dir, 'params', 'VLP16db.yaml')
Expand Down
2 changes: 1 addition & 1 deletion velodyne/launch/velodyne-all-nodes-VLP16-launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ def generate_launch_description():
parameters=[driver_params_file])

convert_share_dir = ament_index_python.packages.get_package_share_directory('velodyne_pointcloud')
convert_params_file = os.path.join(convert_share_dir, 'config', 'default-velodyne_convert_node-params.yaml')
convert_params_file = os.path.join(convert_share_dir, 'config', 'VLP16-velodyne_convert_node-params.yaml')
with open(convert_params_file, 'r') as f:
convert_params = yaml.safe_load(f)['velodyne_convert_node']['ros__parameters']
convert_params['calibration'] = os.path.join(convert_share_dir, 'params', 'VLP16db.yaml')
Expand Down
85 changes: 85 additions & 0 deletions velodyne/launch/velodyne-all-nodes-VLP32C-composed-launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,85 @@
# Copyright 2019 Open Source Robotics Foundation, Inc.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
#
# 2. Redistributions in binary form must reproduce the above
# copyright notice, this list of conditions and the following
# disclaimer in the documentation and/or other materials provided
# with the distribution.
#
# 3. Neither the name of the copyright holder nor the names of its
# contributors may be used to endorse or promote products derived
# from this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

"""Launch the velodyne driver, pointcloud, and laserscan nodes in a composable container with default configuration."""

import os
import yaml

import ament_index_python.packages
from launch import LaunchDescription
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode


def generate_launch_description():
driver_share_dir = ament_index_python.packages.get_package_share_directory('velodyne_driver')
driver_params_file = os.path.join(driver_share_dir, 'config', 'VLP32C-velodyne_driver_node-params.yaml')
with open(driver_params_file, 'r') as f:
driver_params = yaml.safe_load(f)['velodyne_driver_node']['ros__parameters']

convert_share_dir = ament_index_python.packages.get_package_share_directory('velodyne_pointcloud')
convert_params_file = os.path.join(convert_share_dir, 'config', 'VLP32C-velodyne_convert_node-params.yaml')
with open(convert_params_file, 'r') as f:
convert_params = yaml.safe_load(f)['velodyne_convert_node']['ros__parameters']
convert_params['calibration'] = os.path.join(convert_share_dir, 'params', 'VeloView-VLP-32C.yaml')

laserscan_share_dir = ament_index_python.packages.get_package_share_directory('velodyne_laserscan')
laserscan_params_file = os.path.join(laserscan_share_dir, 'config', 'default-velodyne_laserscan_node-params.yaml')
with open(laserscan_params_file, 'r') as f:
laserscan_params = yaml.safe_load(f)['velodyne_laserscan_node']['ros__parameters']

container = ComposableNodeContainer(
node_name='velodyne_container',
node_namespace='',
package='rclcpp_components',
node_executable='component_container',
composable_node_descriptions=[
ComposableNode(
package='velodyne_driver',
node_plugin='velodyne_driver::VelodyneDriver',
node_name='velodyne_driver_node',
parameters=[driver_params]),
ComposableNode(
package='velodyne_pointcloud',
node_plugin='velodyne_pointcloud::Convert',
node_name='velodyne_convert_node',
parameters=[convert_params]),
ComposableNode(
package='velodyne_laserscan',
node_plugin='velodyne_laserscan::VelodyneLaserScan',
node_name='velodyne_laserscan_node',
parameters=[laserscan_params]),
],
output='both',
)

return LaunchDescription([container])
78 changes: 78 additions & 0 deletions velodyne/launch/velodyne-all-nodes-VLP32C-launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,78 @@
# Copyright 2019 Open Source Robotics Foundation, Inc.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
#
# 2. Redistributions in binary form must reproduce the above
# copyright notice, this list of conditions and the following
# disclaimer in the documentation and/or other materials provided
# with the distribution.
#
# 3. Neither the name of the copyright holder nor the names of its
# contributors may be used to endorse or promote products derived
# from this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

"""Launch the velodyne driver, pointcloud, and laserscan nodes with default configuration."""

import os
import yaml

import ament_index_python.packages
import launch
import launch_ros.actions


def generate_launch_description():
driver_share_dir = ament_index_python.packages.get_package_share_directory('velodyne_driver')
driver_params_file = os.path.join(driver_share_dir, 'config', 'VLP32C-velodyne_driver_node-params.yaml')
velodyne_driver_node = launch_ros.actions.Node(package='velodyne_driver',
node_executable='velodyne_driver_node',
output='both',
parameters=[driver_params_file])

convert_share_dir = ament_index_python.packages.get_package_share_directory('velodyne_pointcloud')
convert_params_file = os.path.join(convert_share_dir, 'config', 'VLP32C-velodyne_convert_node-params.yaml')
with open(convert_params_file, 'r') as f:
convert_params = yaml.safe_load(f)['velodyne_convert_node']['ros__parameters']
convert_params['calibration'] = os.path.join(convert_share_dir, 'params', 'VeloView-VLP-32C.yaml')
velodyne_convert_node = launch_ros.actions.Node(package='velodyne_pointcloud',
node_executable='velodyne_convert_node',
output='both',
parameters=[convert_params])

laserscan_share_dir = ament_index_python.packages.get_package_share_directory('velodyne_laserscan')
laserscan_params_file = os.path.join(laserscan_share_dir, 'config', 'default-velodyne_laserscan_node-params.yaml')
velodyne_laserscan_node = launch_ros.actions.Node(package='velodyne_laserscan',
node_executable='velodyne_laserscan_node',
output='both',
parameters=[laserscan_params_file])


return launch.LaunchDescription([velodyne_driver_node,
velodyne_convert_node,
velodyne_laserscan_node,

launch.actions.RegisterEventHandler(
event_handler=launch.event_handlers.OnProcessExit(
target_action=velodyne_driver_node,
on_exit=[launch.actions.EmitEvent(
event=launch.events.Shutdown())],
)),
])
13 changes: 13 additions & 0 deletions velodyne_driver/config/VLP32C-velodyne_driver_node-params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
velodyne_driver_node:
ros__parameters:
device_ip: 192.168.1.201
gps_time: false
time_offset: 0.0
enabled: true
read_once: false
read_fast: false
repeat_delay: 0.0
frame_id: velodyne
model: 32C
rpm: 600.0
port: 2368
6 changes: 3 additions & 3 deletions velodyne_driver/include/velodyne_driver/driver.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,9 +33,9 @@
#ifndef VELODYNE_DRIVER__DRIVER_HPP_
#define VELODYNE_DRIVER__DRIVER_HPP_

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

#include <future>
#include <memory>
Expand All @@ -57,9 +57,9 @@ class VelodyneDriver final : public rclcpp::Node
VelodyneDriver & operator=(const VelodyneDriver & c) = delete;

private:
bool poll(void);
bool poll();

void pollThread(void);
void pollThread();

// configuration parameters
struct
Expand Down
15 changes: 7 additions & 8 deletions velodyne_driver/include/velodyne_driver/input.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,11 +53,10 @@
#ifndef VELODYNE_DRIVER__INPUT_HPP_
#define VELODYNE_DRIVER__INPUT_HPP_

#include <unistd.h>
#include <stdio.h>
#include <pcap.h>
#include <netinet/in.h>

#include <pcap.h>

#include <rclcpp/rclcpp.hpp>
#include <velodyne_msgs/msg/velodyne_packet.hpp>
#include <velodyne_msgs/msg/velodyne_scan.hpp>
Expand Down Expand Up @@ -102,7 +101,7 @@ class InputSocket final : public Input
explicit InputSocket(
rclcpp::Node * private_nh,
const std::string & devip, uint16_t port, bool gps_time);
~InputSocket();
~InputSocket() override;

int getPacket(
velodyne_msgs::msg::VelodynePacket * pkt,
Expand All @@ -111,7 +110,7 @@ class InputSocket final : public Input

private:
int sockfd_;
in_addr devip_;
in_addr devip_{};
bool gps_time_;
};

Expand All @@ -133,7 +132,7 @@ class InputPCAP final : public Input
bool read_once,
bool read_fast,
double repeat_delay);
~InputPCAP();
~InputPCAP() override;

int getPacket(
velodyne_msgs::msg::VelodynePacket * pkt,
Expand All @@ -144,8 +143,8 @@ class InputPCAP final : public Input
rclcpp::Rate packet_rate_;
std::string filename_;
pcap_t * pcap_;
bpf_program pcap_packet_filter_;
char errbuf_[PCAP_ERRBUF_SIZE];
bpf_program pcap_packet_filter_{};
char errbuf_[PCAP_ERRBUF_SIZE]{};
bool empty_;
bool read_once_;
bool read_fast_;
Expand Down
2 changes: 2 additions & 0 deletions velodyne_driver/include/velodyne_driver/time_conversion.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@
* @return timestamp from velodyne, possibly shifted by 1 hour if the function arguments
* disagree by more than a half-hour.
*/
inline
rclcpp::Time resolveHourAmbiguity(const rclcpp::Time & stamp, const rclcpp::Time & nominal_stamp)
{
const int HALFHOUR_TO_SEC = 1800;
Expand All @@ -61,6 +62,7 @@ rclcpp::Time resolveHourAmbiguity(const rclcpp::Time & stamp, const rclcpp::Time
return retval;
}

inline
rclcpp::Time rosTimeFromGpsTimestamp(rclcpp::Time & time_nom, const uint8_t * const data)
{
// time_nom is used to recover the hour
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
# Copyright 2019 Open Source Robotics Foundation, Inc.
# All rights reserved.
#
# Software License Agreement (BSD License 2.0)
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * Redistributions in binary form must reproduce the above
# copyright notice, this list of conditions and the following
# disclaimer in the documentation and/or other materials provided
# with the distribution.
# * Neither the name of {copyright_holder} nor the names of its
# contributors may be used to endorse or promote products derived
# from this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

"""Launch the velodyne driver node in a composable container with default configuration."""

import os

import ament_index_python.packages

from launch import LaunchDescription
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode

import yaml


def generate_launch_description():
config_directory = os.path.join(
ament_index_python.packages.get_package_share_directory('velodyne_driver'),
'config')
param_config = os.path.join(config_directory, 'VLP32C-velodyne_driver_node-params.yaml')
with open(param_config, 'r') as f:
params = yaml.safe_load(f)['velodyne_driver_node']['ros__parameters']
container = ComposableNodeContainer(
node_name='velodyne_driver_container',
node_namespace='',
package='rclcpp_components',
node_executable='component_container',
composable_node_descriptions=[
ComposableNode(
package='velodyne_driver',
node_plugin='velodyne_driver::VelodyneDriver',
node_name='velodyne_driver_node',
parameters=[params]),
],
output='both',
)

return LaunchDescription([container])
Loading

0 comments on commit 8091dda

Please sign in to comment.