Namespaces | Functions | Variables
tango_3d_reconstruction_helper.h File Reference
#include <string>
#include <tango_3d_reconstruction/tango_3d_reconstruction_api.h>
#include <tango_support/tango_support.h>
#include <nav_msgs/OccupancyGrid.h>
#include <ros/ros.h>
#include <visualization_msgs/MarkerArray.h>
Include dependency graph for tango_3d_reconstruction_helper.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

namespace  tango_3d_reconstruction_helper

Functions

bool tango_3d_reconstruction_helper::ExtractFloorPlanImageAndConvertToOccupancyGrid (const Tango3DR_ReconstructionContext &t3dr_context, double time_offset, const std::string &base_frame_id, double t3dr_resolution, uint8_t threshold, nav_msgs::OccupancyGrid *occupancy_grid)
void tango_3d_reconstruction_helper::ExtractMeshAndConvertToMarkerArray (const Tango3DR_ReconstructionContext &t3dr_context, const Tango3DR_GridIndexArray &t3dr_updated_indices, double time_offset, const std::string &base_frame_id, visualization_msgs::MarkerArray *mesh_marker_array)
Tango3DR_Status tango_3d_reconstruction_helper::TangoSetup3DRConfig (const ros::NodeHandle &node_handle, double *t3dr_resolution, Tango3DR_ReconstructionContext *t3dr_context, Tango3DR_CameraCalibration *t3dr_color_camera_intrinsics)
void tango_3d_reconstruction_helper::UpdateMesh (const Tango3DR_ReconstructionContext &t3dr_context, TangoSupport_PointCloudManager *point_cloud_manager, TangoSupport_ImageBufferManager *image_buffer_manager, Tango3DR_Pose *last_camera_depth_pose, Tango3DR_Pose *last_camera_color_pose, Tango3DR_GridIndexArray *t3dr_updated_indices)

Variables

const double tango_3d_reconstruction_helper::TANGO_3DR_DEFAULT_FLOORPLAN_MAX_ERROR = 0.
const int32_t tango_3d_reconstruction_helper::TANGO_3DR_DEFAULT_MAX_VOXEL_WEIGHT = 16383
const int32_t tango_3d_reconstruction_helper::TANGO_3DR_DEFAULT_MIN_NUM_VERTICES = 1
const double tango_3d_reconstruction_helper::TANGO_3DR_DEFAULT_RESOLUTION = 0.05
const int32_t tango_3d_reconstruction_helper::TANGO_3DR_DEFAULT_UPDATE_METHOD = 0
const bool tango_3d_reconstruction_helper::TANGO_3DR_DEFAULT_USE_SPACE_CLEARING = false
const std::string tango_3d_reconstruction_helper::TANGO_3DR_FLOORPLAN_MAX_ERROR_PARAM_NAME = "reconstruction/floorplan_max_error"
const std::string tango_3d_reconstruction_helper::TANGO_3DR_MAX_VOXEL_WEIGHT_PARAM_NAME = "reconstruction/max_voxel_weight"
const std::string tango_3d_reconstruction_helper::TANGO_3DR_MIN_NUM_VERTICES_PARAM_NAME = "reconstruction/min_num_vertices"
const uint8_t tango_3d_reconstruction_helper::TANGO_3DR_OCCUPANCY_GRID_DEFAULT_THRESHOLD = 180
const std::string tango_3d_reconstruction_helper::TANGO_3DR_OCCUPANCY_GRID_THRESHOLD_PARAM_NAME = "reconstruction/occupancy_grid_threshold"
const std::string tango_3d_reconstruction_helper::TANGO_3DR_RESOLUTION_PARAM_NAME = "reconstruction/resolution_3d"
const std::string tango_3d_reconstruction_helper::TANGO_3DR_UPDATE_METHOD_PARAM_NAME = "reconstruction/update_method"
const std::string tango_3d_reconstruction_helper::TANGO_3DR_USE_SPACE_CLEARING_PARAM_NAME = "reconstruction/use_space_clearing"


tango_ros_native
Author(s):
autogenerated on Thu Jun 6 2019 19:49:54