#include <depth_image_octomap_updater.h>
Definition at line 51 of file depth_image_octomap_updater.h.
Definition at line 47 of file depth_image_octomap_updater.cpp.
Definition at line 71 of file depth_image_octomap_updater.cpp.
void occupancy_map_monitor::DepthImageOctomapUpdater::depthImageCallback | ( | const sensor_msgs::ImageConstPtr & | depth_msg, |
const sensor_msgs::CameraInfoConstPtr & | info_msg | ||
) | [private] |
Definition at line 198 of file depth_image_octomap_updater.cpp.
mesh_filter::MeshHandle occupancy_map_monitor::DepthImageOctomapUpdater::excludeShape | ( | const shapes::ShapeConstPtr & | shape | ) | [virtual] |
Implements occupancy_map_monitor::OccupancyMapUpdater.
Definition at line 147 of file depth_image_octomap_updater.cpp.
void occupancy_map_monitor::DepthImageOctomapUpdater::forgetShape | ( | ShapeHandle | handle | ) | [virtual] |
Implements occupancy_map_monitor::OccupancyMapUpdater.
Definition at line 166 of file depth_image_octomap_updater.cpp.
bool occupancy_map_monitor::DepthImageOctomapUpdater::getShapeTransform | ( | mesh_filter::MeshHandle | h, |
Eigen::Affine3d & | transform | ||
) | const [private] |
Definition at line 172 of file depth_image_octomap_updater.cpp.
bool occupancy_map_monitor::DepthImageOctomapUpdater::initialize | ( | ) | [virtual] |
Do any necessary setup (subscribe to ros topics, etc.). This call assumes setMonitor() and setParams() have been previously called.
Implements occupancy_map_monitor::OccupancyMapUpdater.
Definition at line 105 of file depth_image_octomap_updater.cpp.
bool occupancy_map_monitor::DepthImageOctomapUpdater::setParams | ( | XmlRpc::XmlRpcValue & | params | ) | [virtual] |
Set updater params using struct that comes from parsing a yaml string. This must be called after setMonitor()
Implements occupancy_map_monitor::OccupancyMapUpdater.
Definition at line 76 of file depth_image_octomap_updater.cpp.
void occupancy_map_monitor::DepthImageOctomapUpdater::start | ( | void | ) | [virtual] |
Implements occupancy_map_monitor::OccupancyMapUpdater.
Definition at line 122 of file depth_image_octomap_updater.cpp.
void occupancy_map_monitor::DepthImageOctomapUpdater::stop | ( | void | ) | [virtual] |
Implements occupancy_map_monitor::OccupancyMapUpdater.
Definition at line 137 of file depth_image_octomap_updater.cpp.
void occupancy_map_monitor::DepthImageOctomapUpdater::stopHelper | ( | ) | [private] |
Definition at line 142 of file depth_image_octomap_updater.cpp.
Definition at line 96 of file depth_image_octomap_updater.h.
unsigned int occupancy_map_monitor::DepthImageOctomapUpdater::failed_tf_ [private] |
Definition at line 98 of file depth_image_octomap_updater.h.
Definition at line 88 of file depth_image_octomap_updater.h.
std::string occupancy_map_monitor::DepthImageOctomapUpdater::filtered_cloud_topic_ [private] |
Definition at line 83 of file depth_image_octomap_updater.h.
image_transport::ImageTransport occupancy_map_monitor::DepthImageOctomapUpdater::filtered_depth_transport_ [private] |
Definition at line 75 of file depth_image_octomap_updater.h.
image_transport::ImageTransport occupancy_map_monitor::DepthImageOctomapUpdater::filtered_label_transport_ [private] |
Definition at line 76 of file depth_image_octomap_updater.h.
std::vector<unsigned int> occupancy_map_monitor::DepthImageOctomapUpdater::filtered_labels_ [private] |
Definition at line 105 of file depth_image_octomap_updater.h.
boost::scoped_ptr<LazyFreeSpaceUpdater> occupancy_map_monitor::DepthImageOctomapUpdater::free_space_updater_ [private] |
Definition at line 101 of file depth_image_octomap_updater.h.
unsigned int occupancy_map_monitor::DepthImageOctomapUpdater::good_tf_ [private] |
Definition at line 97 of file depth_image_octomap_updater.h.
unsigned int occupancy_map_monitor::DepthImageOctomapUpdater::image_callback_count_ [private] |
Definition at line 95 of file depth_image_octomap_updater.h.
std::string occupancy_map_monitor::DepthImageOctomapUpdater::image_topic_ [private] |
Definition at line 85 of file depth_image_octomap_updater.h.
image_transport::ImageTransport occupancy_map_monitor::DepthImageOctomapUpdater::input_depth_transport_ [private] |
Definition at line 73 of file depth_image_octomap_updater.h.
double occupancy_map_monitor::DepthImageOctomapUpdater::inv_fx_ [private] |
Definition at line 104 of file depth_image_octomap_updater.h.
double occupancy_map_monitor::DepthImageOctomapUpdater::inv_fy_ [private] |
Definition at line 104 of file depth_image_octomap_updater.h.
double occupancy_map_monitor::DepthImageOctomapUpdater::K0_ [private] |
Definition at line 104 of file depth_image_octomap_updater.h.
double occupancy_map_monitor::DepthImageOctomapUpdater::K2_ [private] |
Definition at line 104 of file depth_image_octomap_updater.h.
double occupancy_map_monitor::DepthImageOctomapUpdater::K4_ [private] |
Definition at line 104 of file depth_image_octomap_updater.h.
double occupancy_map_monitor::DepthImageOctomapUpdater::K5_ [private] |
Definition at line 104 of file depth_image_octomap_updater.h.
Definition at line 106 of file depth_image_octomap_updater.h.
boost::scoped_ptr<mesh_filter::MeshFilter<mesh_filter::StereoCameraModel> > occupancy_map_monitor::DepthImageOctomapUpdater::mesh_filter_ [private] |
Definition at line 100 of file depth_image_octomap_updater.h.
image_transport::ImageTransport occupancy_map_monitor::DepthImageOctomapUpdater::model_depth_transport_ [private] |
Definition at line 74 of file depth_image_octomap_updater.h.
Definition at line 87 of file depth_image_octomap_updater.h.
Definition at line 71 of file depth_image_octomap_updater.h.
double occupancy_map_monitor::DepthImageOctomapUpdater::padding_offset_ [private] |
Definition at line 91 of file depth_image_octomap_updater.h.
double occupancy_map_monitor::DepthImageOctomapUpdater::padding_scale_ [private] |
Definition at line 90 of file depth_image_octomap_updater.h.
image_transport::CameraPublisher occupancy_map_monitor::DepthImageOctomapUpdater::pub_filtered_depth_image_ [private] |
Definition at line 80 of file depth_image_octomap_updater.h.
image_transport::CameraPublisher occupancy_map_monitor::DepthImageOctomapUpdater::pub_filtered_label_image_ [private] |
Definition at line 81 of file depth_image_octomap_updater.h.
image_transport::CameraPublisher occupancy_map_monitor::DepthImageOctomapUpdater::pub_model_depth_image_ [private] |
Definition at line 79 of file depth_image_octomap_updater.h.
std::size_t occupancy_map_monitor::DepthImageOctomapUpdater::queue_size_ [private] |
Definition at line 86 of file depth_image_octomap_updater.h.
std::string occupancy_map_monitor::DepthImageOctomapUpdater::sensor_type_ [private] |
Definition at line 84 of file depth_image_octomap_updater.h.
double occupancy_map_monitor::DepthImageOctomapUpdater::shadow_threshold_ [private] |
Definition at line 89 of file depth_image_octomap_updater.h.
unsigned int occupancy_map_monitor::DepthImageOctomapUpdater::skip_horizontal_pixels_ [private] |
Definition at line 93 of file depth_image_octomap_updater.h.
unsigned int occupancy_map_monitor::DepthImageOctomapUpdater::skip_vertical_pixels_ [private] |
Definition at line 92 of file depth_image_octomap_updater.h.
image_transport::CameraSubscriber occupancy_map_monitor::DepthImageOctomapUpdater::sub_depth_image_ [private] |
Definition at line 78 of file depth_image_octomap_updater.h.
boost::shared_ptr<tf::Transformer> occupancy_map_monitor::DepthImageOctomapUpdater::tf_ [private] |
Definition at line 72 of file depth_image_octomap_updater.h.
std::vector<float> occupancy_map_monitor::DepthImageOctomapUpdater::x_cache_ [private] |
Definition at line 103 of file depth_image_octomap_updater.h.
std::vector<float> occupancy_map_monitor::DepthImageOctomapUpdater::y_cache_ [private] |
Definition at line 103 of file depth_image_octomap_updater.h.