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

Make lidar measurement model class #195

Merged
merged 31 commits into from
Sep 25, 2018
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
31 commits
Select commit Hold shift + click to select a range
e619675
Make lidar measurement model class
at-wat Sep 9, 2018
81cf634
Fix model
at-wat Sep 9, 2018
0a7a366
Fix includes
at-wat Sep 9, 2018
7e6e2ad
Merge branch 'master' into lidar-measurement-model-class
at-wat Sep 11, 2018
2b8bff5
Don't return null shared_ptr from random sampler
at-wat Sep 18, 2018
26e606b
Add test for PointCloudRandomSampler class
at-wat Sep 18, 2018
4ba9695
Fix constness
at-wat Sep 18, 2018
2982960
Fix signed/unsigned compare
at-wat Sep 18, 2018
59645ad
Define beam model as a class
at-wat Sep 18, 2018
c7de317
Remove unused variables
at-wat Sep 18, 2018
75d130c
Merge branch 'master' into lidar-measurement-model-class
at-wat Sep 18, 2018
4c5350c
Add comment
at-wat Sep 19, 2018
7caf1e0
Transfar old parameter values to new ones
at-wat Sep 19, 2018
3c87670
Remove unused parameters
at-wat Sep 19, 2018
2d5d062
Change log output level
at-wat Sep 19, 2018
d024a99
Fix parameter name migration rule
at-wat Sep 19, 2018
a28be14
Fix function name
at-wat Sep 19, 2018
6c4befc
Update parameter name in test launches
at-wat Sep 19, 2018
5cd5ff2
Add test for mcl_3dl_compat::paramRename
at-wat Sep 19, 2018
9a8a451
Address review comments
at-wat Sep 20, 2018
0d8990a
Address review comments
at-wat Sep 20, 2018
f9444b8
Fix test
at-wat Sep 20, 2018
b37c72e
Remove STATE_TYPE from LidarMeasurementModel template parameter
at-wat Sep 21, 2018
de81133
Remove POINT_TYPE from LidarMeasurementModel template parameter
at-wat Sep 21, 2018
b2e8e71
Move impl from .h to .cpp
at-wat Sep 21, 2018
a038fad
Add LidarMeasurementResult struct to return measurement result
at-wat Sep 21, 2018
257a144
Fix constness
at-wat Sep 25, 2018
49572be
Fix State6Dof's size value
at-wat Sep 25, 2018
239b387
Add range assert to the State6Dof::[] operator
at-wat Sep 25, 2018
2efa4a7
Address review comments
at-wat Sep 25, 2018
cca96e3
Add dummy return to State6Dof::operator[] for out-of-range index
at-wat Sep 25, 2018
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
6 changes: 5 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,11 @@ add_definitions(${PCL_DEFINITIONS})
# Define PCL_NO_PRECOMPILE to disable using the binary version.
add_definitions(-DPCL_NO_PRECOMPILE)

add_executable(mcl_3dl src/mcl_3dl.cpp)
add_executable(mcl_3dl
src/lidar_measurement_model_beam.cpp
src/lidar_measurement_model_likelihood.cpp
src/mcl_3dl.cpp
)
target_link_libraries(mcl_3dl ${catkin_LIBRARIES} ${Boost_LIBRARIES} ${PCL_LIBRARIES})
add_dependencies(mcl_3dl ${catkin_EXPORTED_TARGETS})

