Skip to content
Snippets Groups Projects
Commit a4c46a30 authored by Joan Solà Ortega's avatar Joan Solà Ortega
Browse files

Throw an error if getState() is called in an unitialized ProcessorMotion

parent e0992431
No related branches found
No related tags found
1 merge request!157Kfpackmanager
This commit is part of merge request !157. Comments created here will be created in the context of that merge request.
...@@ -286,7 +286,7 @@ void ProcessorMotion::process(CaptureBasePtr _incoming_ptr) ...@@ -286,7 +286,7 @@ void ProcessorMotion::process(CaptureBasePtr _incoming_ptr)
void ProcessorMotion::getState(const TimeStamp& _ts, Eigen::VectorXs& _x) void ProcessorMotion::getState(const TimeStamp& _ts, Eigen::VectorXs& _x)
{ {
CaptureMotionPtr capture_motion; CaptureMotionPtr capture_motion;
if (_ts >= origin_ptr_->getTimeStamp()) if (origin_ptr_ && _ts >= origin_ptr_->getTimeStamp())
// timestamp found in the current processor buffer // timestamp found in the current processor buffer
capture_motion = last_ptr_; capture_motion = last_ptr_;
else else
...@@ -302,8 +302,12 @@ void ProcessorMotion::getState(const TimeStamp& _ts, Eigen::VectorXs& _x) ...@@ -302,8 +302,12 @@ void ProcessorMotion::getState(const TimeStamp& _ts, Eigen::VectorXs& _x)
statePlusDelta(state_0, delta, dt, _x); statePlusDelta(state_0, delta, dt, _x);
} }
else else
{
// We could not find any CaptureMotion for the time stamp requested // We could not find any CaptureMotion for the time stamp requested
std::runtime_error("Could not find any Capture for the time stamp requested"); WOLF_ERROR("Could not find any Capture for the time stamp requested. ");
WOLF_TRACE("Did you forget to call Problem::setPrior() in your application?")
throw std::runtime_error("Could not find any Capture for the time stamp requested. Did you forget to call Problem::setPrior() in your application?");
}
} }
CaptureMotionPtr ProcessorMotion::findCaptureContainingTimeStamp(const TimeStamp& _ts) const CaptureMotionPtr ProcessorMotion::findCaptureContainingTimeStamp(const TimeStamp& _ts) const
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment