From dda64b3d6de24edad0790d7a659c03056a9373f2 Mon Sep 17 00:00:00 2001 From: Philipp Schmaelzle Date: Tue, 25 Oct 2022 16:24:13 +0200 Subject: [PATCH 1/4] Add timestamp from phase_lock angle --- .../include/velodyne_driver/driver.h | 3 ++ velodyne_driver/launch/nodelet_manager.launch | 4 ++ velodyne_driver/src/driver/driver.cc | 41 +++++++++++++++++++ 3 files changed, 48 insertions(+) diff --git a/velodyne_driver/include/velodyne_driver/driver.h b/velodyne_driver/include/velodyne_driver/driver.h index ff2b7925e..398e9a3ab 100644 --- a/velodyne_driver/include/velodyne_driver/driver.h +++ b/velodyne_driver/include/velodyne_driver/driver.h @@ -74,15 +74,18 @@ class VelodyneDriver int npackets; // number of packets to collect double rpm; // device rotation rate (RPMs) int cut_angle; // cutting angle in 1/100° + int phase_lock_angle; // configured phase lock angle double time_offset; // time in seconds added to each velodyne time stamp bool enabled; // polling is enabled bool timestamp_first_packet; + bool timestamp_phase_lock; } config_; boost::shared_ptr input_; ros::Publisher output_; int last_azimuth_; + int phase_lock_angle_; /* diagnostics updater */ ros::Timer diag_timer_; diff --git a/velodyne_driver/launch/nodelet_manager.launch b/velodyne_driver/launch/nodelet_manager.launch index e062d5d1f..c40befe1a 100644 --- a/velodyne_driver/launch/nodelet_manager.launch +++ b/velodyne_driver/launch/nodelet_manager.launch @@ -16,7 +16,9 @@ + + @@ -37,6 +39,8 @@ + + diff --git a/velodyne_driver/src/driver/driver.cc b/velodyne_driver/src/driver/driver.cc index b9e5a4ea0..d46b08038 100644 --- a/velodyne_driver/src/driver/driver.cc +++ b/velodyne_driver/src/driver/driver.cc @@ -122,6 +122,12 @@ VelodyneDriver::VelodyneDriver(ros::NodeHandle node, if (config_.timestamp_first_packet) ROS_INFO("Setting velodyne scan start time to timestamp of first packet"); + // if we are timestamping based on the phase lock angle configured packet in the scan + private_nh.param("timestamp_phase_lock", config_.timestamp_phase_lock, false); + if (config_.timestamp_phase_lock) + ROS_INFO("Setting velodyne scan timestamp to timestamp of angle of phase lock"); + + std::string dump_file; private_nh.param("pcap", dump_file, std::string("")); @@ -147,6 +153,28 @@ VelodyneDriver::VelodyneDriver(ros::NodeHandle node, // which is used in velodyne packets config_.cut_angle = int((cut_angle*360/(2*M_PI))*100); + double phase_lock_angle; + private_nh.param("phase_lock_angle", phase_lock_angle, -0.01); + if (phase_lock_angle < 0.0) + { + ROS_INFO_STREAM("No Phase Lock Angle provided."); + } + else if (phase_lock_angle < (2*M_PI)) + { + ROS_INFO_STREAM("Phase Lock Angle configured. " + "Set to " << cut_angle << " rad."); + } + else + { + ROS_ERROR_STREAM("phase_lock_angle is out of range. Allowed range is " + << "between 0.0 and 2*PI or negative values to deactivate this feature."); + phase_lock_angle = -0.01; + } + + // Convert phase_lock_angle from radian to one-hundredth degree, + // which is used in velodyne packets + config_.phase_lock_angle = int((phase_lock_angle*360/(2*M_PI))*100); + int udp_port; private_nh.param("port", udp_port, (int) DATA_PORT_NUMBER); @@ -213,6 +241,8 @@ bool VelodyneDriver::poll(void) // Allocate a new shared pointer for zero-copy sharing with other nodelets. velodyne_msgs::VelodyneScanPtr scan(new velodyne_msgs::VelodyneScan); + ros::Time phase_lock_time; + if( config_.cut_angle >= 0) //Cut at specific angle feature enabled { scan->packets.reserve(config_.npackets); @@ -237,6 +267,14 @@ bool VelodyneDriver::poll(void) last_azimuth_ = azimuth; continue; } + + if((last_azimuth_ < config_.phase_lock_angle && config_.phase_lock_angle <= azimuth) + || ( config_.phase_lock_angle <= azimuth && azimuth < last_azimuth_) + || (azimuth < last_azimuth_ && last_azimuth_ < config_.phase_lock_angle)) + { + phase_lock_time = tmp_packet.stamp; + } + if((last_azimuth_ < config_.cut_angle && config_.cut_angle <= azimuth) || ( config_.cut_angle <= azimuth && azimuth < last_azimuth_) || (azimuth < last_azimuth_ && last_azimuth_ < config_.cut_angle)) @@ -270,6 +308,9 @@ bool VelodyneDriver::poll(void) if (config_.timestamp_first_packet){ scan->header.stamp = scan->packets.front().stamp; } + else if(config_.timestamp_phase_lock && config_.phase_lock_angle >= 0.0){ + scan->header.stamp = phase_lock_time; + } else{ scan->header.stamp = scan->packets.back().stamp; } From 105ee421687365435a70719bf9c4afff216d350e Mon Sep 17 00:00:00 2001 From: Philipp Schmaelzle Date: Tue, 25 Oct 2022 16:27:53 +0200 Subject: [PATCH 2/4] Add parameters to configure timestamp at phase_lock angle to launch files --- velodyne_pointcloud/launch/32e_points.launch | 4 ++++ velodyne_pointcloud/launch/64e_S3.launch | 4 ++++ velodyne_pointcloud/launch/VLP-32C_points.launch | 4 ++++ velodyne_pointcloud/launch/VLP16_points.launch | 4 ++++ velodyne_pointcloud/launch/VLS128_points.launch | 4 ++++ 5 files changed, 20 insertions(+) diff --git a/velodyne_pointcloud/launch/32e_points.launch b/velodyne_pointcloud/launch/32e_points.launch index 9449f103c..e38cd11f7 100755 --- a/velodyne_pointcloud/launch/32e_points.launch +++ b/velodyne_pointcloud/launch/32e_points.launch @@ -19,6 +19,8 @@ + + @@ -39,6 +41,8 @@ + + diff --git a/velodyne_pointcloud/launch/64e_S3.launch b/velodyne_pointcloud/launch/64e_S3.launch index c3c677448..764aa8ac8 100755 --- a/velodyne_pointcloud/launch/64e_S3.launch +++ b/velodyne_pointcloud/launch/64e_S3.launch @@ -19,6 +19,8 @@ + + @@ -39,6 +41,8 @@ + + diff --git a/velodyne_pointcloud/launch/VLP-32C_points.launch b/velodyne_pointcloud/launch/VLP-32C_points.launch index 5043db785..3c717aaac 100755 --- a/velodyne_pointcloud/launch/VLP-32C_points.launch +++ b/velodyne_pointcloud/launch/VLP-32C_points.launch @@ -19,6 +19,8 @@ + + @@ -39,6 +41,8 @@ + + diff --git a/velodyne_pointcloud/launch/VLP16_points.launch b/velodyne_pointcloud/launch/VLP16_points.launch index 63463768e..b2adc6aa1 100755 --- a/velodyne_pointcloud/launch/VLP16_points.launch +++ b/velodyne_pointcloud/launch/VLP16_points.launch @@ -19,6 +19,8 @@ + + @@ -39,6 +41,8 @@ + + diff --git a/velodyne_pointcloud/launch/VLS128_points.launch b/velodyne_pointcloud/launch/VLS128_points.launch index da49ef723..5d908d9f6 100644 --- a/velodyne_pointcloud/launch/VLS128_points.launch +++ b/velodyne_pointcloud/launch/VLS128_points.launch @@ -18,6 +18,8 @@ + + @@ -37,6 +39,8 @@ + + From 502037a1bd0ae9fac7625565ab14b4fb6e414371 Mon Sep 17 00:00:00 2001 From: Philipp Schmaelzle Date: Wed, 26 Oct 2022 09:31:57 +0200 Subject: [PATCH 3/4] Redo timestamp from phase lock to be more generic. timestamp from angle. --- .../include/velodyne_driver/driver.h | 4 +- velodyne_driver/launch/nodelet_manager.launch | 6 +-- velodyne_driver/src/driver/driver.cc | 45 +++++++++---------- velodyne_pointcloud/launch/32e_points.launch | 5 +-- velodyne_pointcloud/launch/64e_S3.launch | 5 +-- .../launch/VLP-32C_points.launch | 5 +-- .../launch/VLP16_points.launch | 6 +-- .../launch/VLS128_points.launch | 5 +-- 8 files changed, 34 insertions(+), 47 deletions(-) diff --git a/velodyne_driver/include/velodyne_driver/driver.h b/velodyne_driver/include/velodyne_driver/driver.h index 398e9a3ab..7b2dc360e 100644 --- a/velodyne_driver/include/velodyne_driver/driver.h +++ b/velodyne_driver/include/velodyne_driver/driver.h @@ -74,18 +74,16 @@ class VelodyneDriver int npackets; // number of packets to collect double rpm; // device rotation rate (RPMs) int cut_angle; // cutting angle in 1/100° - int phase_lock_angle; // configured phase lock angle + int timestamp_angle; // configured phase lock angle double time_offset; // time in seconds added to each velodyne time stamp bool enabled; // polling is enabled bool timestamp_first_packet; - bool timestamp_phase_lock; } config_; boost::shared_ptr input_; ros::Publisher output_; int last_azimuth_; - int phase_lock_angle_; /* diagnostics updater */ ros::Timer diag_timer_; diff --git a/velodyne_driver/launch/nodelet_manager.launch b/velodyne_driver/launch/nodelet_manager.launch index c40befe1a..23f03b0f0 100644 --- a/velodyne_driver/launch/nodelet_manager.launch +++ b/velodyne_driver/launch/nodelet_manager.launch @@ -16,9 +16,8 @@ - + - @@ -39,8 +38,7 @@ - - + diff --git a/velodyne_driver/src/driver/driver.cc b/velodyne_driver/src/driver/driver.cc index d46b08038..019b4b2ba 100644 --- a/velodyne_driver/src/driver/driver.cc +++ b/velodyne_driver/src/driver/driver.cc @@ -122,12 +122,6 @@ VelodyneDriver::VelodyneDriver(ros::NodeHandle node, if (config_.timestamp_first_packet) ROS_INFO("Setting velodyne scan start time to timestamp of first packet"); - // if we are timestamping based on the phase lock angle configured packet in the scan - private_nh.param("timestamp_phase_lock", config_.timestamp_phase_lock, false); - if (config_.timestamp_phase_lock) - ROS_INFO("Setting velodyne scan timestamp to timestamp of angle of phase lock"); - - std::string dump_file; private_nh.param("pcap", dump_file, std::string("")); @@ -153,27 +147,30 @@ VelodyneDriver::VelodyneDriver(ros::NodeHandle node, // which is used in velodyne packets config_.cut_angle = int((cut_angle*360/(2*M_PI))*100); - double phase_lock_angle; - private_nh.param("phase_lock_angle", phase_lock_angle, -0.01); - if (phase_lock_angle < 0.0) + double timestamp_angle; + private_nh.param("timestamp_angle", timestamp_angle, -0.01); + if (timestamp_angle < 0.0) { - ROS_INFO_STREAM("No Phase Lock Angle provided."); + ROS_INFO_STREAM("Time at specific angle feature deactivated."); } - else if (phase_lock_angle < (2*M_PI)) + else if (timestamp_angle < (2*M_PI)) { - ROS_INFO_STREAM("Phase Lock Angle configured. " - "Set to " << cut_angle << " rad."); + ROS_INFO_STREAM("Time at specific angle feature activated. " + "Set to " << timestamp_angle << " rad."); + if (config_.timestamp_first_packet){ + ROS_ERROR_STREAM("timestamp_first_packet AND timestamp_angle configured! timestamp_first_packet will be used!"); + } } else { - ROS_ERROR_STREAM("phase_lock_angle is out of range. Allowed range is " + ROS_ERROR_STREAM("timestamp_angle is out of range. Allowed range is " << "between 0.0 and 2*PI or negative values to deactivate this feature."); - phase_lock_angle = -0.01; + timestamp_angle = -0.01; } - // Convert phase_lock_angle from radian to one-hundredth degree, + // Convert timestamp_angle from radian to one-hundredth degree, // which is used in velodyne packets - config_.phase_lock_angle = int((phase_lock_angle*360/(2*M_PI))*100); + config_.timestamp_angle = int((timestamp_angle*360/(2*M_PI))*100); int udp_port; private_nh.param("port", udp_port, (int) DATA_PORT_NUMBER); @@ -241,7 +238,7 @@ bool VelodyneDriver::poll(void) // Allocate a new shared pointer for zero-copy sharing with other nodelets. velodyne_msgs::VelodyneScanPtr scan(new velodyne_msgs::VelodyneScan); - ros::Time phase_lock_time; + ros::Time time_angle; if( config_.cut_angle >= 0) //Cut at specific angle feature enabled { @@ -268,11 +265,11 @@ bool VelodyneDriver::poll(void) continue; } - if((last_azimuth_ < config_.phase_lock_angle && config_.phase_lock_angle <= azimuth) - || ( config_.phase_lock_angle <= azimuth && azimuth < last_azimuth_) - || (azimuth < last_azimuth_ && last_azimuth_ < config_.phase_lock_angle)) + if((last_azimuth_ < config_.timestamp_angle && config_.timestamp_angle <= azimuth) + || ( config_.timestamp_angle <= azimuth && azimuth < last_azimuth_) + || (azimuth < last_azimuth_ && last_azimuth_ < config_.timestamp_angle)) { - phase_lock_time = tmp_packet.stamp; + time_angle = tmp_packet.stamp; } if((last_azimuth_ < config_.cut_angle && config_.cut_angle <= azimuth) @@ -308,8 +305,8 @@ bool VelodyneDriver::poll(void) if (config_.timestamp_first_packet){ scan->header.stamp = scan->packets.front().stamp; } - else if(config_.timestamp_phase_lock && config_.phase_lock_angle >= 0.0){ - scan->header.stamp = phase_lock_time; + else if(config_.timestamp_angle >= 0.0){ + scan->header.stamp = time_angle; } else{ scan->header.stamp = scan->packets.back().stamp; diff --git a/velodyne_pointcloud/launch/32e_points.launch b/velodyne_pointcloud/launch/32e_points.launch index e38cd11f7..9eb9a3a09 100755 --- a/velodyne_pointcloud/launch/32e_points.launch +++ b/velodyne_pointcloud/launch/32e_points.launch @@ -19,8 +19,7 @@ - - + @@ -42,7 +41,7 @@ - + diff --git a/velodyne_pointcloud/launch/64e_S3.launch b/velodyne_pointcloud/launch/64e_S3.launch index 764aa8ac8..29821ff31 100755 --- a/velodyne_pointcloud/launch/64e_S3.launch +++ b/velodyne_pointcloud/launch/64e_S3.launch @@ -19,8 +19,7 @@ - - + @@ -42,7 +41,7 @@ - + diff --git a/velodyne_pointcloud/launch/VLP-32C_points.launch b/velodyne_pointcloud/launch/VLP-32C_points.launch index 3c717aaac..61072664f 100755 --- a/velodyne_pointcloud/launch/VLP-32C_points.launch +++ b/velodyne_pointcloud/launch/VLP-32C_points.launch @@ -19,8 +19,7 @@ - - + @@ -42,7 +41,7 @@ - + diff --git a/velodyne_pointcloud/launch/VLP16_points.launch b/velodyne_pointcloud/launch/VLP16_points.launch index b2adc6aa1..435f4188e 100755 --- a/velodyne_pointcloud/launch/VLP16_points.launch +++ b/velodyne_pointcloud/launch/VLP16_points.launch @@ -19,8 +19,7 @@ - - + @@ -41,8 +40,7 @@ - - + diff --git a/velodyne_pointcloud/launch/VLS128_points.launch b/velodyne_pointcloud/launch/VLS128_points.launch index 5d908d9f6..e08526b5d 100644 --- a/velodyne_pointcloud/launch/VLS128_points.launch +++ b/velodyne_pointcloud/launch/VLS128_points.launch @@ -18,8 +18,7 @@ - - + @@ -40,7 +39,7 @@ - + From 809356792671a296b70e505552af9fdc07dd7e3c Mon Sep 17 00:00:00 2001 From: PhilippSchmaelzle <64705964+PhilippSchmaelzle@users.noreply.github.com> Date: Wed, 9 Nov 2022 09:42:27 +0100 Subject: [PATCH 4/4] fix leftovers in launch file --- velodyne_pointcloud/launch/VLP-32C_points.launch | 1 - 1 file changed, 1 deletion(-) diff --git a/velodyne_pointcloud/launch/VLP-32C_points.launch b/velodyne_pointcloud/launch/VLP-32C_points.launch index 61072664f..1c028a138 100755 --- a/velodyne_pointcloud/launch/VLP-32C_points.launch +++ b/velodyne_pointcloud/launch/VLP-32C_points.launch @@ -40,7 +40,6 @@ -