Skip to content

Commit

Permalink
ci(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Mar 12, 2022
1 parent 91e15ab commit 94a1884
Show file tree
Hide file tree
Showing 70 changed files with 8,491 additions and 3,682 deletions.
4 changes: 2 additions & 2 deletions COPYING
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ Modified BSD License:
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions
are met:

* Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.

Expand All @@ -26,7 +26,7 @@ Modified BSD License:
Austin Robot Technology, nor the names of other contributors may
be used to endorse or promote products derived from this
software without specific prior written permission.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
Expand Down
3 changes: 2 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
@@ -1,10 +1,11 @@
Repository for VelodyneLiDAR VLS sensors (It currently supports VLS-128).

The code is highly leveraged from https://github.com/ros-drivers/velodyne.
The code is highly leveraged from <https://github.com/ros-drivers/velodyne>.

This code is only tested in ROS Kinetic.

Compile instruction:

```
catkin_make -DCMAKE_BUILD=Release
```
7 changes: 4 additions & 3 deletions bag_to_pcap/scripts/bag_to_pcap.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,11 @@
#!/usr/bin/env python
import binascii
import signal
import sys

import rospy
from velodyne_msgs.msg import VelodyneScan

import signal
import binascii
from velodyne_msgs.msg import VelodyneScan

#Global header for pcap 2.4
global_header = 'd4c3b2a10200040000000000000000000000010001000000' # 24 bytes = 48 characters.
Expand Down
172 changes: 83 additions & 89 deletions velodyne_driver/include/velodyne_driver/input.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,100 +29,94 @@
* from a PCAP dump file
*/

#ifndef __VELODYNE_INPUT_H
#define __VELODYNE_INPUT_H

#include <unistd.h>
#include <stdio.h>
#include <pcap.h>
#include <netinet/in.h>
#ifndef VELODYNE_DRIVER__INPUT_H_
#define VELODYNE_DRIVER__INPUT_H_

#include <rclcpp/rclcpp.hpp>

#include <velodyne_msgs/msg/velodyne_packet.hpp>

#include <netinet/in.h>
#include <pcap.h>
#include <stdio.h>
#include <unistd.h>

namespace velodyne_driver
{
static constexpr uint16_t DATA_PORT_NUMBER = 2368; // default data port
static constexpr uint16_t POSITION_PORT_NUMBER = 8308; // default position port
static constexpr uint16_t TIMESTAMP_BYTE = 1200; // timestamp byte position in data packet
static constexpr uint16_t BLOCK_LENGTH = 42; // length of each data block in bytes

/** @brief Velodyne input base class */
class Input
{
public:
Input(rclcpp::Node * node_ptr, uint16_t port);
virtual ~Input() {}

/** @brief Read one Velodyne packet.
*
* @param pkt points to VelodynePacket message
*
* @returns 0 if successful,
* -1 if end of file
* > 0 if incomplete packet (is this possible?)
*/
virtual int getPacket(velodyne_msgs::msg::VelodynePacket *pkt,
const double time_offset) = 0;

protected:
rclcpp::Node * node_ptr_;
uint16_t port_;
std::string devip_str_;
bool sensor_timestamp_;
};

/** @brief Live Velodyne input from socket. */
class InputSocket: public Input
{
public:
InputSocket(rclcpp::Node * node_ptr,
uint16_t port = DATA_PORT_NUMBER);
virtual ~InputSocket();

virtual int getPacket(velodyne_msgs::msg::VelodynePacket *pkt,
const double time_offset);

void setDeviceIP( const std::string& ip );

private:
int sockfd_;
in_addr devip_;
};


/** @brief Velodyne input from PCAP dump file.
static constexpr uint16_t DATA_PORT_NUMBER = 2368; // default data port
static constexpr uint16_t POSITION_PORT_NUMBER = 8308; // default position port
static constexpr uint16_t TIMESTAMP_BYTE = 1200; // timestamp byte position in data packet
static constexpr uint16_t BLOCK_LENGTH = 42; // length of each data block in bytes

/** @brief Velodyne input base class */
class Input
{
public:
Input(rclcpp::Node * node_ptr, uint16_t port);
virtual ~Input() {}

/** @brief Read one Velodyne packet.
*
* @param pkt points to VelodynePacket message
*
* Dump files can be grabbed by libpcap, Velodyne's DSR software,
* ethereal, wireshark, tcpdump, or the \ref vdump_command.
* @returns 0 if successful,
* -1 if end of file
* > 0 if incomplete packet (is this possible?)
*/
class InputPCAP: public Input
{
public:
InputPCAP(rclcpp::Node * node_ptr,
uint16_t port = DATA_PORT_NUMBER,
std::string filename="",
bool read_once=false,
bool read_fast=false,
double repeat_delay=0.0);
virtual ~InputPCAP();

virtual int getPacket(velodyne_msgs::msg::VelodynePacket *pkt,
const double time_offset);
void setDeviceIP( const std::string& ip );
private:
rclcpp::Time last_packet_receive_time_;
rclcpp::Time last_packet_stamp_;
std::string filename_;
pcap_t *pcap_;
bpf_program pcap_packet_filter_;
char errbuf_[PCAP_ERRBUF_SIZE];
bool empty_;
bool read_once_;
bool read_fast_;
double repeat_delay_;
};

} // velodyne_driver namespace

#endif // __VELODYNE_INPUT_H
virtual int getPacket(velodyne_msgs::msg::VelodynePacket * pkt, const double time_offset) = 0;

protected:
rclcpp::Node * node_ptr_;
uint16_t port_;
std::string devip_str_;
bool sensor_timestamp_;
};

/** @brief Live Velodyne input from socket. */
class InputSocket : public Input
{
public:
InputSocket(rclcpp::Node * node_ptr, uint16_t port = DATA_PORT_NUMBER);
virtual ~InputSocket();

virtual int getPacket(velodyne_msgs::msg::VelodynePacket * pkt, const double time_offset);

void setDeviceIP(const std::string & ip);

private:
int sockfd_;
in_addr devip_;
};

/** @brief Velodyne input from PCAP dump file.
*
* Dump files can be grabbed by libpcap, Velodyne's DSR software,
* ethereal, wireshark, tcpdump, or the \ref vdump_command.
*/
class InputPCAP : public Input
{
public:
InputPCAP(
rclcpp::Node * node_ptr, uint16_t port = DATA_PORT_NUMBER, std::string filename = "",
bool read_once = false, bool read_fast = false, double repeat_delay = 0.0);
virtual ~InputPCAP();

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

private:
rclcpp::Time last_packet_receive_time_;
rclcpp::Time last_packet_stamp_;
std::string filename_;
pcap_t * pcap_;
bpf_program pcap_packet_filter_;
char errbuf_[PCAP_ERRBUF_SIZE];
bool empty_;
bool read_once_;
bool read_fast_;
double repeat_delay_;
};

} // namespace velodyne_driver

