Go to the documentation of this file.
28 #ifndef RTABMAP_APP_H_
29 #define RTABMAP_APP_H_
47 #include <boost/thread/mutex.hpp>
48 #include <pcl/pcl_base.h>
49 #include <pcl/TextureMesh.h>
61 void(*progressCallback)(
void *,
int,
int),
62 void(*initCallback)(
void *,
int,
const char*),
63 void(*statsUpdatedCallback)(
void *,
66 int,
int,
int,
int,
int ,
int,
71 float,
float,
float,
float,
73 float,
float,
float,
float,
float,
float),
74 void(*cameraInfoCallback)(
void *,
int,
const char*,
const char*));
81 int openDatabase(
const std::string & databasePath,
bool databaseInMemory,
bool optimize,
bool clearDatabase);
85 bool startCamera(JNIEnv*
env, jobject iBinder, jobject context, jobject activity,
int driver);
116 float x0,
float y0,
float x1,
float y1);
160 void save(
const std::string & databasePath);
161 bool recover(
const std::string & from,
const std::string & to);
164 float cloudVoxelSize,
165 bool regenerateCloud,
171 float optimizedVoxelSize,
173 int optimizedMaxPolygons,
174 float optimizedColorRadius,
175 bool optimizedCleanWhitePolygons,
176 int optimizedMinClusterSize,
177 float optimizedMaxTextureDistance,
178 int optimizedMinTextureClusterSize,
179 bool blockRendering);
186 float rgb_fx,
float rgb_fy,
float rgb_cx,
float rgb_cy,
187 float depth_fx,
float depth_fy,
float depth_cx,
float depth_cy,
192 const void * yPlane,
const void * uPlane,
const void * vPlane,
int yPlaneLen,
int rgbWidth,
int rgbHeight,
int rgbFormat,
193 const void * depth,
int depthLen,
int depthWidth,
int depthHeight,
int depthFormat,
194 const void *
conf,
int confLen,
int confWidth,
int confHeight,
int confFormat,
195 const float * points,
int pointsLen,
int pointsChannels,
197 float p00,
float p11,
float p02,
float p12,
float p22,
float p32,
float p23,
198 float t0,
float t1,
float t2,
float t3,
float t4,
float t5,
float t6,
float t7);
208 std::vector<pcl::Vertices>
filterOrganizedPolygons(
const std::vector<pcl::Vertices> & polygons,
int cloudSize)
const;
209 std::vector<pcl::Vertices>
filterPolygons(
const std::vector<pcl::Vertices> & polygons,
int cloudSize)
const;
296 std::pair<rtabmap::RtabmapEventInit::Status, std::string>
status_;
319 #endif // TANGO_POINT_CLOUD_POINT_CLOUD_APP_H_
void(* swiftStatsUpdatedCallback)(void *, int, int, int, int, float, int, int, int, int, int, int, float, int, float, int, float, float, float, float, int, int, float, float, float, float, float, float)
void setMinCloudDepth(float value)
rtabmap::Transform mapToOdom_
bool recover(const std::string &from, const std::string &to)
rtabmap::ParametersMap getRtabmapParameters()
void(* swiftInitCallback)(void *, int, const char *)
void setSmoothing(bool enabled)
void setGridRotation(float value)
std::string format(const std::string &str, const std::vector< std::string > &find, const std::vector< std::string > &replace)
void setFullResolution(bool enabled)
rtabmap::ProgressionStatus progressionStatus_
void setAppendMode(bool enabled)
void setGraphOptimization(bool enabled)
void setOnlineBlending(bool enabled)
void setScreenRotation(int displayRotation, int cameraRotation)
void setRawScanSaved(bool enabled)
void SetCameraType(tango_gl::GestureCamera::CameraType camera_type)
void gainCompensation(bool full=false)
rtabmap::ParametersMap mappingParameters_
void setLocalizationMode(bool enabled)
void setCameraColor(bool enabled)
rtabmap::LogHandler * logHandler_
void(* swiftCameraInfoEventCallback)(void *, int, const char *, const char *)
void setWireframe(bool enabled)
bool isBuiltWith(int cameraDriver) const
void setDataRecorderMode(bool enabled)
std::list< rtabmap::SensorEvent > sensorEvents_
boost::mutex sensorMutex_
void setDepthFromMotion(bool enabled)
void setMeshTriangleSize(int value)
void SetViewPort(int width, int height)
bool bilateralFilteringOnNextRender_
void setMaxCloudDepth(float value)
void setGraphVisible(bool visible)
int postProcessing(int approach)
std::map< std::string, float > bufferedStatsData_
std::list< rtabmap::RtabmapEvent * > rtabmapEvents_
std::map< std::string, std::string > ParametersMap
bool exportedMeshUpdated_
void setRenderingTextureDecimation(int value)
void setPointSize(float value)
void setGridVisible(bool visible)
rtabmap::Rtabmap * rtabmap_
gtsam.ISAM2 optimize(List[GpsMeasurement] gps_measurements, List[ImuMeasurement] imu_measurements, gtsam.noiseModel.Diagonal sigma_init_x, gtsam.noiseModel.Diagonal sigma_init_v, gtsam.noiseModel.Diagonal sigma_init_b, gtsam.noiseModel.Diagonal noise_model_gps, KittiCalibration kitti_calibration, int first_gps_pose, int gps_skip)
int renderingTextureDecimation_
void setCloudDensityLevel(int value)
void OnTouchEvent(int touch_count, tango_gl::GestureCamera::TouchEvent event, float x0, float y0, float x1, float y1)
bool clearSceneOnNextRender_
virtual bool handleEvent(UEvent *event)
double lastPostRenderEventTime_
void setMeshAngleTolerance(float value)
void setUpstreamRelocalizationAccThr(float value)
int updateMeshDecimation(int width, int height)
rtabmap::RtabmapThread * rtabmapThread_
std::vector< pcl::Vertices > filterOrganizedPolygons(const std::vector< pcl::Vertices > &polygons, int cloudSize) const
void setBackfaceCulling(bool enabled)
void setMaxGainRadius(float value)
void save(const std::string &databasePath)
std::map< int, rtabmap::Mesh > createdMeshes_
void setMeshDecimationFactor(float value)
rtabmap::SensorCaptureThread * sensorCaptureThread_
pcl::TextureMesh::Ptr optMesh_
float upstreamRelocalizationMaxAcc_
GLM_FUNC_DECL T angle(detail::tquat< T, P > const &x)
bool writeExportedMesh(const std::string &directory, const std::string &name)
void setLighting(bool enabled)
bool cameraJustInitialized_
void setDepthConfidence(int value)
void setBackgroundColor(float gray)
const gtsam::Symbol key( 'X', 0)
std::string exportPointCloudFormat_
CEPHES_EXTERN_EXPORT double y1(double x)
int setMappingParameter(const std::string &key, const std::string &value)
void setOrthoCropFactor(float value)
void setupSwiftCallbacks(void *classPtr, void(*progressCallback)(void *, int, int), void(*initCallback)(void *, int, const char *), void(*statsUpdatedCallback)(void *, int, int, int, int, float, int, int, int, int, int, int, float, int, float, int, float, float, float, float, int, int, float, float, float, float, float, float), void(*cameraInfoCallback)(void *, int, const char *, const char *))
bool filterPolygonsOnNextRender_
void setClusterRatio(float value)
bool takeScreenshotOnNextRender_
boost::mutex renderingMutex_
boost::mutex rtabmapMutex_
std::vector< pcl::Vertices > filterPolygons(const std::vector< pcl::Vertices > &polygons, int cloudSize) const
void setMapCloudShown(bool shown)
CEPHES_EXTERN_EXPORT double y0(double x)
bool postExportation(bool visualize)
int openDatabase(const std::string &databasePath, bool databaseInMemory, bool optimize, bool clearDatabase)
void setExportPointCloudFormat(const std::string &format)
int gainCompensationOnNextRender_
USemaphore screenshotReady_
void postOdometryEvent(rtabmap::Transform pose, float rgb_fx, float rgb_fy, float rgb_cx, float rgb_cy, float depth_fx, float depth_fy, float depth_cx, float depth_cy, const rtabmap::Transform &rgbFrame, const rtabmap::Transform &depthFrame, double stamp, double depthStamp, const void *yPlane, const void *uPlane, const void *vPlane, int yPlaneLen, int rgbWidth, int rgbHeight, int rgbFormat, const void *depth, int depthLen, int depthWidth, int depthHeight, int depthFormat, const void *conf, int confLen, int confWidth, int confHeight, int confFormat, const float *points, int pointsLen, int pointsChannels, rtabmap::Transform viewMatrix, float p00, float p11, float p02, float p12, float p22, float p32, float p23, float t0, float t1, float t2, float t3, float t4, float t5, float t6, float t7)
void setGPS(const rtabmap::GPS &gps)
std::pair< rtabmap::RtabmapEventInit::Status, std::string > status_
bool smoothMesh(int id, rtabmap::Mesh &mesh)
void setPausedMapping(bool paused)
float meshAngleToleranceDeg_
rtabmap::Transform * optRefPose_
bool exportMesh(float cloudVoxelSize, bool regenerateCloud, bool meshing, int textureSize, int textureCount, int normalK, bool optimized, float optimizedVoxelSize, int optimizedDepth, int optimizedMaxPolygons, float optimizedColorRadius, bool optimizedCleanWhitePolygons, int optimizedMinClusterSize, float optimizedMaxTextureDistance, int optimizedMinTextureClusterSize, bool blockRendering)
std::map< int, rtabmap::Transform > rawPoses_
float meshDecimationFactor_
std::list< rtabmap::Transform > poseEvents_
void InitializeGLContent()
void setMeshRendering(bool enabled, bool withTexture)
void setNodesFiltering(bool enabled)
rtabmap::CameraMobile * camera_
void setOdomCloudShown(bool shown)
int lastDrawnCloudsCount_
double lastPoseEventTime_
void addEnvSensor(int type, float value)
boost::mutex meshesMutex_
boost::mutex cameraMutex_
void setTrajectoryMode(bool enabled)
rtabmap
Author(s): Mathieu Labbe
autogenerated on Sun Dec 1 2024 03:42:51