Skip to content

Commit

Permalink
Disable cut_angle by default. (#497)
Browse files Browse the repository at this point in the history
  • Loading branch information
JWhitleyWork committed May 27, 2023
1 parent 00d793b commit 026a4f0
Show file tree
Hide file tree
Showing 3 changed files with 3 additions and 3 deletions.
2 changes: 1 addition & 1 deletion velodyne_driver/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -20,5 +20,5 @@ Parameters
* `model` (string) - The model number of the Velodyne attached. This should be one of `64E`, `64E_S2`, `64E_S2.1`, `64E_S3`, `32E`, `32C`, or `VLP16`. Defaults to `64E`.
* `rpm` (double) - The RPM that the Velodyne is configured for. Note that this is descriptive, not prescriptive, so this should be set to match the value configured through the Velodyne web interface.
* `pcap` (string) - The PCAP playback file to use to playback data from. Only used in PCAP playback mode. Defaults to the empty string.
* `cut_angle` (double) - The azimuth angle at which to declare a single rotation complete. If this is less than 0, then a fixed number of packets (device-dependent) is used per rotation. This mostly works, but can vary because of variations in the hardware. If a positive number <= 2*Pi, a rotation will be declared "complete" when the azimuth reported by the device reaches that value. Defaults to 2*Pi.
* `cut_angle` (double) - The azimuth angle at which to declare a single rotation complete. If this is less than 0, then a fixed number of packets (device-dependent) is used per rotation. This mostly works, but can vary because of variations in the hardware. If a positive number <= 2*Pi, a rotation will be declared "complete" when the azimuth reported by the device reaches that value. Defaults to -1.0.
* `port` (int) - The port on which to receive data from the Velodyne. From the factory, the Velodyne is configured to publish data on 2368. Defaults to 2368.
2 changes: 1 addition & 1 deletion velodyne_driver/include/velodyne_driver/driver.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ class VelodyneDriver final : public rclcpp::Node
std::string model; // device model name
int npackets; // number of packets to collect
double rpm; // device rotation rate (RPMs)
int cut_angle; // cutting angle in 1/100°
int cut_angle; // cutting angle in radians
double time_offset; // time in seconds added to each velodyne time stamp
bool enabled; // polling is enabled
bool timestamp_first_packet; // timestamp based on first packet instead of last one
Expand Down
2 changes: 1 addition & 1 deletion velodyne_driver/src/driver/driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ VelodyneDriver::VelodyneDriver(const rclcpp::NodeOptions & options)
config_.model = this->declare_parameter("model", std::string("64E"));
config_.rpm = this->declare_parameter("rpm", 600.0);
std::string dump_file = this->declare_parameter("pcap", std::string(""));
double cut_angle = this->declare_parameter("cut_angle", 2.0 * M_PI);
double cut_angle = this->declare_parameter("cut_angle", -1.0);
int udp_port = this->declare_parameter("port", static_cast<int>(DATA_PORT_NUMBER));
config_.timestamp_first_packet = this->declare_parameter("timestamp_first_packet", false);

Expand Down

0 comments on commit 026a4f0

Please sign in to comment.