[ros2] lint the pcl_ros code base to try and get a green build :) (#406)
* Lint! * Fix flake8 errors * Fix clang-tidy errors * Remove [[maybe_unused]]
This commit is contained in:
parent
3966b71ad6
commit
1e544f132e
@ -1,8 +1,8 @@
|
||||
#! /usr/bin/env python
|
||||
|
||||
from dynamic_reconfigure.parameter_generator_catkin import int_t
|
||||
from dynamic_reconfigure.parameter_generator_catkin import double_t
|
||||
from dynamic_reconfigure.parameter_generator_catkin import bool_t
|
||||
from dynamic_reconfigure.parameter_generator_catkin import double_t
|
||||
from dynamic_reconfigure.parameter_generator_catkin import int_t
|
||||
from dynamic_reconfigure.parameter_generator_catkin import str_t
|
||||
|
||||
# set up parameters that we care about
|
||||
@ -11,37 +11,37 @@ PACKAGE = 'pcl_ros'
|
||||
|
||||
def add_common_parameters(gen):
|
||||
# add(self, name, paramtype, level, description, default = None, min = None,
|
||||
# max = None, edit_method = "")
|
||||
gen.add("max_iterations", int_t, 0,
|
||||
"The maximum number of iterations the algorithm will run for",
|
||||
# max = None, edit_method = '')
|
||||
gen.add('max_iterations', int_t, 0,
|
||||
'The maximum number of iterations the algorithm will run for',
|
||||
50, 0, 100000)
|
||||
gen.add("probability", double_t, 0,
|
||||
"The desired probability of choosing at least one sample free from outliers",
|
||||
gen.add('probability', double_t, 0,
|
||||
'The desired probability of choosing at least one sample free from outliers',
|
||||
0.99, 0.5, 0.99)
|
||||
gen.add("distance_threshold", double_t, 0,
|
||||
"The distance to model threshold",
|
||||
gen.add('distance_threshold', double_t, 0,
|
||||
'The distance to model threshold',
|
||||
0.02, 0, 1.0)
|
||||
gen.add("optimize_coefficients", bool_t, 0,
|
||||
"Model coefficient refinement",
|
||||
gen.add('optimize_coefficients', bool_t, 0,
|
||||
'Model coefficient refinement',
|
||||
True)
|
||||
gen.add("radius_min", double_t, 0,
|
||||
"The minimum allowed model radius (where applicable)",
|
||||
gen.add('radius_min', double_t, 0,
|
||||
'The minimum allowed model radius (where applicable)',
|
||||
0.0, 0, 1.0)
|
||||
gen.add("radius_max", double_t, 0,
|
||||
"The maximum allowed model radius (where applicable)",
|
||||
gen.add('radius_max', double_t, 0,
|
||||
'The maximum allowed model radius (where applicable)',
|
||||
0.05, 0, 1.0)
|
||||
gen.add("eps_angle", double_t, 0,
|
||||
("The maximum allowed difference between the model normal "
|
||||
"and the given axis in radians."),
|
||||
gen.add('eps_angle', double_t, 0,
|
||||
('The maximum allowed difference between the model normal '
|
||||
'and the given axis in radians.'),
|
||||
0.17, 0.0, 1.5707)
|
||||
gen.add("min_inliers", int_t, 0,
|
||||
"The minimum number of inliers a model must have in order to be considered valid.",
|
||||
gen.add('min_inliers', int_t, 0,
|
||||
'The minimum number of inliers a model must have in order to be considered valid.',
|
||||
0, 0, 100000)
|
||||
gen.add("input_frame", str_t, 0,
|
||||
("The input TF frame the data should be transformed into, "
|
||||
"if input.header.frame_id is different."),
|
||||
"")
|
||||
gen.add("output_frame", str_t, 0,
|
||||
("The output TF frame the data should be transformed into, "
|
||||
"if input.header.frame_id is different."),
|
||||
"")
|
||||
gen.add('input_frame', str_t, 0,
|
||||
('The input TF frame the data should be transformed into, '
|
||||
'if input.header.frame_id is different.'),
|
||||
'')
|
||||
gen.add('output_frame', str_t, 0,
|
||||
('The output TF frame the data should be transformed into, '
|
||||
'if input.header.frame_id is different.'),
|
||||
'')
|
||||
|
||||
@ -1,8 +1,8 @@
|
||||
#! /usr/bin/env python
|
||||
|
||||
from dynamic_reconfigure.parameter_generator_catkin import str_t
|
||||
from dynamic_reconfigure.parameter_generator_catkin import double_t
|
||||
from dynamic_reconfigure.parameter_generator_catkin import bool_t
|
||||
from dynamic_reconfigure.parameter_generator_catkin import double_t
|
||||
from dynamic_reconfigure.parameter_generator_catkin import str_t
|
||||
|
||||
# set up parameters that we care about
|
||||
PACKAGE = 'pcl_ros'
|
||||
@ -10,27 +10,27 @@ PACKAGE = 'pcl_ros'
|
||||
|
||||
def add_common_parameters(gen):
|
||||
# def add (self, name, paramtype, level, description, default = None, min = None,
|
||||
# max = None, edit_method = ""):
|
||||
gen.add("filter_field_name", str_t, 0, "The field name used for filtering", "z")
|
||||
gen.add("filter_limit_min", double_t, 0,
|
||||
"The minimum allowed field value a point will be considered from",
|
||||
# max = None, edit_method = ''):
|
||||
gen.add('filter_field_name', str_t, 0, 'The field name used for filtering', 'z')
|
||||
gen.add('filter_limit_min', double_t, 0,
|
||||
'The minimum allowed field value a point will be considered from',
|
||||
0.0, -100000.0, 100000.0)
|
||||
gen.add("filter_limit_max", double_t, 0,
|
||||
"The maximum allowed field value a point will be considered from",
|
||||
gen.add('filter_limit_max', double_t, 0,
|
||||
'The maximum allowed field value a point will be considered from',
|
||||
1.0, -100000.0, 100000.0)
|
||||
gen.add("filter_limit_negative", bool_t, 0,
|
||||
("Set to true if we want to return the data outside "
|
||||
"[filter_limit_min; filter_limit_max]."),
|
||||
gen.add('filter_limit_negative', bool_t, 0,
|
||||
('Set to true if we want to return the data outside '
|
||||
'[filter_limit_min; filter_limit_max].'),
|
||||
False)
|
||||
gen.add("keep_organized", bool_t, 0,
|
||||
("Set whether the filtered points should be kept and set to NaN, "
|
||||
"or removed from the PointCloud, thus potentially breaking its organized structure."),
|
||||
gen.add('keep_organized', bool_t, 0,
|
||||
('Set whether the filtered points should be kept and set to NaN, '
|
||||
'or removed from the PointCloud, thus potentially breaking its organized structure.'),
|
||||
False)
|
||||
gen.add("input_frame", str_t, 0,
|
||||
("The input TF frame the data should be transformed into before processing, "
|
||||
"if input.header.frame_id is different."),
|
||||
"")
|
||||
gen.add("output_frame", str_t, 0,
|
||||
("The output TF frame the data should be transformed into after processing, "
|
||||
"if input.header.frame_id is different."),
|
||||
"")
|
||||
gen.add('input_frame', str_t, 0,
|
||||
('The input TF frame the data should be transformed into before processing, '
|
||||
'if input.header.frame_id is different.'),
|
||||
'')
|
||||
gen.add('output_frame', str_t, 0,
|
||||
('The output TF frame the data should be transformed into after processing, '
|
||||
'if input.header.frame_id is different.'),
|
||||
'')
|
||||
|
||||
@ -37,7 +37,6 @@
|
||||
#ifndef PCL_ROS__IMPL__TRANSFORMS_HPP_
|
||||
#define PCL_ROS__IMPL__TRANSFORMS_HPP_
|
||||
|
||||
#include "pcl_ros/transforms.hpp"
|
||||
#include <pcl/common/transforms.h>
|
||||
#include <pcl_conversions/pcl_conversions.h>
|
||||
#include <tf2/convert.h>
|
||||
@ -45,14 +44,18 @@
|
||||
#include <tf2/LinearMath/Transform.h>
|
||||
#include <tf2/LinearMath/Quaternion.h>
|
||||
#include <tf2/LinearMath/Vector3.h>
|
||||
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
|
||||
#include <tf2_ros/buffer.h>
|
||||
#include <tf2_ros/transform_listener.h>
|
||||
|
||||
#include <Eigen/Dense>
|
||||
#include <string>
|
||||
|
||||
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
|
||||
#include <geometry_msgs/msg/transform_stamped.hpp>
|
||||
#include <rclcpp/logging.hpp>
|
||||
#include <rclcpp/time.hpp>
|
||||
#include <Eigen/Dense>
|
||||
#include <string>
|
||||
|
||||
#include "pcl_ros/transforms.hpp"
|
||||
|
||||
using pcl_conversions::fromPCL;
|
||||
using pcl_conversions::toPCL;
|
||||
|
||||
@ -38,11 +38,11 @@
|
||||
#ifndef PCL_ROS__IO__BAG_IO_HPP_
|
||||
#define PCL_ROS__IO__BAG_IO_HPP_
|
||||
|
||||
#include <pcl_ros/pcl_nodelet.hpp>
|
||||
#include <sensor_msgs/PointCloud2.h>
|
||||
#include <rosbag/bag.h>
|
||||
#include <rosbag/view.h>
|
||||
#include <string>
|
||||
#include <pcl_ros/pcl_nodelet.hpp>
|
||||
|
||||
namespace pcl_ros
|
||||
{
|
||||
|
||||
@ -44,30 +44,25 @@
|
||||
#ifndef PCL_ROS__PCL_NODE_HPP_
|
||||
#define PCL_ROS__PCL_NODE_HPP_
|
||||
|
||||
#include <sensor_msgs/msg/point_cloud2.hpp>
|
||||
// PCL includes
|
||||
#include <pcl_msgs/msg/point_indices.hpp>
|
||||
#include <pcl_msgs/msg/model_coefficients.hpp>
|
||||
#include <pcl/pcl_base.h>
|
||||
#include <pcl/point_types.h>
|
||||
#include <pcl_conversions/pcl_conversions.h>
|
||||
// ROS Nodelet includes
|
||||
// #include <nodelet_topic_tools/nodelet_lazy.h> // TODO(daisukes): lazy subscription
|
||||
#include <message_filters/subscriber.h>
|
||||
#include <message_filters/synchronizer.h>
|
||||
#include <message_filters/sync_policies/exact_time.h>
|
||||
#include <message_filters/sync_policies/approximate_time.h>
|
||||
|
||||
// Include TF
|
||||
#include <pcl/pcl_base.h>
|
||||
#include <pcl/point_types.h>
|
||||
#include <pcl_conversions/pcl_conversions.h>
|
||||
#include <tf2_ros/transform_listener.h>
|
||||
#include <tf2_ros/buffer.h>
|
||||
// #include <nodelet_topic_tools/nodelet_lazy.h> // TODO(daisukes): lazy subscription
|
||||
|
||||
// STL
|
||||
#include <memory>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
// ROS2 includes
|
||||
|
||||
#include <rclcpp/rclcpp.hpp>
|
||||
#include <sensor_msgs/msg/point_cloud2.hpp>
|
||||
#include <pcl_msgs/msg/point_indices.hpp>
|
||||
#include <pcl_msgs/msg/model_coefficients.hpp>
|
||||
|
||||
// #include "pcl_ros/point_cloud.hpp"
|
||||
|
||||
@ -199,8 +194,8 @@ protected:
|
||||
bool approximate_sync_;
|
||||
|
||||
/** \brief TF listener object. */
|
||||
tf2_ros::TransformListener tf_listener_;
|
||||
tf2_ros::Buffer tf_buffer_;
|
||||
tf2_ros::TransformListener tf_listener_;
|
||||
|
||||
/** \brief Test whether a given PointCloud message is "valid" (i.e., has points, and width and height are non-zero).
|
||||
* \param cloud the point cloud to test
|
||||
@ -249,7 +244,9 @@ protected:
|
||||
* \param topic_name an optional topic name (only used for printing, defaults to "indices")
|
||||
*/
|
||||
inline bool
|
||||
isValid(const PointIndicesConstPtr & indices, const std::string & topic_name = "indices")
|
||||
isValid(
|
||||
const PointIndicesConstPtr & /*indices*/,
|
||||
const std::string & /*topic_name*/ = "indices")
|
||||
{
|
||||
/*if (indices->indices.empty ())
|
||||
{
|
||||
@ -269,7 +266,9 @@ protected:
|
||||
* \param topic_name an optional topic name (only used for printing, defaults to "model")
|
||||
*/
|
||||
inline bool
|
||||
isValid(const ModelCoefficientsConstPtr & model, const std::string & topic_name = "model")
|
||||
isValid(
|
||||
const ModelCoefficientsConstPtr & /*model*/,
|
||||
const std::string & /*topic_name*/ = "model")
|
||||
{
|
||||
/*if (model->values.empty ())
|
||||
{
|
||||
|
||||
@ -44,12 +44,12 @@
|
||||
|
||||
#include <ros/ros.h>
|
||||
#include <pcl/point_cloud.h>
|
||||
#include <pcl/pcl_config.h> // for PCL_VERSION_COMPARE
|
||||
#include <pcl/pcl_config.h> // for PCL_VERSION_COMPARE
|
||||
#if PCL_VERSION_COMPARE(>=, 1, 11, 0)
|
||||
#include <pcl/type_traits.h>
|
||||
#else
|
||||
#include <pcl/point_traits.h>
|
||||
#endif // PCL_VERSION_COMPARE(>=, 1, 11, 0)
|
||||
#endif // PCL_VERSION_COMPARE(>=, 1, 11, 0)
|
||||
#include <pcl/for_each_type.h>
|
||||
#include <pcl/conversions.h>
|
||||
#if ROS_POINTER_COMPATIBILITY_IMPLEMENTED
|
||||
@ -61,9 +61,6 @@
|
||||
#endif
|
||||
#include <pcl_conversions/pcl_conversions.h>
|
||||
#include <sensor_msgs/PointCloud2.h>
|
||||
#include <boost/foreach.hpp> // for BOOST_FOREACH
|
||||
#include <boost/mpl/size.hpp>
|
||||
#include <boost/ref.hpp>
|
||||
#include <string>
|
||||
#include <utility>
|
||||
#include <vector>
|
||||
@ -71,6 +68,9 @@
|
||||
#include <type_traits>
|
||||
#include <memory>
|
||||
#endif
|
||||
#include <boost/foreach.hpp> // for BOOST_FOREACH
|
||||
#include <boost/mpl/size.hpp>
|
||||
#include <boost/ref.hpp>
|
||||
|
||||
namespace pcl
|
||||
{
|
||||
|
||||
@ -41,11 +41,11 @@
|
||||
#include <tf2/LinearMath/Transform.h>
|
||||
#include <tf2_ros/buffer.h>
|
||||
#include <tf2_ros/transform_listener.h>
|
||||
#include <Eigen/Dense>
|
||||
#include <string>
|
||||
#include <rclcpp/time.hpp>
|
||||
#include <sensor_msgs/msg/point_cloud2.hpp>
|
||||
#include <geometry_msgs/msg/transform_stamped.hpp>
|
||||
#include <Eigen/Dense>
|
||||
#include <string>
|
||||
|
||||
namespace pcl_ros
|
||||
{
|
||||
|
||||
@ -36,8 +36,8 @@
|
||||
*/
|
||||
|
||||
#include <pluginlib/class_list_macros.h>
|
||||
#include <pcl_ros/io/pcd_io.hpp>
|
||||
#include <string>
|
||||
#include <pcl_ros/io/pcd_io.hpp>
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
|
||||
void
|
||||
|
||||
@ -38,10 +38,6 @@
|
||||
#include <tf/transform_listener.h>
|
||||
#include <tf/transform_broadcaster.h>
|
||||
|
||||
#include <boost/bind.hpp>
|
||||
#include <boost/scoped_ptr.hpp>
|
||||
|
||||
#include <pcl_ros/point_cloud.hpp>
|
||||
#include <pcl_conversions/pcl_conversions.h>
|
||||
|
||||
#include <ros/ros.h>
|
||||
@ -52,6 +48,11 @@
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
#include <boost/bind.hpp>
|
||||
#include <boost/scoped_ptr.hpp>
|
||||
|
||||
#include <pcl_ros/point_cloud.hpp>
|
||||
|
||||
// using a random point type, as we want to make sure that it does work with
|
||||
// other points than just XYZ
|
||||
typedef pcl::PointCloud<pcl::PointXYZRGBNormal> PCDType;
|
||||
|
||||
@ -36,6 +36,7 @@
|
||||
|
||||
#include "pcl_ros/transforms.hpp"
|
||||
#include "pcl_ros/impl/transforms.hpp"
|
||||
|
||||
#include <pcl/common/transforms.h>
|
||||
#include <pcl/point_types.h>
|
||||
#include <pcl_conversions/pcl_conversions.h>
|
||||
@ -43,18 +44,20 @@
|
||||
#include <tf2/exceptions.h>
|
||||
#include <tf2/LinearMath/Transform.h>
|
||||
#include <tf2/LinearMath/Vector3.h>
|
||||
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
|
||||
#include <tf2_ros/buffer.h>
|
||||
#include <tf2_ros/transform_listener.h>
|
||||
#include <sensor_msgs/msg/point_cloud2.hpp>
|
||||
#include <geometry_msgs/msg/transform_stamped.hpp>
|
||||
#include <rclcpp/logging.hpp>
|
||||
#include <rclcpp/time.hpp>
|
||||
|
||||
#include <Eigen/Dense>
|
||||
#include <cmath>
|
||||
#include <limits>
|
||||
#include <string>
|
||||
|
||||
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
|
||||
#include <sensor_msgs/msg/point_cloud2.hpp>
|
||||
#include <geometry_msgs/msg/transform_stamped.hpp>
|
||||
#include <rclcpp/logging.hpp>
|
||||
#include <rclcpp/time.hpp>
|
||||
|
||||
namespace pcl_ros
|
||||
{
|
||||
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
@ -36,9 +36,8 @@ import launch.actions
|
||||
import launch_ros.actions
|
||||
import launch_testing.actions
|
||||
import launch_testing.markers
|
||||
import pytest
|
||||
|
||||
from launch_testing_ros import WaitForTopics
|
||||
import pytest
|
||||
from sensor_msgs.msg import PointCloud2
|
||||
|
||||
|
||||
@ -78,6 +77,7 @@ def generate_test_description():
|
||||
|
||||
|
||||
class TestFilter(unittest.TestCase):
|
||||
|
||||
def test_filter_output(self):
|
||||
wait_for_topics = WaitForTopics([('output', PointCloud2)], timeout=5.0)
|
||||
assert wait_for_topics.wait()
|
||||
|
||||
@ -36,9 +36,8 @@ import launch.actions
|
||||
import launch_ros.actions
|
||||
import launch_testing.actions
|
||||
import launch_testing.markers
|
||||
import pytest
|
||||
|
||||
from launch_testing_ros import WaitForTopics
|
||||
import pytest
|
||||
from sensor_msgs.msg import PointCloud2
|
||||
|
||||
|
||||
@ -49,9 +48,9 @@ def generate_test_description():
|
||||
filter_executable = os.getenv('FILTER_EXECUTABLE')
|
||||
parameters = ast.literal_eval(os.getenv('PARAMETERS')) if 'PARAMETERS' in os.environ else {}
|
||||
|
||||
ros_arguments = ["-r", "input:=point_cloud2"]
|
||||
ros_arguments = ['-r', 'input:=point_cloud2']
|
||||
for key in parameters.keys():
|
||||
ros_arguments.extend(["-p", "{}:={}".format(key, parameters[key])])
|
||||
ros_arguments.extend(['-p', '{}:={}'.format(key, parameters[key])])
|
||||
|
||||
return launch.LaunchDescription([
|
||||
|
||||
@ -72,7 +71,7 @@ def generate_test_description():
|
||||
launch_ros.actions.Node(
|
||||
package='pcl_ros',
|
||||
executable=filter_executable,
|
||||
output="screen",
|
||||
output='screen',
|
||||
ros_arguments=ros_arguments
|
||||
),
|
||||
launch_testing.actions.ReadyToTest()
|
||||
@ -80,6 +79,7 @@ def generate_test_description():
|
||||
|
||||
|
||||
class TestFilter(unittest.TestCase):
|
||||
|
||||
def test_filter_output(self):
|
||||
wait_for_topics = WaitForTopics([('output', PointCloud2)], timeout=5.0)
|
||||
assert wait_for_topics.wait()
|
||||
|
||||
@ -49,11 +49,13 @@ Cloud Data) format.
|
||||
#include <pcl/common/io.h>
|
||||
#include <pcl/io/pcd_io.h>
|
||||
#include <pcl_conversions/pcl_conversions.h>
|
||||
|
||||
#include <tf/transform_listener.h>
|
||||
#include <tf/transform_broadcaster.h>
|
||||
#include <boost/filesystem.hpp>
|
||||
#include <sstream>
|
||||
#include <string>
|
||||
|
||||
#include <boost/filesystem.hpp>
|
||||
#include "pcl_ros/transforms.hpp"
|
||||
|
||||
typedef sensor_msgs::PointCloud2 PointCloud;
|
||||
|
||||
@ -43,21 +43,18 @@
|
||||
|
||||
**/
|
||||
|
||||
// STL
|
||||
#include <pcl/common/io.h>
|
||||
#include <pcl/io/pcd_io.h>
|
||||
#include <pcl/point_types.h>
|
||||
#include <pcl_conversions/pcl_conversions.h>
|
||||
|
||||
#include <chrono>
|
||||
#include <string>
|
||||
#include <thread>
|
||||
|
||||
// PCL
|
||||
#include <pcl/common/io.h>
|
||||
#include <pcl/io/pcd_io.h>
|
||||
#include <pcl/point_types.h>
|
||||
|
||||
// ROS core
|
||||
#include <rclcpp/rclcpp.hpp>
|
||||
#include "rclcpp_components/register_node_macro.hpp"
|
||||
#include <sensor_msgs/msg/point_cloud2.hpp>
|
||||
#include <pcl_conversions/pcl_conversions.h>
|
||||
|
||||
namespace pcl_ros
|
||||
{
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user