Skip to content
Snippets Groups Projects
Commit b4b9920d authored by NicolaCovallero's avatar NicolaCovallero
Browse files

fixed some comments and other minor changes

parent 0329921a
No related branches found
No related tags found
No related merge requests found
......@@ -54,9 +54,10 @@ const bool USE_PARAMETERS = false;
//-------------------
/**
* \brief IRI ROS Specific Driver Class
*
* \brief IRI ROS Specific Driver Class - Tabletop Object Segmentation by Supervoxels convexity
*
* Class to segmented tabletop objects, the table has to be
* the bigger plane in the scene.
*/
class TosSupervoxelsAlgorithm
{
......@@ -168,14 +169,6 @@ class TosSupervoxelsAlgorithm
void init(pcl::PointCloud<pcl::PointXYZRGBA> input_cloud,
tos_supervoxels_parameters &opt);
/*! \brief Class initializer
*
* \param input_cloud input cloud to segment
* \param opt parameters for the algorithm
*/
//void init(pcl::PointCloud<pcl::PointXYZRGBA> input_cloud,
// iri_tos_supervoxels::parameters &opt);
/*! \brief Class initializer, with default parameters
*
* \param input_cloud input cloud to segment
......@@ -195,19 +188,15 @@ class TosSupervoxelsAlgorithm
*/
tos_supervoxels_parameters get_default_parameters();
/*! \brief get the default parameters of the algorithm in the message format
*/
//iri_tos_supervoxels::parameters get_default_parameters_msg();
/*! \brief Detect and segment the objects on the table
*/
void segment();
/*! \brief Get the detected objects as a vector of the variable Object
/*! \brief Get the segmented objects as a vector of the variable Object
*/
std::vector<Object> get_segmented_objects();
/*! \brief Get the detected objects as a vector of point clouds
/*! \brief Get the segmented objects as a vector of point clouds
*/
std::vector<pcl::PointCloud<pcl::PointXYZRGBA> > get_segmented_objects_simple();
......@@ -231,6 +220,8 @@ class TosSupervoxelsAlgorithm
*/
pcl::PointCloud<pcl::PointNormal> get_sv_normal_cloud();
// functions to set and get the parameters of the algorithm
void set_disable_transform(bool disable_transform_in);
void set_voxel_resolution(double voxel_resolution_in);
void set_seed_resolution(double seed_resolution_in);
......
......@@ -4,12 +4,15 @@
name="iri_tos_supervoxels_alg" output="screen">
<param name="seed_resolution" value="0.015"/>
<param name="th_points" value="50"/>
<param name="service_name" value="object_segmentation"/>
</node>
<!-- client -->
<node pkg="iri_tos_supervoxels" type="iri_tos_supervoxels_client"
name="iri_tos_supervoxels_alg_client" output="screen">
<param name="input_topic" value="/camera/depth/points"/>
<param name="service_name" value="/iri_tos_supervoxels_alg/object_segmentation"/>
</node>
</launch>
\ No newline at end of file
......@@ -32,29 +32,6 @@ void TosSupervoxelsAlgorithm::init(pcl::PointCloud<pcl::PointXYZRGBA> input_clou
this->obj_segment.init(input_cloud);
}
/*void TosSupervoxelsAlgorithm::init(pcl::PointCloud<pcl::PointXYZRGBA> input_cloud,
iri_tos_supervoxels::parameters &opt)
{
this->obj_segment.init(input_cloud);
this->obj_segment.set_disable_transform(opt.disable_transform);
this->obj_segment.set_voxel_resolution(opt.voxel_resolution);
this->obj_segment.set_seed_resolution(opt.seed_resolution);
this->obj_segment.set_color_importance(opt.color_importance);
this->obj_segment.set_spatial_importance(opt.spatial_importance);
this->obj_segment.set_normal_importance(opt.normal_importance);
this->obj_segment.set_concavity_tolerance_threshold(opt.concavity_tolerance_threshold);
this->obj_segment.set_smoothness_threshold(opt.smoothness_threshold);
this->obj_segment.set_min_segment_size(opt.min_segment_size);
this->obj_segment.set_use_extended_convexity(opt.use_extended_convexity);
this->obj_segment.set_use_sanity_criterion(opt.use_sanity_criterion);
this->obj_segment.set_zmin(opt.zmin);
this->obj_segment.set_zmax(opt.zmax);
this->obj_segment.set_th_points(opt.th_points);
}*/
void TosSupervoxelsAlgorithm::reset()
{
this->obj_segment.reset();
......@@ -65,41 +42,11 @@ pcl::PointCloud<pcl::PointXYZRGBA>::Ptr TosSupervoxelsAlgorithm::get_input_cloud
return this->obj_segment.get_input_cloud();
}
tos_supervoxels_parameters TosSupervoxelsAlgorithm::get_default_parameters()
{
return this->obj_segment.get_default_parameters();
}
/*iri_tos_supervoxels::parameters TosSupervoxelsAlgorithm::get_default_parameters_msg()
{
iri_tos_supervoxels::parameters p;
tos_supervoxels_parameters opt = this->obj_segment.get_default_parameters();
p.disable_transform = opt.disable_transform;
p.voxel_resolution = opt.voxel_resolution;
p.seed_resolution = opt.seed_resolution;
p.color_importance = opt.color_importance;
p.spatial_importance = opt.spatial_importance;
p.normal_importance = opt.normal_importance;
// LCCPSegmentation Stuff
p.concavity_tolerance_threshold = opt.concavity_tolerance_threshold;
p.smoothness_threshold = opt.smoothness_threshold;
p.min_segment_size = opt.min_segment_size;
p.use_extended_convexity = opt.use_extended_convexity;
p.use_sanity_criterion = opt.use_sanity_criterion;
p.zmin = opt.zmin;//meters
p.zmax = opt.zmax;//meters
p.th_points = opt.th_points;
return p;
}*/
void TosSupervoxelsAlgorithm::segment()
{
this->obj_segment.segment();
......
......@@ -21,6 +21,7 @@ void callback(const sensor_msgs::PointCloud2 cloud_msg)
iri_tos_supervoxels::object_segmentation srv;
srv.request.point_cloud = cloud_msg;
// call the service to segment the table otp objects
if(client.call(srv))
{
//creating new point cloud for debugging with random color for each segmented object
......@@ -33,7 +34,7 @@ void callback(const sensor_msgs::PointCloud2 cloud_msg)
pcl::fromROSMsg(srv.response.objects[i],tmp);
//we now construct manually the point cloud
//choose a random color for the object
//choose a random color for each segmented object
float r,g,b;
r = static_cast <float> (rand()) / static_cast <float> (RAND_MAX);
g = static_cast <float> (rand()) / static_cast <float> (RAND_MAX);
......@@ -55,14 +56,14 @@ void callback(const sensor_msgs::PointCloud2 cloud_msg)
detected_objects_cloud.height = 1;
detected_objects_cloud.is_dense = true;
std::cout << "detected_objects_cloud.points.size() " << detected_objects_cloud.points.size() << "\n";
//std::cout << "detected_objects_cloud.points.size() " << detected_objects_cloud.points.size() << "\n";
pcl::toROSMsg(detected_objects_cloud,detected_objects_msg);
std::cout << "detected_objects_msg.data.size() " << detected_objects_msg.data.size() << "\n";
//std::cout << "detected_objects_msg.data.size() " << detected_objects_msg.data.size() << "\n";
detected_objects_msg.header.seq = 1;
detected_objects_msg.header.frame_id = cloud_msg.header.frame_id;
detected_objects_msg.header.stamp = ros::Time::now();
std::cout << "frame of point cloud: " << detected_objects_msg.header.frame_id << "\n";
//std::cout << "frame of point cloud: " << detected_objects_msg.header.frame_id << "\n";
pub.publish(detected_objects_msg);
}
else
......
......@@ -6,6 +6,7 @@ TosSupervoxelsAlgNode::TosSupervoxelsAlgNode(void) :
//init class attributes if necessary
this->loop_rate_ = 10;//in [Hz]
// initialize class parameters
this->public_node_handle_.param("disable_transform",alg_.params.disable_transform,DISABLE_TRANSFORM);
this->public_node_handle_.param("voxel_resolution",alg_.params.voxel_resolution,VOXEL_RESOLUTION);
this->public_node_handle_.param("seed_resolution",alg_.params.seed_resolution,SEED_RESOLUTION);
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment