Initialize shared pointers before use
Should address runtime errors reported in #29
This commit is contained in:
parent
fd75f3a02c
commit
11d24d0e97
@ -66,7 +66,7 @@ namespace pcl_ros
|
|||||||
PointCloud2 &output)
|
PointCloud2 &output)
|
||||||
{
|
{
|
||||||
boost::mutex::scoped_lock lock (mutex_);
|
boost::mutex::scoped_lock lock (mutex_);
|
||||||
pcl::PCLPointCloud2::Ptr pcl_input;
|
pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
|
||||||
pcl_conversions::toPCL(*(input), *(pcl_input));
|
pcl_conversions::toPCL(*(input), *(pcl_input));
|
||||||
impl_.setInputCloud (pcl_input);
|
impl_.setInputCloud (pcl_input);
|
||||||
impl_.setIndices (indices);
|
impl_.setIndices (indices);
|
||||||
|
|||||||
@ -64,7 +64,7 @@ namespace pcl_ros
|
|||||||
PointCloud2 &output)
|
PointCloud2 &output)
|
||||||
{
|
{
|
||||||
boost::mutex::scoped_lock lock (mutex_);
|
boost::mutex::scoped_lock lock (mutex_);
|
||||||
pcl::PCLPointCloud2::Ptr pcl_input;
|
pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
|
||||||
pcl_conversions::toPCL (*(input), *(pcl_input));
|
pcl_conversions::toPCL (*(input), *(pcl_input));
|
||||||
impl_.setInputCloud (pcl_input);
|
impl_.setInputCloud (pcl_input);
|
||||||
impl_.setIndices (indices);
|
impl_.setIndices (indices);
|
||||||
|
|||||||
@ -68,11 +68,11 @@ namespace pcl_ros
|
|||||||
filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices,
|
filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices,
|
||||||
PointCloud2 &output)
|
PointCloud2 &output)
|
||||||
{
|
{
|
||||||
pcl::PCLPointCloud2::Ptr pcl_input;
|
pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
|
||||||
pcl_conversions::toPCL (*(input), *(pcl_input));
|
pcl_conversions::toPCL (*(input), *(pcl_input));
|
||||||
impl_.setInputCloud (pcl_input);
|
impl_.setInputCloud (pcl_input);
|
||||||
impl_.setIndices (indices);
|
impl_.setIndices (indices);
|
||||||
pcl::ModelCoefficients::Ptr pcl_model;
|
pcl::ModelCoefficients::Ptr pcl_model(new pcl::ModelCoefficients);
|
||||||
pcl_conversions::toPCL(*(model_), *(pcl_model));
|
pcl_conversions::toPCL(*(model_), *(pcl_model));
|
||||||
impl_.setModelCoefficients (pcl_model);
|
impl_.setModelCoefficients (pcl_model);
|
||||||
pcl::PCLPointCloud2 pcl_output;
|
pcl::PCLPointCloud2 pcl_output;
|
||||||
|
|||||||
@ -61,7 +61,7 @@ namespace pcl_ros
|
|||||||
filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices,
|
filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices,
|
||||||
PointCloud2 &output)
|
PointCloud2 &output)
|
||||||
{
|
{
|
||||||
pcl::PCLPointCloud2::Ptr pcl_input;
|
pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
|
||||||
pcl_conversions::toPCL (*(input), *(pcl_input));
|
pcl_conversions::toPCL (*(input), *(pcl_input));
|
||||||
impl_.setInputCloud (pcl_input);
|
impl_.setInputCloud (pcl_input);
|
||||||
impl_.setIndices (indices);
|
impl_.setIndices (indices);
|
||||||
|
|||||||
@ -74,7 +74,7 @@ namespace pcl_ros
|
|||||||
PointCloud2 &output)
|
PointCloud2 &output)
|
||||||
{
|
{
|
||||||
boost::mutex::scoped_lock lock (mutex_);
|
boost::mutex::scoped_lock lock (mutex_);
|
||||||
pcl::PCLPointCloud2::Ptr pcl_input;
|
pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
|
||||||
pcl_conversions::toPCL(*(input), *(pcl_input));
|
pcl_conversions::toPCL(*(input), *(pcl_input));
|
||||||
impl_.setInputCloud (pcl_input);
|
impl_.setInputCloud (pcl_input);
|
||||||
impl_.setIndices (indices);
|
impl_.setIndices (indices);
|
||||||
|
|||||||
@ -58,7 +58,7 @@ pcl_ros::VoxelGrid::filter (const PointCloud2::ConstPtr &input,
|
|||||||
PointCloud2 &output)
|
PointCloud2 &output)
|
||||||
{
|
{
|
||||||
boost::mutex::scoped_lock lock (mutex_);
|
boost::mutex::scoped_lock lock (mutex_);
|
||||||
pcl::PCLPointCloud2::Ptr pcl_input;
|
pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
|
||||||
pcl_conversions::toPCL (*(input), *(pcl_input));
|
pcl_conversions::toPCL (*(input), *(pcl_input));
|
||||||
impl_.setInputCloud (pcl_input);
|
impl_.setInputCloud (pcl_input);
|
||||||
impl_.setIndices (indices);
|
impl_.setIndices (indices);
|
||||||
|
|||||||
Loading…
x
Reference in New Issue
Block a user