Skip to content

Commit

Permalink
Fix part of pointed out in first review
Browse files Browse the repository at this point in the history
Fix part of pointed out in first review.
This commit will be squashed when review is over.
  • Loading branch information
UnaNancyOwen committed Sep 12, 2017
1 parent 9da5ebc commit 8c6145e
Show file tree
Hide file tree
Showing 2 changed files with 15 additions and 15 deletions.
12 changes: 6 additions & 6 deletions io/include/pcl/io/vlp_grabber.h
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ namespace pcl
* \param[in] port UDP Port that should be used to listen for VLP packets
*/
VLPGrabber (const boost::asio::ip::address& ipAddress,
const unsigned short port);
const uint16_t port);

/** \brief virtual Destructor inherited from the Grabber interface. It never throws. */
virtual
Expand All @@ -80,17 +80,17 @@ namespace pcl
virtual std::string
getName () const;

/** \brief Allows one to customize the colors used for each of the lasers.
*/
/** \brief Allows one to customize the colors used for each of the lasers. */
void
setLaserColorRGB (const pcl::RGB& color,
unsigned int laserNumber);
uint8_t laserNumber);

protected:
static const int VLP_MAX_NUM_LASERS = 16;
static const int VLP_DUAL_MODE = 0x39;
static const uint8_t VLP_MAX_NUM_LASERS = 16;
static const uint8_t VLP_DUAL_MODE = 0x39;

private:
/** \brief Lookup table of Colors for coloring each of the lasers. */
pcl::RGB laser_rgb_mapping_[VLP_MAX_NUM_LASERS];

virtual void
Expand Down
18 changes: 9 additions & 9 deletions io/src/vlp_grabber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ pcl::VLPGrabber::VLPGrabber (const std::string& pcapFile) :

/////////////////////////////////////////////////////////////////////////////
pcl::VLPGrabber::VLPGrabber (const boost::asio::ip::address& ipAddress,
const unsigned short int port) :
const uint16_t port) :
HDLGrabber (ipAddress, port)
{
initializeLaserMapping ();
Expand All @@ -66,7 +66,7 @@ pcl::VLPGrabber::~VLPGrabber () throw ()
void
pcl::VLPGrabber::initializeLaserMapping ()
{
for (int i = 0; i < 8; i++)
for (uint8_t i = 0; i < VLP_MAX_NUM_LASERS / 2u; i++)
{
laser_rgb_mapping_[i * 2].b = static_cast<uint8_t> (i * 6 + 64);
laser_rgb_mapping_[i * 2 + 1].b = static_cast<uint8_t> ((i + 16) * 6 + 64);
Expand All @@ -78,7 +78,7 @@ void
pcl::VLPGrabber::loadVLP16Corrections ()
{
double vlp16_vertical_corrections[] = { -15, 1, -13, 3, -11, 5, -9, 7, -7, 9, -5, 11, -3, 13, -1, 15 };
for (int i = 0; i < VLP_MAX_NUM_LASERS; i++)
for (uint8_t i = 0; i < VLP_MAX_NUM_LASERS; i++)
{
HDLGrabber::laser_corrections_[i].azimuthCorrection = 0.0;
HDLGrabber::laser_corrections_[i].distanceCorrection = 0.0;
Expand Down Expand Up @@ -114,7 +114,7 @@ pcl::VLPGrabber::toPointClouds (HDLDataPacket *dataPacket)

double interpolated_azimuth_delta;

int index = 1;
uint8_t index = 1;
if (dataPacket->mode == VLP_DUAL_MODE)
{
index = 2;
Expand All @@ -128,11 +128,11 @@ pcl::VLPGrabber::toPointClouds (HDLDataPacket *dataPacket)
interpolated_azimuth_delta = (dataPacket->firingData[index].rotationalPosition - dataPacket->firingData[0].rotationalPosition) / 2.0;
}

for (int i = 0; i < HDL_FIRING_PER_PKT; ++i)
for (uint8_t i = 0; i < HDL_FIRING_PER_PKT; ++i)
{
HDLFiringData firing_data = dataPacket->firingData[i];

for (int j = 0; j < HDL_LASER_PER_FIRING; j++)
for (uint8_t j = 0; j < HDL_LASER_PER_FIRING; j++)
{
double current_azimuth = firing_data.rotationalPosition;
if (j >= VLP_MAX_NUM_LASERS)
Expand Down Expand Up @@ -226,10 +226,10 @@ pcl::VLPGrabber::getName () const
/////////////////////////////////////////////////////////////////////////////
void
pcl::VLPGrabber::setLaserColorRGB (const pcl::RGB& color,
unsigned int laserNumber)
uint8_t laserNumber)
{
if (laserNumber >= (unsigned int) VLP_MAX_NUM_LASERS)
return;
if (laserNumber >= VLP_MAX_NUM_LASERS)
return;

laser_rgb_mapping_[laserNumber] = color;
}
Expand Down

0 comments on commit 8c6145e

Please sign in to comment.