Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Vlp32 #139

Merged
merged 3 commits into from
Jan 5, 2018
Merged

Vlp32 #139

Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion README.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ Overview
========

Velodyne_ is a collection of ROS_ packages supporting `Velodyne high
definition 3D LIDARs`_.
definition 3D LIDARs`_ .

**Warning**::

Expand Down
5 changes: 5 additions & 0 deletions velodyne_driver/src/driver/driver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,11 @@ VelodyneDriver::VelodyneDriver(ros::NodeHandle node,
packet_rate = 1808.0;
model_full_name = std::string("HDL-") + config_.model;
}
else if (config_.model == "32C")
{
packet_rate = 1808.0;
model_full_name = std::string("VLP-") + config_.model;
}
else if (config_.model == "VLP16")
{
packet_rate = 754; // 754 Packets/Second for Last or Strongest mode 1508 for dual (VLP-16 User Manual)
Expand Down
51 changes: 51 additions & 0 deletions velodyne_pointcloud/launch/VLP-32C_points.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
<!-- -*- mode: XML -*- -->
<!-- run velodyne_pointcloud/CloudNodelet in a nodelet manager for an VLP-32C -->

<launch>

<!-- declare arguments with default values -->
<arg name="calibration" default="$(find velodyne_pointcloud)/params/VeloView-VLP-32C.yaml"/>

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It seems like this parameter file is missing from this PR.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks for catching this, @trainman419.

@ASDeveloper00 - Please add this file ASAP.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Nevermind. I realized I have it as well. @trainman419 - It has been added.

<arg name="device_ip" default="" />
<arg name="frame_id" default="velodyne" />
<arg name="manager" default="$(arg frame_id)_nodelet_manager" />
<arg name="max_range" default="130.0" />
<arg name="min_range" default="0.4" />
<arg name="pcap" default="" />
<arg name="port" default="2368" />
<arg name="read_fast" default="false" />
<arg name="read_once" default="false" />
<arg name="repeat_delay" default="0.0" />
<arg name="rpm" default="600.0" />
<arg name="laserscan_ring" default="-1" />
<arg name="laserscan_resolution" default="0.007" />

<!-- start nodelet manager and driver nodelets -->
<include file="$(find velodyne_driver)/launch/nodelet_manager.launch">
<arg name="device_ip" value="$(arg device_ip)"/>
<arg name="frame_id" value="$(arg frame_id)"/>
<arg name="manager" value="$(arg manager)" />
<arg name="model" value="32C"/>
<arg name="pcap" value="$(arg pcap)"/>
<arg name="port" value="$(arg port)"/>
<arg name="read_fast" value="$(arg read_fast)"/>
<arg name="read_once" value="$(arg read_once)"/>
<arg name="repeat_delay" value="$(arg repeat_delay)"/>
<arg name="rpm" value="$(arg rpm)"/>
</include>

<!-- start cloud nodelet -->
<include file="$(find velodyne_pointcloud)/launch/cloud_nodelet.launch">
<arg name="calibration" value="$(arg calibration)"/>
<arg name="manager" value="$(arg manager)" />
<arg name="max_range" value="$(arg max_range)"/>
<arg name="min_range" value="$(arg min_range)"/>
</include>

<!-- start laserscan nodelet -->
<include file="$(find velodyne_pointcloud)/launch/laserscan_nodelet.launch">
<arg name="manager" value="$(arg manager)" />
<arg name="ring" value="$(arg laserscan_ring)"/>
<arg name="resolution" value="$(arg laserscan_resolution)"/>
</include>

</launch>