37 #ifndef MOVEIT_OCCUPANCY_MAP_DEPTH_IMAGE_OCCUPANCY_MAP_UPDATER_ 38 #define MOVEIT_OCCUPANCY_MAP_DEPTH_IMAGE_OCCUPANCY_MAP_UPDATER_ 65 void depthImageCallback(
const sensor_msgs::ImageConstPtr& depth_msg,
const sensor_msgs::CameraInfoConstPtr& info_msg);
101 std::unique_ptr<mesh_filter::MeshFilter<mesh_filter::StereoCameraModel> >
mesh_filter_;
virtual ShapeHandle excludeShape(const shapes::ShapeConstPtr &shape)
std::string filtered_cloud_topic_
unsigned int skip_vertical_pixels_
image_transport::CameraPublisher pub_filtered_depth_image_
DepthImageOctomapUpdater()
virtual bool initialize()
Do any necessary setup (subscribe to ros topics, etc.). This call assumes setMonitor() and setParams(...
image_transport::ImageTransport model_depth_transport_
image_transport::CameraPublisher pub_model_depth_image_
Base class for classes which update the occupancy map.
double average_callback_dt_
ros::WallTime last_depth_callback_start_
ros::Time last_update_time_
image_transport::CameraSubscriber sub_depth_image_
unsigned int image_callback_count_
double far_clipping_plane_distance_
image_transport::ImageTransport input_depth_transport_
virtual ~DepthImageOctomapUpdater()
std::vector< float > x_cache_
unsigned int skip_horizontal_pixels_
double near_clipping_plane_distance_
bool getShapeTransform(mesh_filter::MeshHandle h, Eigen::Affine3d &transform) const
std::unique_ptr< LazyFreeSpaceUpdater > free_space_updater_
boost::shared_ptr< tf::Transformer > tf_
image_transport::ImageTransport filtered_depth_transport_
std::vector< unsigned int > filtered_labels_
virtual bool setParams(XmlRpc::XmlRpcValue ¶ms)
Set updater params using struct that comes from parsing a yaml string. This must be called after setM...
virtual void forgetShape(ShapeHandle handle)
void depthImageCallback(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
image_transport::ImageTransport filtered_label_transport_
image_transport::CameraPublisher pub_filtered_label_image_
std::unique_ptr< mesh_filter::MeshFilter< mesh_filter::StereoCameraModel > > mesh_filter_
std::shared_ptr< const Shape > ShapeConstPtr
std::vector< float > y_cache_