Skip to content

Commit

Permalink
Implement reset command, return success/failure
Browse files Browse the repository at this point in the history
  • Loading branch information
PeterBowman committed Sep 18, 2023
1 parent 9a98e8d commit e5cd035
Show file tree
Hide file tree
Showing 3 changed files with 23 additions and 6 deletions.
10 changes: 8 additions & 2 deletions libraries/VisionIDL/vision.thrift
Original file line number Diff line number Diff line change
Expand Up @@ -38,12 +38,18 @@ service SceneReconstructionIDL
/**
* pause the scene reconstruction process
*/
void pause();
bool pause();

/**
* start/resume the scene reconstruction process
*/
void resume();
bool resume();

/**
* reset the currently stored reconstruction
* @return bool
*/
bool reset();

/**
* get current camera pose
Expand Down
13 changes: 11 additions & 2 deletions programs/sceneReconstruction/SceneReconstruction.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -310,16 +310,25 @@ bool SceneReconstruction::close()
return cameraDriver.close();
}

void SceneReconstruction::pause()
bool SceneReconstruction::pause()
{
yCDebug(KINFU) << "Pausing";
isRunning = false;
return true;
}

void SceneReconstruction::resume()
bool SceneReconstruction::resume()
{
yCDebug(KINFU) << "Resuming";
isRunning = true;
return true;
}

bool SceneReconstruction::reset()
{
yCDebug(KINFU) << "Resetting";
kinfu->reset();
return true;
}

return_pose SceneReconstruction::getPose()
Expand Down
6 changes: 4 additions & 2 deletions programs/sceneReconstruction/SceneReconstruction.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,9 +60,11 @@ class SceneReconstruction : public yarp::os::RFModule,

bool close() override;

void pause() override;
bool pause() override;

void resume() override;
bool resume() override;

bool reset() override;

return_pose getPose() override;

Expand Down

0 comments on commit e5cd035

Please sign in to comment.