Go to the documentation of this file.
28 #define CAMERA_PATH_ID 13
29 #define ROBOT_TRAJECTORY_ID 14
32 : QObject(), m_scan_graph(graph), m_current_scan(1), m_current_cam_frame(1), m_number_cam_frames(0),
33 m_followRobotTrajectory(false) {
42 if(frame <= m_scan_graph->size()) {
63 std::cerr <<
"Error in " << __FILE__ <<
":" << __LINE__ <<
" : invalid node ID "<< i-1 << std::endl;
void cameraPathStopped(int id)
void removeFromCameraPath()
void playCameraPath(int id, int start_frame)
void changeCamPose(const octomath::Pose6D &pose)
void addCurrentToCameraPath(int id, int frame)
void stopCameraPath(int id)
#define ROBOT_TRAJECTORY_ID
octomap::ScanGraph * m_scan_graph
void updateCameraPath(int id, int frame)
unsigned int m_current_cam_frame
void jumpToCamFrame(int id, int frame)
void cameraPathFrameChanged(int id, int current_camera_frame)
void setScanGraph(octomap::ScanGraph *graph)
unsigned int m_current_scan
unsigned int m_start_frame
ScanNode * getNodeByID(unsigned int id)
void frameChanged(unsigned int frame)
void changeNumberOfFrames(unsigned count)
void scanGraphAvailable(bool available)
void jumpToFrame(unsigned int frame)
virtual ~CameraFollowMode()
void appendToCameraPath(int id, const octomath::Pose6D &pose)
void deleteCameraPath(int id)
bool m_followRobotTrajectory
CameraFollowMode(octomap::ScanGraph *graph=NULL)
unsigned int m_number_cam_frames
octovis
Author(s): Kai M. Wurm
, Armin Hornung
autogenerated on Thu Apr 3 2025 02:40:44