Skip to content
Open
Show file tree
Hide file tree
Changes from 3 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 4 additions & 1 deletion robosherlock/launch/rs.launch
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,9 @@
<arg name="save_path" default=""/>
<arg name="withIDRes" default="false"/>
<arg name="wait" default="false"/>

<arg name="ts" default="0"/>
<arg name="time_stamp" default="$(arg ts)"/>

<arg name="parallel" default="false"/>
<arg name="pervasive" default="false"/>
<arg name="enableQnA" default="false"/>
Expand All @@ -30,6 +32,7 @@
launch-prefix="$(arg launch-prefix)">
<param name="ae" type="str" value="$(arg ae)"/>
<param name="vis" type="bool" value="$(arg vis)"/>
<param name="ts" type="double" value="$(arg ts)"/>
<param name="parallel" type="bool" value="$(arg parallel)"/>
<param name="save_path" type="str" value="$(arg save_path)"/>
<param name="withIDRes" type="bool" value="$(arg withIDRes)"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@ class MongoDBBridge : public CamInterface

std::vector<uint64_t> frames;
size_t actualFrame;
size_t index;
bool continual;
bool loop;
double playbackSpeed;
Expand Down
176 changes: 106 additions & 70 deletions robosherlock/src/io/src/MongoDBBridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,9 @@ MongoDBBridge::MongoDBBridge(const boost::property_tree::ptree &pt) : CamInterfa
storage = rs::Storage(host, db);

actualFrame = 0;


index=-1;

storage.getScenes(frames);

if(continual) {
Expand Down Expand Up @@ -81,79 +83,113 @@ void MongoDBBridge::readConfig(const boost::property_tree::ptree &pt)

bool MongoDBBridge::setData(uima::CAS &tcas, uint64_t timestamp)
{
ros::NodeHandle n_("~");
double_t time_stamp; // Variable which store the value of queued time stamp

n_.getParam("ts",time_stamp); // getting the value of "ts" from the command arg and store in time_stamp.
n_.deleteParam("ts"); // deleting the "ts" variable.

MEASURE_TIME;
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

MEASURE_TIME should always be at the beginning of a method

const bool isNextFrame = timestamp == std::numeric_limits<uint64_t>::max();

if(actualFrame >= frames.size()) {
if(continual) {
storage.getScenes(frames);
if(actualFrame >= frames.size()) {
return false;
}
}
else if(loop) {
actualFrame = 0;
}
else {
outInfo("last frame. shuting down.");
cv::waitKey();
ros::shutdown();
return false;
}
}
if(isNextFrame) {
outInfo("default behaviour");
timestamp = frames[actualFrame];
outInfo("setting data from frame: " << actualFrame << " (" << timestamp << ")");

auto it= std::find(frames.begin(), frames.end(), time_stamp); // finding if the queued timestamp is in the frames vector

if(it== frames.end()){
outWarn("Timestamp Queried is not in the frame or Timestamp Query not enabled");
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is triggered on every iteration when the ts parameter is not set by the user.
Could you please change the method so that it checks if the timestamp parameter is set and only then do the required steps?

}
else if(timestamp < frames.size()) {
timestamp = frames[timestamp];
outInfo("setting data from frame with timestamp: (" << timestamp << ")");
else{
index= it- frames.begin(); // getting index value where time_stamp present
}
else if(timestamp >= frames.size()) {
if(std::find(frames.begin(), frames.end(), timestamp) == frames.end()) {
outWarn("timestamp asked for is not in database");
return false;
}
}

if(!storage.loadScene(*tcas.getBaseCas(), timestamp)) {
if(timestamp == 0) {
outInfo("loading frame failed. shuting down.");
ros::shutdown();
return false;
}
else {
outInfo("No frame with that timestamp");
return false;
}
}


if(playbackSpeed > 0.0 && isNextFrame) {
if(lastTimestamp > timestamp) {
lastTimestamp = timestamp;
simTimeLast = frames[actualFrame];
lastRun = ros::Time::now().toNSec();
}

uint64_t now = ros::Time::now().toNSec();
uint64_t simTime = (uint64_t)((now - lastRun) * playbackSpeed) + simTimeLast;
if(simTime <= timestamp) {
uint64_t sleepTime = (timestamp - simTime) / playbackSpeed;
outDebug("waiting for " << sleepTime / 1000000.0 << " ms.");
std::this_thread::sleep_for(std::chrono::nanoseconds(sleepTime));
}

now = ros::Time::now().toNSec();
simTimeLast = (uint64_t)((now - lastRun) * playbackSpeed) + simTimeLast;
lastRun = now;
}


++actualFrame;
if(!continual && !loop && actualFrame == frames.size()) {
_newData = false;
if(index!=-1){
timestamp = frames[index];
if(!storage.loadScene(*tcas.getBaseCas(), timestamp)) {
if(timestamp == 0) {
outInfo("loading frame failed. shuting down.");
ros::shutdown();
return false;
}
else {
outInfo("No frame with that timestamp");
return false;
}
}
if(!continual && !loop) {
_newData = false;
}

}
else{
if(actualFrame >= frames.size()) {
if(continual) {
storage.getScenes(frames);
if(actualFrame >= frames.size()) {
return false;
}
}
else if(loop) {
actualFrame = 0;
}
else {
outInfo("last frame. shuting down.");
cv::waitKey();
ros::shutdown();
return false;
}
}
if(isNextFrame) {
outInfo("default behaviour");
timestamp = frames[actualFrame];
outInfo("setting data from frame: " << actualFrame << " (" << timestamp << ")");
}
else if(timestamp < frames.size()) {
timestamp = frames[timestamp];
outInfo("setting data from frame with timestamp: (" << timestamp << ")");
}
else if(timestamp >= frames.size()) {
if(std::find(frames.begin(), frames.end(), timestamp) == frames.end()) {
outWarn("timestamp asked for is not in database");
return false;
}
}

if(!storage.loadScene(*tcas.getBaseCas(), timestamp)) {
if(timestamp == 0) {
outInfo("loading frame failed. shuting down.");
ros::shutdown();
return false;
}
else {
outInfo("No frame with that timestamp");
return false;
}
}


if(playbackSpeed > 0.0 && isNextFrame) {
if(lastTimestamp > timestamp) {
lastTimestamp = timestamp;
simTimeLast = frames[actualFrame];
lastRun = ros::Time::now().toNSec();
}

uint64_t now = ros::Time::now().toNSec();
uint64_t simTime = (uint64_t)((now - lastRun) * playbackSpeed) + simTimeLast;
if(simTime <= timestamp) {
uint64_t sleepTime = (timestamp - simTime) / playbackSpeed;
outDebug("waiting for " << sleepTime / 1000000.0 << " ms.");
std::this_thread::sleep_for(std::chrono::nanoseconds(sleepTime));
}

now = ros::Time::now().toNSec();
simTimeLast = (uint64_t)((now - lastRun) * playbackSpeed) + simTimeLast;
lastRun = now;
}


++actualFrame;
if(!continual && !loop && actualFrame == frames.size()) {
_newData = false;
}
}
return true;
}