#endif // VELODYNE_DRIVER__INPUT_H_
47 changes: 16 additions & 31 deletions velodyne_driver/include/velodyne_driver/ring_sequence.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,41 +14,26 @@
* \author Jack O'Quin
*/


#ifndef __VELODYNE_RING_SEQUENCE_H
#define __VELODYNE_RING_SEQUENCE_H
#ifndef VELODYNE_DRIVER__RING_SEQUENCE_H_
#define VELODYNE_DRIVER__RING_SEQUENCE_H_

namespace velodyne
{
/// number of lasers
const int N_LASERS = 64;
/// number of lasers
const int N_LASERS = 64;

/// ring sequence for device laser numbers
const int LASER_SEQUENCE[N_LASERS] =
{
6, 7, 10, 11, 0, 1, 4, 5,
8, 9, 14, 15, 18, 19, 22, 23,
12, 13, 16, 17, 20, 21, 26, 27,
30, 31, 2, 3, 24, 25, 28, 29,
38, 39, 42, 43, 32, 33, 36, 37,
40, 41, 46, 47, 50, 51, 54, 55,
44, 45, 48, 49, 52, 53, 58, 59,
62, 63, 34, 35, 56, 57, 60, 61
};
/// ring sequence for device laser numbers
const int LASER_SEQUENCE[N_LASERS] = {
6, 7, 10, 11, 0, 1, 4, 5, 8, 9, 14, 15, 18, 19, 22, 23, 12, 13, 16, 17, 20, 21,
26, 27, 30, 31, 2, 3, 24, 25, 28, 29, 38, 39, 42, 43, 32, 33, 36, 37, 40, 41, 46, 47,
50, 51, 54, 55, 44, 45, 48, 49, 52, 53, 58, 59, 62, 63, 34, 35, 56, 57, 60, 61};

/// convert laser number to ring sequence (inverse of LASER_SEQUENCE)
const int LASER_RING[N_LASERS] =
{
4, 5, 26, 27, 6, 7, 0, 1,
8, 9, 2, 3, 16, 17, 10, 11,
18, 19, 12, 13, 20, 21, 14, 15,
28, 29, 22, 23, 30, 31, 24, 25,
36, 37, 58, 59, 38, 39, 32, 33,
40, 41, 34, 35, 48, 49, 42, 43,
50, 51, 44, 45, 52, 53, 46, 47,
60, 61, 54, 55, 62, 63, 56, 57
};
/// convert laser number to ring sequence (inverse of LASER_SEQUENCE)
const int LASER_RING[N_LASERS] = {4, 5, 26, 27, 6, 7, 0, 1, 8, 9, 2, 3, 16, 17, 10, 11,
18, 19, 12, 13, 20, 21, 14, 15, 28, 29, 22, 23, 30, 31, 24, 25,
36, 37, 58, 59, 38, 39, 32, 33, 40, 41, 34, 35, 48, 49, 42, 43,
50, 51, 44, 45, 52, 53, 46, 47, 60, 61, 54, 55, 62, 63, 56, 57};

} // velodyne namespace
} // namespace velodyne