Expand Down
84 changes: 84 additions & 0 deletions include/mcl_3dl/lidar_measurement_model_base.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,84 @@
/*
* Copyright (c) 2018, the mcl_3dl authors
* All rights reserved.
*
* 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.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the copyright holder nor the names of its
* 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 FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef MCL_3DL_LIDAR_MEASUREMENT_MODEL_BASE_H
#define MCL_3DL_LIDAR_MEASUREMENT_MODEL_BASE_H
DaikiMaekawa marked this conversation as resolved.
Show resolved Hide resolved

#include <string>
#include <utility>
#include <vector>

#include <ros/ros.h>

#include <pcl/point_types.h>
#include <pcl_ros/point_cloud.h>

#include <mcl_3dl/chunked_kdtree.h>
#include <mcl_3dl/state_6dof.h>
#include <mcl_3dl/vec3.h>

namespace mcl_3dl
{
struct LidarMeasurementResult
{
float likelihood;
float quality;

LidarMeasurementResult(const float likelihood_value, const float quality_value)
: likelihood(likelihood_value)
, quality(quality_value)
{
}
};

class LidarMeasurementModelBase
{
public:
DaikiMaekawa marked this conversation as resolved.
Show resolved Hide resolved
using Ptr = std::shared_ptr<LidarMeasurementModelBase>;
using PointType = pcl::PointXYZI;

virtual void loadConfig(
const ros::NodeHandle &nh,
const std::string &name) = 0;
DaikiMaekawa marked this conversation as resolved.
Show resolved Hide resolved
virtual void setGlobalLocalizationStatus(
const size_t, const size_t) = 0;
virtual float getMaxSearchRange() const = 0;

virtual pcl::PointCloud<PointType>::Ptr filter(
const pcl::PointCloud<PointType>::ConstPtr &) const = 0;

virtual LidarMeasurementResult measure(
ChunkedKdtree<PointType>::Ptr &,
const pcl::PointCloud<PointType>::ConstPtr &,
const std::vector<Vec3> &,
const State6DOF &) const = 0;
};
} // namespace mcl_3dl

#endif // MCL_3DL_LIDAR_MEASUREMENT_MODEL_BASE_H
Original file line number Diff line number Diff line change
@@ -0,0 +1,95 @@
/*
* Copyright (c) 2018, the mcl_3dl authors
* All rights reserved.
*
* 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.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDEDNode 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 FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef MCL_3DL_LIDAR_MEASUREMENT_MODELS_LIDAR_MEASUREMENT_MODEL_BEAM_H
#define MCL_3DL_LIDAR_MEASUREMENT_MODELS_LIDAR_MEASUREMENT_MODEL_BEAM_H

#include <string>
#include <vector>

#include <ros/ros.h>

#include <pcl/point_types.h>
#include <pcl_ros/point_cloud.h>

#include <mcl_3dl/chunked_kdtree.h>
#include <mcl_3dl/lidar_measurement_model_base.h>
#include <mcl_3dl/pf.h>
#include <mcl_3dl/point_cloud_random_sampler.h>
#include <mcl_3dl/vec3.h>

namespace mcl_3dl
{
class LidarMeasurementModelBeam : public LidarMeasurementModelBase
{
private:
size_t num_points_;
size_t num_points_default_;
size_t num_points_global_;
float clip_far_sq_;
float clip_near_sq_;
float clip_z_min_;
float clip_z_max_;
float beam_likelihood_min_;
float beam_likelihood_;
float sin_total_ref_;
float map_grid_min_;
float map_grid_max_;

PointCloudRandomSampler sampler_;

public:
LidarMeasurementModelBeam(const float x, const float y, const float z);

inline float getMaxSearchRange() const
{
return map_grid_max_ * 4;
}
inline float getSinTotalRef() const
{
return sin_total_ref_;
}

void loadConfig(
const ros::NodeHandle &nh,
const std::string &name);
void setGlobalLocalizationStatus(
const size_t num_particles,
const size_t current_num_particles);
pcl::PointCloud<PointType>::Ptr filter(
const pcl::PointCloud<PointType>::ConstPtr &pc) const;
LidarMeasurementResult measure(
ChunkedKdtree<PointType>::Ptr &kdtree,
const pcl::PointCloud<PointType>::ConstPtr &pc,
const std::vector<Vec3> &origins,
const State6DOF &s) const;
};
} // namespace mcl_3dl

#endif // MCL_3DL_LIDAR_MEASUREMENT_MODELS_LIDAR_MEASUREMENT_MODEL_BEAM_H
Original file line number Diff line number Diff line change
@@ -0,0 +1,87 @@
/*
* Copyright (c) 2018, the mcl_3dl authors
* All rights reserved.
*
* 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.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDEDNode 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 FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef MCL_3DL_LIDAR_MEASUREMENT_MODELS_LIDAR_MEASUREMENT_MODEL_LIKELIHOOD_H
#define MCL_3DL_LIDAR_MEASUREMENT_MODELS_LIDAR_MEASUREMENT_MODEL_LIKELIHOOD_H

#include <string>
#include <vector>

#include <ros/ros.h>

#include <pcl/point_types.h>
#include <pcl_ros/point_cloud.h>

#include <mcl_3dl/chunked_kdtree.h>
#include <mcl_3dl/lidar_measurement_model_base.h>
#include <mcl_3dl/pf.h>
#include <mcl_3dl/point_cloud_random_sampler.h>
#include <mcl_3dl/vec3.h>

namespace mcl_3dl
{
class LidarMeasurementModelLikelihood : public LidarMeasurementModelBase
{
private:
size_t num_points_;
size_t num_points_default_;
size_t num_points_global_;
float clip_far_sq_;
float clip_near_sq_;
float clip_z_min_;
float clip_z_max_;
float match_weight_;
float match_dist_min_;
float match_dist_flat_;

PointCloudRandomSampler sampler_;

public:
inline float getMaxSearchRange() const
{
return match_dist_min_;
}

void loadConfig(
const ros::NodeHandle &nh,
const std::string &name);
void setGlobalLocalizationStatus(
const size_t num_particles,
const size_t current_num_particles);
pcl::PointCloud<PointType>::Ptr filter(
const pcl::PointCloud<PointType>::ConstPtr &pc) const;
LidarMeasurementResult measure(
ChunkedKdtree<PointType>::Ptr &kdtree,
const pcl::PointCloud<PointType>::ConstPtr &pc,
const std::vector<Vec3> &origins,
const State6DOF &s) const;
};
} // namespace mcl_3dl

#endif // MCL_3DL_LIDAR_MEASUREMENT_MODELS_LIDAR_MEASUREMENT_MODEL_LIKELIHOOD_H
74 changes: 74 additions & 0 deletions include/mcl_3dl/point_cloud_random_sampler.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,74 @@
/*
* Copyright (c) 2018, the mcl_3dl authors
* All rights reserved.
*
* 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.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the copyright holder nor the names of its
* 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 FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef MCL_3DL_POINT_CLOUD_RANDOM_SAMPLER_H
#define MCL_3DL_POINT_CLOUD_RANDOM_SAMPLER_H

#include <random>

#include <pcl/point_types.h>
#include <pcl_ros/point_cloud.h>

namespace mcl_3dl
{
class PointCloudRandomSampler
at-wat marked this conversation as resolved.
Show resolved Hide resolved
{
private:
std::random_device seed_gen_;
std::shared_ptr<std::default_random_engine> engine_;

public:
PointCloudRandomSampler()
: engine_(new std::default_random_engine(seed_gen_()))
{
}
template <class POINT_TYPE>
typename pcl::PointCloud<POINT_TYPE>::Ptr sample(
const typename pcl::PointCloud<POINT_TYPE>::ConstPtr &pc,
const size_t num) const
{
typename pcl::PointCloud<POINT_TYPE>::Ptr output(new pcl::PointCloud<POINT_TYPE>);
output->header = pc->header;

if (pc->points.size() == 0)
return output;

output->points.reserve(num);
std::uniform_int_distribution<size_t> ud(0, pc->points.size() - 1);
for (size_t i = 0; i < num; i++)
{
output->push_back(pc->points[ud(*engine_)]);
}

return output;
}
};
} // namespace mcl_3dl

#endif // MCL_3DL_POINT_CLOUD_RANDOM_SAMPLER_H
Loading