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

Updated "cut at specified angle feature" with latest master version. #126

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
96 commits
Select commit Hold shift + click to select a range
425f5b2
parameter and code added for working with multiple velodynes
ddillenberger Oct 10, 2014
e1aa46a
cleanup debug line
ddillenberger Oct 11, 2014
f366bca
fixed missing header
bricerebsamen Jan 8, 2015
d48c203
parameters to set the udp port
Jan 8, 2015
89aa0a6
Merge pull request #39 from zooxco/multivelodyne
jack-oquin Sep 22, 2015
d65ef88
permit min_range settings below 0.9 meters (#60)
jack-oquin Oct 14, 2015
85228ed
restore VLP-16 min_range setting to 0.4 (#60)
jack-oquin Oct 14, 2015
70a8fae
VLP-16: skip badly formatted data packets (#62, #63)
jack-oquin Nov 1, 2015
f3b19fd
velodyne_driver: use port number for PCAP data (#66)
jack-oquin Nov 21, 2015
f75228e
Remove unused variable
jlblancoc Nov 29, 2015
455721b
Merge pull request #68 from jlblancoc/patch-1
jack-oquin Nov 29, 2015
0c235c1
Fix and add a few comments.
acschaefer Feb 8, 2016
597aa91
Fix data type error that distorts the point cloud.
acschaefer Feb 9, 2016
fd36398
Merge pull request #73 from fudger/master
jack-oquin Feb 9, 2016
3f6924e
resolve sign error
pomerlef Feb 11, 2016
3df0861
Merge branch 'master' of https://github.com/ros-drivers/velodyne
pomerlef Feb 11, 2016
03db2fd
Add *.user files to gitignore.
acschaefer Feb 17, 2016
796d139
Align console output of calibration data.
acschaefer Feb 17, 2016
acce5e1
Fix line that always indicates use of model VLP-16.
acschaefer Feb 18, 2016
2856180
Add a missing space.
acschaefer Feb 18, 2016
79c8d82
Merge pull request #77 from fudger/pretty_print
jack-oquin Feb 18, 2016
80a1494
Add docs to gitignore.
acschaefer Feb 19, 2016
26fface
Set up dynamic reconfiguration for transform_node.
acschaefer Feb 19, 2016
95b4691
Improve coding style.
acschaefer Feb 22, 2016
f7d0ce4
Resolve frame ID name using tf prefix.
acschaefer Feb 22, 2016
47df691
allow floats instead of ints in min/max_intensity
wjwwood Mar 9, 2016
ccb9a0b
allow horiz_offset_correction to be optional with 0 as default
wjwwood Mar 9, 2016
f896e22
Merge pull request #80 from ros-drivers/fix_yaml_import
jack-oquin Mar 12, 2016
bf1592c
add travis pr testing
wjwwood Mar 12, 2016
5b1eced
make a build failure stop the next steps
wjwwood Mar 12, 2016
0b82b20
fix the yaml-cpp 0.5 code paths
wjwwood Mar 12, 2016
f3f1fde
try to fixup travis-ci
wjwwood Mar 12, 2016
594d0be
fix test_results call
wjwwood Mar 12, 2016
3fc2d20
Merge pull request #82 from ros-drivers/fix_pr_80
jack-oquin Mar 12, 2016
71d6ec2
Merge pull request #76 from pomerlef/master
jack-oquin Mar 19, 2016
fbe603a
calibration: make max_intensity and min_intensity optional (#84)
jack-oquin Mar 20, 2016
c3e5178
calibration: add gtest for #84
jack-oquin Mar 21, 2016
9a5d583
calibration: read all intensities as float, then convert (#84)
jack-oquin Mar 21, 2016
8e58199
calibration: unit test case improvements (#84)
jack-oquin Mar 22, 2016
14d0241
prepare change history for coming Indigo release (#59)
jack-oquin Mar 25, 2016
b344cf0
Merge branch 'reconfigure_transform_node' of https://github.com/fudge…
jack-oquin Apr 12, 2016
196f273
velodyne_pointcloud: fix transform unit tests
jack-oquin Apr 12, 2016
76e5f85
velodyne_pointcloud: use recommended add_dependencies() CMake variabl…
jack-oquin Apr 12, 2016
c434f43
Merge branch 'fudger-reconfigure_transform_node'
jack-oquin Apr 12, 2016
893bdcb
velodyne_pointcloud: add dynamic reconfig update to change log (#78)
jack-oquin Apr 12, 2016
5e4a52e
velodyne_pointcloud: Fix compile warning "Wrong initialization order"
Tones29 Apr 20, 2016
094db69
velodyne_driver: Make input destructors virtual
Tones29 Apr 22, 2016
ed051a8
velodyne_driver: Add dynamic_reconfigure and time_offset correction
Tones29 Apr 22, 2016
bd05bf4
Merge pull request #89 from Tones29/feat_dynrec_driver
jack-oquin May 25, 2016
8ca4f47
update velodyne_driver package description to include all models
May 25, 2016
b8e8faa
Merge pull request #91 from chukcha2/master
jack-oquin May 25, 2016
00db43d
Modified velodyne_pointcloud/src/conversion/colors.cc to remove
Jun 2, 2016
252615c
Modified velodyne_point_cloud/src/lib/rawdata.cc to address warning
Jun 2, 2016
2887506
Merge pull request #92 from adasta/master
jack-oquin Jun 3, 2016
f2bfe50
merge current master (#94)
jack-oquin Jun 16, 2016
075cb76
fix g++ 5.3.1 compile errors (#94)
jack-oquin Jun 16, 2016
618a73a
Merge pull request #94 from ros-drivers/pcap_port
jack-oquin Jun 16, 2016
78fa227
update README for Kinetic (#93)
jack-oquin Jun 17, 2016
f85ab35
update change history
jack-oquin Jun 30, 2016
58040a0
updated VLP-16 packet rate from user manual.
Jul 1, 2016
2095ee3
Merge pull request #96 from priyankadey/master
jack-oquin Jul 3, 2016
374e19d
velodyne_driver: credit @priyankadey for VLP-16 bug fix (#96)
jack-oquin Jul 5, 2016
2495c8f
velodyne_driver/src/lib/input.cc : fix for device_ip filter
teosnare Aug 9, 2016
3a19dcc
Fix misleading typecasts.
fudger Aug 11, 2016
26c24ef
Add more options in launch files.
Aug 11, 2016
109a51f
Merge pull request #103 from fudger/patch-1
jack-oquin Aug 15, 2016
e3d7e74
Remove unused constants.
fudger Aug 16, 2016
0b03832
Rearranged alphabetically.
Aug 16, 2016
34d1dad
Merge pull request #104 from altrouge/launch_options
jack-oquin Aug 26, 2016
d8b0c2f
Merge pull request #105 from fudger/patch-1
jack-oquin Sep 20, 2016
611df63
Merge pull request #101 from teosnare/master
jack-oquin Oct 6, 2016
4d0d71f
add launch args to support multiple devices (#108)
jack-oquin Oct 8, 2016
ed6e94b
test multiple nodelet manager support (#108)
jack-oquin Oct 9, 2016
d678c87
Added velodyne_laserscan package and inserted into existing launch files
khallenbeck-dsi Dec 8, 2016
e6560cc
Added an interface to set up raw data processing from a locally defin…
tstoyanov Dec 20, 2016
e263b80
Merge pull request #111 from OrebroUniversity/master
jack-oquin Dec 20, 2016
3747e93
velodyne_pointcloud: remove incorrect catkin_package() DEPENDS option…
jack-oquin Apr 19, 2017
00f407e
Fixed bug. Laserscans now cover full 360 degrees.
volkandre Sep 28, 2017
cb8898d
Updated cut_at_specified_angle_feature with latest master version.
Sep 28, 2017
462c809
Add VLP16 Puck Hi-Res support
Sep 28, 2017
7b7be3c
Merge pull request #1 from volkandre/master
khallenbeck-dsi Sep 30, 2017
d6fce8b
Package.xml format version 2
khallenbeck-dsi Oct 12, 2017
345820e
Fixed validating PointCloud2 field types
khallenbeck-dsi Oct 12, 2017
269e83c
Added tests for velodyne_laserscan
khallenbeck-dsi Oct 12, 2017
76be2be
Merge pull request #127 from swri-robotics/add_vlp16_hires_support
Oct 18, 2017
cccc138
Update to use non deprecated pluginlib macro
khallenbeck-dsi Nov 1, 2017
78ee547
Merge pull request #129 from kmhallen/pluginlib_macro
Nov 6, 2017
f40555d
Merge remote-tracking branch 'ros-drivers/master'
robustify Nov 6, 2017
8e999eb
Merge pull request #110 from kmhallen/master
Nov 6, 2017
722b849
Updating change logs for release.
Nov 10, 2017
d17e252
Testing removing single quotes in changelog.
Nov 10, 2017
f8c6e82
Bumping version.
Nov 10, 2017
7fde5de
Updated branch from ros-drivers master and resolved conflicts.
Dec 4, 2017
4800414
Updated branch from ros-drivers/master and resolved conflicts.
Dec 4, 2017
bb8401b
Merge branch 'cut_at_specified_angle_feature' of https://github.com/v…
Dec 4, 2017
f2f168c
Fixed timestamp related bug found by @cfneuhaus, which was described …
Dec 4, 2017
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: 2 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -1,4 +1,6 @@
*.pyc
*.tar.gz
*~
*.user
doc
TAGS
33 changes: 33 additions & 0 deletions .travis.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
sudo: required
dist: trusty
# Force travis to use its minimal image with default Python settings
language: generic
compiler:
- gcc
env:
global:
- CATKIN_WS=~/catkin_ws
- CATKIN_WS_SRC=${CATKIN_WS}/src
matrix:
- CI_ROS_DISTRO="indigo"
- CI_ROS_DISTRO="jade"
install:
- sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu trusty main" > /etc/apt/sources.list.d/ros-latest.list'
- wget http://packages.ros.org/ros.key -O - | sudo apt-key add -
- sudo apt-get update -qq
- sudo apt-get install -qq -y python-rosdep
- sudo rosdep init
- rosdep update
# Use rosdep to install all dependencies (including ROS itself)
- rosdep install --from-paths ./ -i -y --rosdistro $CI_ROS_DISTRO
script:
- source /opt/ros/$CI_ROS_DISTRO/setup.bash
- mkdir -p $CATKIN_WS_SRC
- ln -s $TRAVIS_BUILD_DIR $CATKIN_WS_SRC
- cd $CATKIN_WS
# Build [and Install] packages, build tests, and run tests
- catkin_make_isolated --install --cmake-args -DCMAKE_BUILD_TYPE=Release &&
catkin_make_isolated --install --cmake-args -DCMAKE_BUILD_TYPE=Release --catkin-make-args tests &&
catkin_make_isolated --install --cmake-args -DCMAKE_BUILD_TYPE=Release --catkin-make-args run_tests
# Check results
- catkin_test_results ./build_isolated
7 changes: 4 additions & 3 deletions README.rst
Original file line number Diff line number Diff line change
Expand Up @@ -9,9 +9,10 @@ definition 3D LIDARs`_.
The master branch normally contains code being tested for the next
ROS release. It will not always work with every previous release.

The current ``master`` branch works with ROS Indigo and Hydro. It may
work with Groovy, but that is not guaranteed. To build for Fuerte
from source, check out the ``rosbuild`` branch instead of ``master``.
The current ``master`` branch works with ROS Kinetic, Jade, and
Indigo. It may work with Hydro and Groovy, but that has not been
tested recently. To build for Fuerte from source, check out the
``rosbuild`` branch instead of ``master``.

.. _ROS: http://www.ros.org
.. _Velodyne: http://www.ros.org/wiki/velodyne
Expand Down
7 changes: 7 additions & 0 deletions velodyne/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -1,6 +1,13 @@
Change history
==============

1.3.0 (2017-11-10)
------------------
* Merge pull request `#110 <https://github.com/ros-drivers/velodyne/issues/110>`_ from kmhallen/master
Added velodyne_laserscan package
* Added velodyne_laserscan package and inserted into existing launch files
* Contributors: Jack O'Quin, Joshua Whitley, Kevin Hallenbeck

1.2.0 (2014-08-06)
------------------

Expand Down
5 changes: 3 additions & 2 deletions velodyne/package.xml
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
<package>

<name>velodyne</name>
<version>1.2.0</version>
<version>1.3.0</version>
<description>
Basic ROS support for the Velodyne 3D LIDARs.
</description>
<maintainer email="jack.oquin@gmail.com">Jack O'Quin</maintainer>
<maintainer email="jwhitley@autonomoustuff.com">Josh Whitley</maintainer>
<author> Jack O'Quin</author>
<license>BSD</license>
<!--
Expand All @@ -18,6 +18,7 @@
<buildtool_depend>catkin</buildtool_depend>

<run_depend>velodyne_driver</run_depend>
<run_depend>velodyne_laserscan</run_depend>
<run_depend>velodyne_msgs</run_depend>
<run_depend>velodyne_pointcloud</run_depend>

Expand Down
50 changes: 48 additions & 2 deletions velodyne_driver/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -1,6 +1,53 @@
Change history
==============

1.3.0 (2017-11-10)
------------------
* Merge pull request `#129 <https://github.com/ros-drivers/velodyne/issues/129>`_ from kmhallen/pluginlib_macro
Modern pluginlib macro
* Update to use non deprecated pluginlib macro
* add launch args to support multiple devices (`#108 <https://github.com/ros-drivers/velodyne/issues/108>`_)
* Merge pull request `#101 <https://github.com/ros-drivers/velodyne/issues/101>`_ from teosnare/master
velodyne_driver/src/lib/input.cc : fix for device_ip filter
* Merge pull request `#104 <https://github.com/ros-drivers/velodyne/issues/104>`_ from altrouge/launch_options
Add more options in launch files.
* Rearranged alphabetically.
* Add more options in launch files.
- rpm, device_ip, port, read_once, read_fast, repeat_delay
* velodyne_driver/src/lib/input.cc : fix for device_ip filter
Fix for device_ip filter in InputSocket: initialization of devip\_ for correct ip filtering in InputSocket::getPacket.
* velodyne_driver: credit @priyankadey for VLP-16 bug fix (`#96 <https://github.com/ros-drivers/velodyne/issues/96>`_)
* Merge pull request `#96 <https://github.com/ros-drivers/velodyne/issues/96>`_ from priyankadey/master
updated VLP-16 packet rate from user manual.
* updated VLP-16 packet rate from user manual.
Also verified with sensor. It reduced overlap in the pointcloud
* update change history
* Merge pull request `#94 <https://github.com/ros-drivers/velodyne/issues/94>`_ from ros-drivers/pcap_port
velodyne_driver: use port number for PCAP data (`#46 <https://github.com/ros-drivers/velodyne/issues/46>`_, `#66 <https://github.com/ros-drivers/velodyne/issues/66>`_)
* fix g++ 5.3.1 compile errors (`#94 <https://github.com/ros-drivers/velodyne/issues/94>`_)
* merge current master (`#94 <https://github.com/ros-drivers/velodyne/issues/94>`_)
* Merge pull request `#91 <https://github.com/ros-drivers/velodyne/issues/91>`_ from chukcha2/master
update velodyne_driver package description to include all models
* update velodyne_driver package description to include all models
* Merge pull request `#89 <https://github.com/ros-drivers/velodyne/issues/89>`_ from Tones29/feat_dynrec_driver
Add dynamic latency configuration to velodyne_driver
* velodyne_driver: Add dynamic_reconfigure and time_offset correction
The value of time_offset is added to the calculated time stamp in live mode for each packet.
* velodyne_driver: Make input destructors virtual
* prepare change history for coming Indigo release (`#59 <https://github.com/ros-drivers/velodyne/issues/59>`_)
* velodyne_driver: use port number for PCAP data (`#66 <https://github.com/ros-drivers/velodyne/issues/66>`_)
* Merge pull request `#39 <https://github.com/ros-drivers/velodyne/issues/39>`_ from zooxco/multivelodyne
support for multiple velodynes
* Merge pull request `#44 <https://github.com/ros-drivers/velodyne/issues/44>`_ from SISegwayRmp/master
adding driver and pointcloud support for the VLP16
* adding the VLP16 test scripts and updating the CMakeLists to include the test file from http://download.ros.org/data/velodyne/vlp16.pcap
* adding support for the VLP16
* parameters to set the udp port
* fixed missing header
* cleanup debug line
* parameter and code added for working with multiple velodynes
* Contributors: Andreas Wachaja, Brice Rebsamen, Daniel Jartoux, Denis Dillenberger, Gabor Meszaros, Ilya, Jack O'Quin, Joshua Whitley, Kevin Hallenbeck, Matteo Murtas, Micho Radovnikovich, Priyanka Dey, William Woodall, jack.oquin, junior, phussey

1.2.0 (2014-08-06)
------------------
* Fixed bug in diagnostic rate for driver (`#16
Expand All @@ -16,8 +63,7 @@ Change history
1.1.1 (2013-07-30)
------------------

* Add support for HDL-64E S2 and S2.1 models, which were not working
before (`#11`_), thanks to Gabor Meszaros (`#12`_).
* Add support for HDL-64E S2 and S2.1 models, which were not working before (`#11`_), thanks to Gabor Meszaros (`#12`_).
* Add additional parameters to launch files (`#14`_).

1.1.0 (2013-07-16)
Expand Down
4 changes: 4 additions & 0 deletions velodyne_driver/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@ project(velodyne_driver)

set(${PROJECT_NAME}_CATKIN_DEPS
diagnostic_updater
dynamic_reconfigure
nodelet
roscpp
tf
Expand All @@ -18,6 +19,9 @@ set(libpcap_LIBRARIES -lpcap)

include_directories(include ${Boost_INCLUDE_DIR} ${catkin_INCLUDE_DIRS})

# Generate dynamic_reconfigure server
generate_dynamic_reconfigure_options(cfg/VelodyneNode.cfg)

# objects needed by other ROS packages that depend on this one
catkin_package(CATKIN_DEPENDS ${${PROJECT_NAME}_CATKIN_DEPS}
INCLUDE_DIRS include
Expand Down
14 changes: 14 additions & 0 deletions velodyne_driver/cfg/VelodyneNode.cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
#!/usr/bin/env python
PACKAGE = "velodyne_driver"
NODE_NAME = "velodyne_node"
PARAMS_NAME = "VelodyneNode"

from math import pi
from dynamic_reconfigure.parameter_generator_catkin import *

gen = ParameterGenerator()

gen.add("time_offset", double_t, 0, "A manually calibrated offset (in seconds) to add to the timestamp before publication of a message.",
0.0, -1.0, 1.0)

exit(gen.generate(PACKAGE, NODE_NAME, PARAMS_NAME))
45 changes: 30 additions & 15 deletions velodyne_driver/include/velodyne_driver/input.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@
*
* Copyright (C) 2007 Austin Robot Technology, Yaxin Liu, Patrick Beeson
* Copyright (C) 2009, 2010 Austin Robot Technology, Jack O'Quin
* Copyright (C) 2015, Jack O'Quin
*
* License: Modified BSD Software License Agreement
*
Expand All @@ -18,7 +19,7 @@
*
* Classes:
*
* velodyne::Input -- pure virtual base class to access the data
* velodyne::Input -- base class for accessing the data
* independently of its source
*
* velodyne::InputSocket -- derived class reads live data from the
Expand All @@ -34,19 +35,22 @@
#include <unistd.h>
#include <stdio.h>
#include <pcap.h>
#include <netinet/in.h>

#include <ros/ros.h>
#include <velodyne_msgs/VelodynePacket.h>

namespace velodyne_driver
{
static uint16_t UDP_PORT_NUMBER = 2368;
static uint16_t DATA_PORT_NUMBER = 2368; // default data port
static uint16_t POSITION_PORT_NUMBER = 8308; // default position port

/** @brief Pure virtual Velodyne input base class */
/** @brief Velodyne input base class */
class Input
{
public:
Input() {}
Input(ros::NodeHandle private_nh, uint16_t port);
virtual ~Input() {}

/** @brief Read one Velodyne packet.
*
Expand All @@ -56,22 +60,31 @@ namespace velodyne_driver
* -1 if end of file
* > 0 if incomplete packet (is this possible?)
*/
virtual int getPacket(velodyne_msgs::VelodynePacket *pkt) = 0;
virtual int getPacket(velodyne_msgs::VelodynePacket *pkt,
const double time_offset) = 0;

protected:
ros::NodeHandle private_nh_;
uint16_t port_;
std::string devip_str_;
};

/** @brief Live Velodyne input from socket. */
class InputSocket: public Input
{
public:
InputSocket(ros::NodeHandle private_nh,
uint16_t udp_port = UDP_PORT_NUMBER);
~InputSocket();

virtual int getPacket(velodyne_msgs::VelodynePacket *pkt);
uint16_t port = DATA_PORT_NUMBER);
virtual ~InputSocket();

virtual int getPacket(velodyne_msgs::VelodynePacket *pkt,
const double time_offset);
void setDeviceIP( const std::string& ip );
private:

private:
int sockfd_;
in_addr devip_;
};


Expand All @@ -84,26 +97,28 @@ namespace velodyne_driver
{
public:
InputPCAP(ros::NodeHandle private_nh,
double packet_rate,
uint16_t port = DATA_PORT_NUMBER,
double packet_rate = 0.0,
std::string filename="",
bool read_once=false,
bool read_fast=false,
double repeat_delay=0.0);
~InputPCAP();
virtual ~InputPCAP();

virtual int getPacket(velodyne_msgs::VelodynePacket *pkt);
virtual int getPacket(velodyne_msgs::VelodynePacket *pkt,
const double time_offset);
void setDeviceIP( const std::string& ip );

private:

ros::Rate packet_rate_;
std::string filename_;
FILE *fp_;
pcap_t *pcap_;
bpf_program pcap_packet_filter_;
char errbuf_[PCAP_ERRBUF_SIZE];
bool empty_;
bool read_once_;
bool read_fast_;
double repeat_delay_;
ros::Rate packet_rate_;
};

} // velodyne_driver namespace
Expand Down
32 changes: 19 additions & 13 deletions velodyne_driver/launch/nodelet_manager.launch
Original file line number Diff line number Diff line change
@@ -1,30 +1,36 @@
<!-- -*- mode: XML -*- -->
<!-- start velodyne_driver/DriverNodelet in a nodelet manager

$Id$
-->
<!-- start velodyne_driver/DriverNodelet in a nodelet manager -->

<launch>

<!-- start nodelet manager and load driver nodelet -->
<node pkg="nodelet" type="nodelet" name="velodyne_nodelet_manager"
args="manager" />
<arg name="device_ip" default="" />
<arg name="frame_id" default="velodyne" />
<arg name="manager" default="$(arg frame_id)_nodelet_manager" />
<arg name="model" default="64E" />
<arg name="pcap" default="" />
<arg name="read_once" default="false" />
<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="frame_id" default="velodyne" />
<node pkg="nodelet" type="nodelet" name="driver_nodelet"
args="load velodyne_driver/DriverNodelet velodyne_nodelet_manager" >
<arg name="cut_angle" default="-0.01" />

<!-- start nodelet manager -->
<node pkg="nodelet" type="nodelet" name="$(arg manager)" args="manager" />

<!-- load driver nodelet into it -->
<node pkg="nodelet" type="nodelet" name="$(arg manager)_driver"
args="load velodyne_driver/DriverNodelet $(arg manager)" >
<param name="device_ip" value="$(arg device_ip)" />
<param name="frame_id" value="$(arg frame_id)"/>
<param name="model" value="$(arg model)"/>
<param name="pcap" value="$(arg pcap)"/>
<param name="read_once" value="$(arg read_once)"/>
<param name="port" value="$(arg port)" />
<param name="read_fast" value="$(arg read_fast)"/>
<param name="read_once" value="$(arg read_once)"/>
<param name="repeat_delay" value="$(arg repeat_delay)"/>
<param name="rpm" value="$(arg rpm)"/>
<param name="frame_id" value="$(arg frame_id)"/>
<param name="cut_angle" value="$(arg cut_angle)"/>
</node>

</launch>
9 changes: 6 additions & 3 deletions velodyne_driver/package.xml
Original file line number Diff line number Diff line change
@@ -1,11 +1,12 @@
<package>

<name>velodyne_driver</name>
<version>1.2.0</version>
<version>1.3.0</version>
<description>
ROS device driver for Velodyne HDL-64E, and HDL-32 LIDARs.
ROS device driver for Velodyne 3D LIDARs.
</description>
<maintainer email="jack.oquin@gmail.com">Jack O'Quin</maintainer>
<maintainer email="jwhitley@autonomoustuff.com">Josh Whitley</maintainer>
<maintainer email="brice.rebsamen@gmail.com">Brice Rebsamen</maintainer>
<author> Jack O'Quin</author>
<author>Patrick Beeson</author>
<author>Michael Quinlan</author>
Expand All @@ -19,6 +20,7 @@
<buildtool_depend>catkin</buildtool_depend>

<build_depend>diagnostic_updater</build_depend>
<build_depend>dynamic_reconfigure</build_depend>
<build_depend>libpcap</build_depend>
<build_depend>nodelet</build_depend>
<build_depend>pluginlib</build_depend>
Expand All @@ -31,6 +33,7 @@
<build_depend>rostest</build_depend>

<run_depend>diagnostic_updater</run_depend>
<run_depend>dynamic_reconfigure</run_depend>
<run_depend>libpcap</run_depend>
<run_depend>nodelet</run_depend>
<run_depend>pluginlib</run_depend>
Expand Down
2 changes: 2 additions & 0 deletions velodyne_driver/src/driver/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
# build the driver node
add_executable(velodyne_node velodyne_node.cc driver.cc)
add_dependencies(velodyne_node velodyne_driver_gencfg)
target_link_libraries(velodyne_node
velodyne_input
${catkin_LIBRARIES}
Expand All @@ -8,6 +9,7 @@ target_link_libraries(velodyne_node

# build the nodelet version
add_library(driver_nodelet nodelet.cc driver.cc)
add_dependencies(driver_nodelet velodyne_driver_gencfg)
target_link_libraries(driver_nodelet
velodyne_input
${catkin_LIBRARIES}
Expand Down
Loading