MRPT
1.9.9
|
#include "obs-precomp.h"
#include <mrpt/containers/stl_containers_utils.h>
#include <mrpt/core/round.h>
#include <mrpt/obs/CObservationVelodyneScan.h>
#include <mrpt/poses/CPose3DInterpolator.h>
#include <mrpt/serialization/CArchive.h>
#include <mrpt/serialization/stl_serialization.h>
#include <iostream>
Go to the source code of this file.
Typedefs | |
using | Velo = mrpt::obs::CObservationVelodyneScan |
Functions | |
static double | HDL32AdjustTimeStamp (int firingblock, int dsr) |
[us] More... | |
static double | VLP16AdjustTimeStamp (int firingblock, int dsr, int firingwithinblock) |
[us] More... | |
static void | velodyne_scan_to_pointcloud (const Velo &scan, const Velo::TGeneratePointCloudParameters ¶ms, Velo::PointCloudStorageWrapper &out_pc) |
Variables | |
static CSinCosLookUpTableFor2DScans | velodyne_sincos_tables |
const float | VLP16_BLOCK_TDURATION = 110.592f |
const float | VLP16_DSR_TOFFSET = 2.304f |
const float | VLP16_FIRING_TOFFSET = 55.296f |
const double | HDR32_DSR_TOFFSET = 1.152 |
const double | HDR32_FIRING_TOFFSET = 46.08 |
Definition at line 24 of file CObservationVelodyneScan.cpp.
|
static |
[us]
Definition at line 126 of file CObservationVelodyneScan.cpp.
References HDR32_DSR_TOFFSET, and HDR32_FIRING_TOFFSET.
Referenced by velodyne_scan_to_pointcloud().
|
static |
Definition at line 138 of file CObservationVelodyneScan.cpp.
References mrpt::obs::CObservationVelodyneScan::PointCloudStorageWrapper::add_point(), mrpt::obs::T2DScanProperties::aperture, ASSERT_BELOW_, mrpt::obs::CObservationVelodyneScan::TVelodyneRawPacket::blocks, mrpt::obs::CObservationVelodyneScan::BLOCKS_PER_PACKET, mrpt::obs::CObservationVelodyneScan::calibration, mrpt::obs::CSinCosLookUpTableFor2DScans::TSinCosValues::ccos, mrpt::obs::VelodyneCalibration::PerLaserCalib::cosVertCorrection, mrpt::obs::CSinCosLookUpTableFor2DScans::TSinCosValues::csin, mrpt::d2f(), mrpt::obs::CObservationVelodyneScan::laser_return_t::distance(), mrpt::math::distance(), mrpt::obs::CObservationVelodyneScan::DISTANCE_RESOLUTION, mrpt::obs::VelodyneCalibration::PerLaserCalib::distanceCorrection, mrpt::obs::CSinCosLookUpTableFor2DScans::getSinCosForScan(), mrpt::obs::CObservationVelodyneScan::TVelodyneRawPacket::gps_timestamp(), HDL32AdjustTimeStamp(), mrpt::obs::CObservationVelodyneScan::raw_block_t::header(), mrpt::obs::VelodyneCalibration::PerLaserCalib::horizontalOffsetCorrection, mrpt::obs::CObservationVelodyneScan::laser_return_t::intensity(), mrpt::obs::VelodyneCalibration::laser_corrections, mrpt::obs::CObservationVelodyneScan::TVelodyneRawPacket::laser_return_mode, mrpt::obs::CObservationVelodyneScan::raw_block_t::laser_returns, mrpt::obs::CObservationVelodyneScan::LOWER_BANK, M_PI, mrpt::obs::CObservationVelodyneScan::maxRange, mrpt::obs::CObservationVelodyneScan::minRange, mrpt::obs::T2DScanProperties::nRays, params, mrpt::obs::CObservationVelodyneScan::PointCloudStorageWrapper::reserve(), mrpt::obs::CObservationVelodyneScan::PointCloudStorageWrapper::resizeLaserCount(), mrpt::obs::CObservationVelodyneScan::RETMODE_DUAL, mrpt::obs::T2DScanProperties::rightToLeft, mrpt::obs::CObservationVelodyneScan::raw_block_t::rotation(), mrpt::obs::CObservationVelodyneScan::ROTATION_MAX_UNITS, mrpt::round(), mrpt::obs::CObservationVelodyneScan::scan_packets, mrpt::obs::CObservationVelodyneScan::SCANS_PER_BLOCK, mrpt::obs::CObservationVelodyneScan::SCANS_PER_FIRING, mrpt::obs::VelodyneCalibration::PerLaserCalib::sinVertCorrection, THROW_EXCEPTION, mrpt::obs::CObservation::timestamp, mrpt::system::timestampAdd(), mrpt::obs::CObservationVelodyneScan::UPPER_BANK, velodyne_sincos_tables, mrpt::obs::VelodyneCalibration::PerLaserCalib::verticalOffsetCorrection, VLP16AdjustTimeStamp(), mrpt::math::TPoint3D_data< T >::x, mrpt::math::TPoint3D_data< T >::y, and mrpt::math::TPoint3D_data< T >::z.
Referenced by mrpt::obs::CObservationVelodyneScan::generatePointCloud(), and mrpt::obs::CObservationVelodyneScan::generatePointCloudAlongSE3Trajectory().
|
static |
[us]
Definition at line 131 of file CObservationVelodyneScan.cpp.
References VLP16_BLOCK_TDURATION, VLP16_DSR_TOFFSET, and VLP16_FIRING_TOFFSET.
Referenced by velodyne_scan_to_pointcloud().
const double HDR32_DSR_TOFFSET = 1.152 |
Definition at line 35 of file CObservationVelodyneScan.cpp.
Referenced by HDL32AdjustTimeStamp().
const double HDR32_FIRING_TOFFSET = 46.08 |
Definition at line 36 of file CObservationVelodyneScan.cpp.
Referenced by HDL32AdjustTimeStamp().
|
static |
Definition at line 29 of file CObservationVelodyneScan.cpp.
Referenced by velodyne_scan_to_pointcloud().
const float VLP16_BLOCK_TDURATION = 110.592f |
Definition at line 31 of file CObservationVelodyneScan.cpp.
Referenced by VLP16AdjustTimeStamp().
const float VLP16_DSR_TOFFSET = 2.304f |
Definition at line 32 of file CObservationVelodyneScan.cpp.
Referenced by VLP16AdjustTimeStamp().
const float VLP16_FIRING_TOFFSET = 55.296f |
Definition at line 33 of file CObservationVelodyneScan.cpp.
Referenced by VLP16AdjustTimeStamp().
Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: c7a3bec24 Sun Mar 29 18:33:13 2020 +0200 at dom mar 29 18:50:38 CEST 2020 |