00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040 #ifndef PCL_PCL_HISTOGRAM_VISUALIZER_IMPL_H_
00041 #define PCL_PCL_HISTOGRAM_VISUALIZER_IMPL_H_
00042
00044 template <typename PointT> bool
00045 pcl::visualization::PCLHistogramVisualizer::addFeatureHistogram (
00046 const pcl::PointCloud<PointT> &cloud, int hsize,
00047 const std::string &id, int win_width, int win_height)
00048 {
00049 RenWinInteractMap::iterator am_it = wins_.find (id);
00050 if (am_it != wins_.end ())
00051 {
00052 PCL_WARN ("[addFeatureHistogram] A window with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ());
00053 return (false);
00054 }
00055
00056 vtkSmartPointer<vtkDoubleArray> xy_array = vtkSmartPointer<vtkDoubleArray>::New ();
00057 xy_array->SetNumberOfComponents (2);
00058 xy_array->SetNumberOfTuples (hsize);
00059
00060
00061 double xy[2];
00062 for (int d = 0; d < hsize; ++d)
00063 {
00064 xy[0] = d;
00065 xy[1] = cloud.points[0].histogram[d];
00066 xy_array->SetTuple (d, xy);
00067 }
00068 RenWinInteract renwinint;
00069 createActor (xy_array, renwinint, id, win_width, win_height);
00070
00071
00072 wins_[id] = renwinint;
00073 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00074 resetStoppedFlag ();
00075 #endif
00076 return (true);
00077 }
00078
00080 template <typename PointT> bool
00081 pcl::visualization::PCLHistogramVisualizer::addFeatureHistogram (
00082 const pcl::PointCloud<PointT> &cloud,
00083 const std::string &field_name,
00084 const int index,
00085 const std::string &id, int win_width, int win_height)
00086 {
00087 if (index < 0 || index >= cloud.points.size ())
00088 {
00089 PCL_ERROR ("[addFeatureHistogram] Invalid point index (%d) given!\n", index);
00090 return (false);
00091 }
00092
00093
00094 std::vector<sensor_msgs::PointField> fields;
00095
00096 int field_idx = pcl::getFieldIndex<PointT> (cloud, field_name, fields);
00097 if (field_idx == -1)
00098 {
00099 PCL_ERROR ("[addFeatureHistogram] The specified field <%s> does not exist!\n", field_name.c_str ());
00100 return (false);
00101 }
00102
00103 RenWinInteractMap::iterator am_it = wins_.find (id);
00104 if (am_it != wins_.end ())
00105 {
00106 PCL_WARN ("[addFeatureHistogram] A window with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ());
00107 return (false);
00108 }
00109
00110 vtkSmartPointer<vtkDoubleArray> xy_array = vtkSmartPointer<vtkDoubleArray>::New ();
00111 xy_array->SetNumberOfComponents (2);
00112 xy_array->SetNumberOfTuples (fields[field_idx].count);
00113
00114
00115 double xy[2];
00116 for (int d = 0; d < fields[field_idx].count; ++d)
00117 {
00118 xy[0] = d;
00119
00120 float data;
00121 memcpy (&data, reinterpret_cast<const char*> (&cloud.points[index]) + fields[field_idx].offset + d * sizeof (float), sizeof (float));
00122 xy[1] = data;
00123 xy_array->SetTuple (d, xy);
00124 }
00125 RenWinInteract renwinint;
00126 createActor (xy_array, renwinint, id, win_width, win_height);
00127
00128
00129 wins_[id] = renwinint;
00130 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00131 resetStoppedFlag ();
00132 #endif
00133 return (true);
00134 }
00135
00137 template <typename PointT> bool
00138 pcl::visualization::PCLHistogramVisualizer::updateFeatureHistogram (
00139 const pcl::PointCloud<PointT> &cloud, int hsize,
00140 const std::string &id)
00141 {
00142 RenWinInteractMap::iterator am_it = wins_.find (id);
00143 if (am_it == wins_.end ())
00144 {
00145 PCL_WARN ("[updateFeatureHistogram] A window with id <%s> does not exists!.\n", id.c_str ());
00146 return (false);
00147 }
00148 RenWinInteract* renwinupd = &wins_[id];
00149
00150 vtkSmartPointer<vtkDoubleArray> xy_array = vtkSmartPointer<vtkDoubleArray>::New ();
00151 xy_array->SetNumberOfComponents (2);
00152 xy_array->SetNumberOfTuples (hsize);
00153
00154
00155 double xy[2];
00156 for (int d = 0; d < hsize; ++d)
00157 {
00158 xy[0] = d;
00159 xy[1] = cloud.points[0].histogram[d];
00160 xy_array->SetTuple (d, xy);
00161 }
00162 reCreateActor (xy_array, renwinupd, hsize);
00163 return (true);
00164 }
00165
00167 template <typename PointT> bool
00168 pcl::visualization::PCLHistogramVisualizer::updateFeatureHistogram (
00169 const pcl::PointCloud<PointT> &cloud, const std::string &field_name, const int index,
00170 const std::string &id)
00171 {
00172 if (index < 0 || index >= cloud.points.size ())
00173 {
00174 PCL_ERROR ("[updateFeatureHistogram] Invalid point index (%d) given!\n", index);
00175 return (false);
00176 }
00177
00178
00179 std::vector<sensor_msgs::PointField> fields;
00180
00181 int field_idx = pcl::getFieldIndex<PointT> (cloud, field_name, fields);
00182 if (field_idx == -1)
00183 {
00184 PCL_ERROR ("[updateFeatureHistogram] The specified field <%s> does not exist!\n", field_name.c_str ());
00185 return (false);
00186 }
00187
00188 RenWinInteractMap::iterator am_it = wins_.find (id);
00189 if (am_it == wins_.end ())
00190 {
00191 PCL_WARN ("[updateFeatureHistogram] A window with id <%s> does not exists!.\n", id.c_str ());
00192 return (false);
00193 }
00194 RenWinInteract* renwinupd = &wins_[id];
00195
00196 vtkSmartPointer<vtkDoubleArray> xy_array = vtkSmartPointer<vtkDoubleArray>::New ();
00197 xy_array->SetNumberOfComponents (2);
00198 xy_array->SetNumberOfTuples (fields[field_idx].count);
00199
00200
00201 double xy[2];
00202 for (int d = 0; d < fields[field_idx].count; ++d)
00203 {
00204 xy[0] = d;
00205
00206 float data;
00207 memcpy (&data, reinterpret_cast<const char*> (&cloud.points[index]) + fields[field_idx].offset + d * sizeof (float), sizeof (float));
00208 xy[1] = data;
00209 xy_array->SetTuple (d, xy);
00210 }
00211
00212 reCreateActor (xy_array, renwinupd, cloud.fields[field_idx].count - 1);
00213 return (true);
00214 }
00215
00216 #endif
00217