#endif // __VELODYNE_RING_SEQUENCE_H
#endif // VELODYNE_DRIVER__RING_SEQUENCE_H_
20 changes: 7 additions & 13 deletions velodyne_driver/include/velodyne_driver/time_conversion.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,8 +45,8 @@
* @return timestamp from velodyne, possibly shifted by 1 hour if the function arguments
* disagree by more than a half-hour.
*/
inline
rclcpp::Time resolveHourAmbiguity(const rclcpp::Time & stamp, const rclcpp::Time & nominal_stamp)
inline rclcpp::Time resolveHourAmbiguity(
const rclcpp::Time & stamp, const rclcpp::Time & nominal_stamp)
{
const int HALFHOUR_TO_SEC = 1800;
rclcpp::Time retval = stamp;
Expand All @@ -62,23 +62,17 @@ rclcpp::Time resolveHourAmbiguity(const rclcpp::Time & stamp, const rclcpp::Time
return retval;
}

inline
rclcpp::Time rosTimeFromGpsTimestamp(rclcpp::Time & time_nom, const uint8_t * const data)
inline rclcpp::Time rosTimeFromGpsTimestamp(rclcpp::Time & time_nom, const uint8_t * const data)
{
// time_nom is used to recover the hour
const int HOUR_TO_SEC = 3600;
// time for each packet is a 4 byte uint
// It is the number of microseconds from the top of the hour
uint32_t usecs =
static_cast<uint32_t>(
((uint32_t) data[3]) << 24 |
((uint32_t) data[2] ) << 16 |
((uint32_t) data[1] ) << 8 |
((uint32_t) data[0] ));
uint32_t usecs = static_cast<uint32_t>(
((uint32_t)data[3]) << 24 | ((uint32_t)data[2]) << 16 | ((uint32_t)data[1]) << 8 |
((uint32_t)data[0]));
uint32_t cur_hour = time_nom.nanoseconds() / 1000000000 / HOUR_TO_SEC;
auto stamp = rclcpp::Time(
(cur_hour * HOUR_TO_SEC) + (usecs / 1000000),
(usecs % 1000000) * 1000);
auto stamp = rclcpp::Time((cur_hour * HOUR_TO_SEC) + (usecs / 1000000), (usecs % 1000000) * 1000);
return resolveHourAmbiguity(stamp, time_nom);
}

Expand Down
35 changes: 17 additions & 18 deletions velodyne_driver/launch/nodelet_manager.launch.xml
Original file line number Diff line number Diff line change
@@ -1,39 +1,38 @@
<!-- -*- mode: XML -*- -->
<!-- start velodyne_driver/DriverNodelet in a nodelet manager -->

<launch>

<arg name="device_ip" default="" />
<arg name="frame_id" default="velodyne" />
<arg name="manager" default="$(var frame_id)_nodelet_manager" />
<arg name="model" default="64E" />
<arg name="pcap" default="" />
<arg name="port" default="2368" />
<arg name="npackets" default="" />
<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="scan_phase" default="0.0" />
<arg name="sensor_timestamp" default="false" />
<arg name="device_ip" default=""/>
<arg name="frame_id" default="velodyne"/>
<arg name="manager" default="$(var frame_id)_nodelet_manager"/>
<arg name="model" default="64E"/>
<arg name="pcap" default=""/>
<arg name="port" default="2368"/>
<arg name="npackets" default=""/>
<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="scan_phase" default="0.0"/>
<arg name="sensor_timestamp" default="false"/>

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

<!-- load driver nodelet into it -->
<node pkg="velodyne_driver" exec="velodyne_driver_node" name="$(var manager)_driver">
<param name="device_ip" value="$(var device_ip)" />
<param name="device_ip" value="$(var device_ip)"/>
<param name="frame_id" value="$(var frame_id)"/>
<param name="model" value="$(var model)"/>
<param name="pcap" value="$(var pcap)"/>
<param name="port" value="$(var port)" />
<param name="npackets" value="$(var npackets)" />
<param name="port" value="$(var port)"/>
<param name="npackets" value="$(var npackets)"/>
<param name="read_fast" value="$(var read_fast)"/>
<param name="read_once" value="$(var read_once)"/>
<param name="repeat_delay" value="$(var repeat_delay)"/>
<param name="rpm" value="$(var rpm)"/>
<param name="scan_phase" value="$(var scan_phase)"/>
<param name="sensor_timestamp" value="$(var sensor_timestamp)" />
<param name="sensor_timestamp" value="$(var sensor_timestamp)"/>
</node>

</launch>
2 changes: 1 addition & 1 deletion velodyne_driver/mainpage.dox
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@

\htmlinclude manifest.html

ROS device driver for Velodyne 3D LIDARs.
ROS device driver for Velodyne 3D LIDARs.

\section read Velodyne device driver

Expand Down
Loading

0 comments on commit 94a1884

Please sign in to comment.