[libcamera-devel,v3,8/8] libcamera: pipeline: rkisp1: Remove Timeline
diff mbox series

Message ID 20201123221234.485933-9-niklas.soderlund@ragnatech.se
State Superseded
Delegated to: Niklas Söderlund
Headers show
Series
  • libcamera: Add helper for controls that take effect with a delay
Related show

Commit Message

Niklas Söderlund Nov. 23, 2020, 10:12 p.m. UTC
There are no users left of the Timeline and there is no longer a need to
keep emulating a start of exposure event as the CSI-2 resciver reports
it. Remove the Timeline helper and what's left of it's integration in
the pipeline.

There is no functional change as nothing i the pipeline uses the
Timeline.

Signed-off-by: Niklas Söderlund <niklas.soderlund@ragnatech.se>
---
 src/libcamera/pipeline/rkisp1/meson.build  |   1 -
 src/libcamera/pipeline/rkisp1/rkisp1.cpp   |  45 ----
 src/libcamera/pipeline/rkisp1/timeline.cpp | 227 ---------------------
 src/libcamera/pipeline/rkisp1/timeline.h   |  71 -------
 4 files changed, 344 deletions(-)
 delete mode 100644 src/libcamera/pipeline/rkisp1/timeline.cpp
 delete mode 100644 src/libcamera/pipeline/rkisp1/timeline.h

Comments

Jacopo Mondi Nov. 27, 2020, 11:06 a.m. UTC | #1
Hi Niklas,

On Mon, Nov 23, 2020 at 11:12:34PM +0100, Niklas Söderlund wrote:
> There are no users left of the Timeline and there is no longer a need to
> keep emulating a start of exposure event as the CSI-2 resciver reports
> it. Remove the Timeline helper and what's left of it's integration in
> the pipeline.
>
> There is no functional change as nothing i the pipeline uses the
> Timeline.
>
> Signed-off-by: Niklas Söderlund <niklas.soderlund@ragnatech.se>
> ---
>  src/libcamera/pipeline/rkisp1/meson.build  |   1 -
>  src/libcamera/pipeline/rkisp1/rkisp1.cpp   |  45 ----
>  src/libcamera/pipeline/rkisp1/timeline.cpp | 227 ---------------------
>  src/libcamera/pipeline/rkisp1/timeline.h   |  71 -------

Nice!
Reviewed-by: Jacopo Mondi <jacopo@jmondi.org>

Thanks
  j

>  4 files changed, 344 deletions(-)
>  delete mode 100644 src/libcamera/pipeline/rkisp1/timeline.cpp
>  delete mode 100644 src/libcamera/pipeline/rkisp1/timeline.h
>
> diff --git a/src/libcamera/pipeline/rkisp1/meson.build b/src/libcamera/pipeline/rkisp1/meson.build
> index 5cd40d949d543fa9..cad66535c25f8cc0 100644
> --- a/src/libcamera/pipeline/rkisp1/meson.build
> +++ b/src/libcamera/pipeline/rkisp1/meson.build
> @@ -3,5 +3,4 @@
>  libcamera_sources += files([
>      'rkisp1.cpp',
>      'rkisp1_path.cpp',
> -    'timeline.cpp',
>  ])
> diff --git a/src/libcamera/pipeline/rkisp1/rkisp1.cpp b/src/libcamera/pipeline/rkisp1/rkisp1.cpp
> index 3662a53ac4a43fcd..c2b61e88ec34aa60 100644
> --- a/src/libcamera/pipeline/rkisp1/rkisp1.cpp
> +++ b/src/libcamera/pipeline/rkisp1/rkisp1.cpp
> @@ -33,7 +33,6 @@
>  #include "libcamera/internal/v4l2_videodevice.h"
>
>  #include "rkisp1_path.h"
> -#include "timeline.h"
>
>  namespace libcamera {
>
> @@ -42,12 +41,6 @@ LOG_DEFINE_CATEGORY(RkISP1)
>  class PipelineHandlerRkISP1;
>  class RkISP1CameraData;
>
> -enum RkISP1ActionType {
> -	SetSensor,
> -	SOE,
> -	QueueBuffers,
> -};
> -
>  struct RkISP1FrameInfo {
>  	unsigned int frame;
>  	Request *request;
> @@ -80,41 +73,6 @@ private:
>  	std::map<unsigned int, RkISP1FrameInfo *> frameInfo_;
>  };
>
> -class RkISP1Timeline : public Timeline
> -{
> -public:
> -	RkISP1Timeline()
> -		: Timeline()
> -	{
> -		setDelay(SetSensor, -1, 5);
> -		setDelay(SOE, 0, -1);
> -		setDelay(QueueBuffers, -1, 10);
> -	}
> -
> -	void bufferReady(FrameBuffer *buffer)
> -	{
> -		/*
> -		 * Calculate SOE by taking the end of DMA set by the kernel and applying
> -		 * the time offsets provideprovided by the IPA to find the best estimate
> -		 * of SOE.
> -		 */
> -
> -		ASSERT(frameOffset(SOE) == 0);
> -
> -		utils::time_point soe = std::chrono::time_point<utils::clock>()
> -			+ std::chrono::nanoseconds(buffer->metadata().timestamp)
> -			+ timeOffset(SOE);
> -
> -		notifyStartOfExposure(buffer->metadata().sequence, soe);
> -	}
> -
> -	void setDelay(unsigned int type, int frame, int msdelay)
> -	{
> -		utils::duration delay = std::chrono::milliseconds(msdelay);
> -		setRawDelay(type, frame, delay);
> -	}
> -};
> -
>  class RkISP1CameraData : public CameraData
>  {
>  public:
> @@ -140,7 +98,6 @@ public:
>  	unsigned int frame_;
>  	std::vector<IPABuffer> ipaBuffers_;
>  	RkISP1Frames frameInfo_;
> -	RkISP1Timeline timeline_;
>
>  	RkISP1MainPath *mainPath_;
>  	RkISP1SelfPath *selfPath_;
> @@ -887,8 +844,6 @@ void PipelineHandlerRkISP1::stop(Camera *camera)
>
>  	data->ipa_->stop();
>
> -	data->timeline_.reset();
> -
>  	data->frameInfo_.clear();
>
>  	freeBuffers(camera);
> diff --git a/src/libcamera/pipeline/rkisp1/timeline.cpp b/src/libcamera/pipeline/rkisp1/timeline.cpp
> deleted file mode 100644
> index 6b83bbe5b5892531..0000000000000000
> --- a/src/libcamera/pipeline/rkisp1/timeline.cpp
> +++ /dev/null
> @@ -1,227 +0,0 @@
> -/* SPDX-License-Identifier: LGPL-2.1-or-later */
> -/*
> - * Copyright (C) 2019, Google Inc.
> - *
> - * timeline.cpp - Timeline for per-frame control
> - */
> -
> -#include "timeline.h"
> -
> -#include "libcamera/internal/log.h"
> -
> -/**
> - * \file timeline.h
> - * \brief Timeline for per-frame control
> - */
> -
> -namespace libcamera {
> -
> -LOG_DEFINE_CATEGORY(Timeline)
> -
> -/**
> - * \class FrameAction
> - * \brief Action that can be schedule on a Timeline
> - *
> - * A frame action is an event schedule to be executed on a Timeline. A frame
> - * action has two primal attributes a frame number and a type.
> - *
> - * The frame number describes the frame to which the action is associated. The
> - * type is a numerical ID which identifies the action within the pipeline and
> - * IPA protocol.
> - */
> -
> -/**
> - * \class Timeline
> - * \brief Executor of FrameAction
> - *
> - * The timeline has three primary functions:
> - *
> - * 1. Keep track of the Start of Exposure (SOE) for every frame processed by
> - *    the hardware. Using this information it shall keep an up-to-date estimate
> - *    of the frame interval (time between two consecutive SOE events).
> - *
> - *    The estimated frame interval together with recorded SOE events are the
> - *    foundation for how the timeline schedule FrameAction at specific points
> - *    in time.
> - *    \todo Improve the frame interval estimation algorithm.
> - *
> - * 2. Keep track of current delays for different types of actions. The delays
> - *    for different actions might differ during a capture session. Exposure time
> - *    effects the over all FPS and different ISP parameters might impacts its
> - *    processing time.
> - *
> - *    The action type delays shall be updated by the IPA in conjunction with
> - *    how it changes the capture parameters.
> - *
> - * 3. Schedule actions on the timeline. This is the process of taking a
> - *    FrameAction which contains an abstract description of what frame and
> - *    what type of action it contains and turning that into an time point
> - *    and make sure the action is executed at that time.
> - */
> -
> -Timeline::Timeline()
> -	: frameInterval_(0)
> -{
> -	timer_.timeout.connect(this, &Timeline::timeout);
> -}
> -
> -/**
> - * \brief Reset and stop the timeline
> - *
> - * The timeline needs to be reset when the timeline should no longer execute
> - * actions. A timeline should be reset between two capture sessions to prevent
> - * the old capture session to effect the second one.
> - */
> -void Timeline::reset()
> -{
> -	timer_.stop();
> -
> -	actions_.clear();
> -	history_.clear();
> -}
> -
> -/**
> - * \brief Schedule an action on the timeline
> - * \param[in] action FrameAction to schedule
> - *
> - * The act of scheduling an action to the timeline is the process of taking
> - * the properties of the action (type, frame and time offsets) and translating
> - * that to a time point using the current values for the action type timings
> - * value recorded in the timeline. If an action is scheduled too late, execute
> - * it immediately.
> - */
> -void Timeline::scheduleAction(std::unique_ptr<FrameAction> action)
> -{
> -	unsigned int lastFrame;
> -	utils::time_point lastTime;
> -
> -	if (history_.empty()) {
> -		lastFrame = 0;
> -		lastTime = std::chrono::steady_clock::now();
> -	} else {
> -		lastFrame = history_.back().first;
> -		lastTime = history_.back().second;
> -	}
> -
> -	/*
> -	 * Calculate when the action shall be schedule by first finding out how
> -	 * many frames in the future the action acts on and then add the actions
> -	 * frame offset. After the spatial frame offset is found out translate
> -	 * that to a time point by using the last estimated start of exposure
> -	 * (SOE) as the fixed offset. Lastly add the action time offset to the
> -	 * time point.
> -	 */
> -	int frame = action->frame() - lastFrame + frameOffset(action->type());
> -	utils::time_point deadline = lastTime + frame * frameInterval_
> -		+ timeOffset(action->type());
> -
> -	utils::time_point now = std::chrono::steady_clock::now();
> -	if (deadline < now) {
> -		LOG(Timeline, Warning)
> -			<< "Action scheduled too late "
> -			<< utils::time_point_to_string(deadline)
> -			<< ", run now " << utils::time_point_to_string(now);
> -		action->run();
> -	} else {
> -		actions_.emplace(deadline, std::move(action));
> -		updateDeadline();
> -	}
> -}
> -
> -void Timeline::notifyStartOfExposure(unsigned int frame, utils::time_point time)
> -{
> -	history_.push_back(std::make_pair(frame, time));
> -
> -	if (history_.size() <= HISTORY_DEPTH / 2)
> -		return;
> -
> -	while (history_.size() > HISTORY_DEPTH)
> -		history_.pop_front();
> -
> -	/* Update esitmated time between two start of exposures. */
> -	utils::duration sumExposures(0);
> -	unsigned int numExposures = 0;
> -
> -	utils::time_point lastTime;
> -	for (auto it = history_.begin(); it != history_.end(); it++) {
> -		if (it != history_.begin()) {
> -			sumExposures += it->second - lastTime;
> -			numExposures++;
> -		}
> -
> -		lastTime = it->second;
> -	}
> -
> -	frameInterval_ = sumExposures;
> -	if (numExposures)
> -		frameInterval_ /= numExposures;
> -}
> -
> -int Timeline::frameOffset(unsigned int type) const
> -{
> -	const auto it = delays_.find(type);
> -	if (it == delays_.end()) {
> -		LOG(Timeline, Error)
> -			<< "No frame offset set for action type " << type;
> -		return 0;
> -	}
> -
> -	return it->second.first;
> -}
> -
> -utils::duration Timeline::timeOffset(unsigned int type) const
> -{
> -	const auto it = delays_.find(type);
> -	if (it == delays_.end()) {
> -		LOG(Timeline, Error)
> -			<< "No time offset set for action type " << type;
> -		return utils::duration::zero();
> -	}
> -
> -	return it->second.second;
> -}
> -
> -void Timeline::setRawDelay(unsigned int type, int frame, utils::duration time)
> -{
> -	delays_[type] = std::make_pair(frame, time);
> -}
> -
> -void Timeline::updateDeadline()
> -{
> -	if (actions_.empty())
> -		return;
> -
> -	const utils::time_point &deadline = actions_.begin()->first;
> -
> -	if (timer_.isRunning() && deadline >= timer_.deadline())
> -		return;
> -
> -	if (deadline <= std::chrono::steady_clock::now()) {
> -		timeout(&timer_);
> -		return;
> -	}
> -
> -	timer_.start(deadline);
> -}
> -
> -void Timeline::timeout([[maybe_unused]] Timer *timer)
> -{
> -	utils::time_point now = std::chrono::steady_clock::now();
> -
> -	for (auto it = actions_.begin(); it != actions_.end();) {
> -		const utils::time_point &sched = it->first;
> -
> -		if (sched > now)
> -			break;
> -
> -		FrameAction *action = it->second.get();
> -
> -		action->run();
> -
> -		it = actions_.erase(it);
> -	}
> -
> -	updateDeadline();
> -}
> -
> -} /* namespace libcamera */
> diff --git a/src/libcamera/pipeline/rkisp1/timeline.h b/src/libcamera/pipeline/rkisp1/timeline.h
> deleted file mode 100644
> index 35a085159b8f545b..0000000000000000
> --- a/src/libcamera/pipeline/rkisp1/timeline.h
> +++ /dev/null
> @@ -1,71 +0,0 @@
> -/* SPDX-License-Identifier: LGPL-2.1-or-later */
> -/*
> - * Copyright (C) 2019, Google Inc.
> - *
> - * timeline.h - Timeline for per-frame controls
> - */
> -#ifndef __LIBCAMERA_TIMELINE_H__
> -#define __LIBCAMERA_TIMELINE_H__
> -
> -#include <list>
> -#include <map>
> -
> -#include "libcamera/internal/timer.h"
> -#include "libcamera/internal/utils.h"
> -
> -namespace libcamera {
> -
> -class FrameAction
> -{
> -public:
> -	FrameAction(unsigned int frame, unsigned int type)
> -		: frame_(frame), type_(type) {}
> -
> -	virtual ~FrameAction() = default;
> -
> -	unsigned int frame() const { return frame_; }
> -	unsigned int type() const { return type_; }
> -
> -	virtual void run() = 0;
> -
> -private:
> -	unsigned int frame_;
> -	unsigned int type_;
> -};
> -
> -class Timeline
> -{
> -public:
> -	Timeline();
> -	virtual ~Timeline() = default;
> -
> -	virtual void reset();
> -	virtual void scheduleAction(std::unique_ptr<FrameAction> action);
> -	virtual void notifyStartOfExposure(unsigned int frame, utils::time_point time);
> -
> -	utils::duration frameInterval() const { return frameInterval_; }
> -
> -protected:
> -	int frameOffset(unsigned int type) const;
> -	utils::duration timeOffset(unsigned int type) const;
> -
> -	void setRawDelay(unsigned int type, int frame, utils::duration time);
> -
> -	std::map<unsigned int, std::pair<int, utils::duration>> delays_;
> -
> -private:
> -	static constexpr unsigned int HISTORY_DEPTH = 10;
> -
> -	void timeout(Timer *timer);
> -	void updateDeadline();
> -
> -	std::list<std::pair<unsigned int, utils::time_point>> history_;
> -	std::multimap<utils::time_point, std::unique_ptr<FrameAction>> actions_;
> -	utils::duration frameInterval_;
> -
> -	Timer timer_;
> -};
> -
> -} /* namespace libcamera */
> -
> -#endif /* __LIBCAMERA_TIMELINE_H__ */
> --
> 2.29.2
>
> _______________________________________________
> libcamera-devel mailing list
> libcamera-devel@lists.libcamera.org
> https://lists.libcamera.org/listinfo/libcamera-devel
Laurent Pinchart Dec. 5, 2020, 1:39 a.m. UTC | #2
Hi Niklas,

Thank you for the patch.

On Mon, Nov 23, 2020 at 11:12:34PM +0100, Niklas Söderlund wrote:
> There are no users left of the Timeline and there is no longer a need to
> keep emulating a start of exposure event as the CSI-2 resciver reports
> it. Remove the Timeline helper and what's left of it's integration in
> the pipeline.
> 
> There is no functional change as nothing i the pipeline uses the
> Timeline.
> 
> Signed-off-by: Niklas Söderlund <niklas.soderlund@ragnatech.se>

Reviewed-by: Laurent Pinchart <laurent.pinchart@ideasonboard.com>

> ---
>  src/libcamera/pipeline/rkisp1/meson.build  |   1 -
>  src/libcamera/pipeline/rkisp1/rkisp1.cpp   |  45 ----
>  src/libcamera/pipeline/rkisp1/timeline.cpp | 227 ---------------------
>  src/libcamera/pipeline/rkisp1/timeline.h   |  71 -------
>  4 files changed, 344 deletions(-)
>  delete mode 100644 src/libcamera/pipeline/rkisp1/timeline.cpp
>  delete mode 100644 src/libcamera/pipeline/rkisp1/timeline.h
> 
> diff --git a/src/libcamera/pipeline/rkisp1/meson.build b/src/libcamera/pipeline/rkisp1/meson.build
> index 5cd40d949d543fa9..cad66535c25f8cc0 100644
> --- a/src/libcamera/pipeline/rkisp1/meson.build
> +++ b/src/libcamera/pipeline/rkisp1/meson.build
> @@ -3,5 +3,4 @@
>  libcamera_sources += files([
>      'rkisp1.cpp',
>      'rkisp1_path.cpp',
> -    'timeline.cpp',
>  ])
> diff --git a/src/libcamera/pipeline/rkisp1/rkisp1.cpp b/src/libcamera/pipeline/rkisp1/rkisp1.cpp
> index 3662a53ac4a43fcd..c2b61e88ec34aa60 100644
> --- a/src/libcamera/pipeline/rkisp1/rkisp1.cpp
> +++ b/src/libcamera/pipeline/rkisp1/rkisp1.cpp
> @@ -33,7 +33,6 @@
>  #include "libcamera/internal/v4l2_videodevice.h"
>  
>  #include "rkisp1_path.h"
> -#include "timeline.h"
>  
>  namespace libcamera {
>  
> @@ -42,12 +41,6 @@ LOG_DEFINE_CATEGORY(RkISP1)
>  class PipelineHandlerRkISP1;
>  class RkISP1CameraData;
>  
> -enum RkISP1ActionType {
> -	SetSensor,
> -	SOE,
> -	QueueBuffers,
> -};
> -
>  struct RkISP1FrameInfo {
>  	unsigned int frame;
>  	Request *request;
> @@ -80,41 +73,6 @@ private:
>  	std::map<unsigned int, RkISP1FrameInfo *> frameInfo_;
>  };
>  
> -class RkISP1Timeline : public Timeline
> -{
> -public:
> -	RkISP1Timeline()
> -		: Timeline()
> -	{
> -		setDelay(SetSensor, -1, 5);
> -		setDelay(SOE, 0, -1);
> -		setDelay(QueueBuffers, -1, 10);
> -	}
> -
> -	void bufferReady(FrameBuffer *buffer)
> -	{
> -		/*
> -		 * Calculate SOE by taking the end of DMA set by the kernel and applying
> -		 * the time offsets provideprovided by the IPA to find the best estimate
> -		 * of SOE.
> -		 */
> -
> -		ASSERT(frameOffset(SOE) == 0);
> -
> -		utils::time_point soe = std::chrono::time_point<utils::clock>()
> -			+ std::chrono::nanoseconds(buffer->metadata().timestamp)
> -			+ timeOffset(SOE);
> -
> -		notifyStartOfExposure(buffer->metadata().sequence, soe);
> -	}
> -
> -	void setDelay(unsigned int type, int frame, int msdelay)
> -	{
> -		utils::duration delay = std::chrono::milliseconds(msdelay);
> -		setRawDelay(type, frame, delay);
> -	}
> -};
> -
>  class RkISP1CameraData : public CameraData
>  {
>  public:
> @@ -140,7 +98,6 @@ public:
>  	unsigned int frame_;
>  	std::vector<IPABuffer> ipaBuffers_;
>  	RkISP1Frames frameInfo_;
> -	RkISP1Timeline timeline_;
>  
>  	RkISP1MainPath *mainPath_;
>  	RkISP1SelfPath *selfPath_;
> @@ -887,8 +844,6 @@ void PipelineHandlerRkISP1::stop(Camera *camera)
>  
>  	data->ipa_->stop();
>  
> -	data->timeline_.reset();
> -
>  	data->frameInfo_.clear();
>  
>  	freeBuffers(camera);
> diff --git a/src/libcamera/pipeline/rkisp1/timeline.cpp b/src/libcamera/pipeline/rkisp1/timeline.cpp
> deleted file mode 100644
> index 6b83bbe5b5892531..0000000000000000
> --- a/src/libcamera/pipeline/rkisp1/timeline.cpp
> +++ /dev/null
> @@ -1,227 +0,0 @@
> -/* SPDX-License-Identifier: LGPL-2.1-or-later */
> -/*
> - * Copyright (C) 2019, Google Inc.
> - *
> - * timeline.cpp - Timeline for per-frame control
> - */
> -
> -#include "timeline.h"
> -
> -#include "libcamera/internal/log.h"
> -
> -/**
> - * \file timeline.h
> - * \brief Timeline for per-frame control
> - */
> -
> -namespace libcamera {
> -
> -LOG_DEFINE_CATEGORY(Timeline)
> -
> -/**
> - * \class FrameAction
> - * \brief Action that can be schedule on a Timeline
> - *
> - * A frame action is an event schedule to be executed on a Timeline. A frame
> - * action has two primal attributes a frame number and a type.
> - *
> - * The frame number describes the frame to which the action is associated. The
> - * type is a numerical ID which identifies the action within the pipeline and
> - * IPA protocol.
> - */
> -
> -/**
> - * \class Timeline
> - * \brief Executor of FrameAction
> - *
> - * The timeline has three primary functions:
> - *
> - * 1. Keep track of the Start of Exposure (SOE) for every frame processed by
> - *    the hardware. Using this information it shall keep an up-to-date estimate
> - *    of the frame interval (time between two consecutive SOE events).
> - *
> - *    The estimated frame interval together with recorded SOE events are the
> - *    foundation for how the timeline schedule FrameAction at specific points
> - *    in time.
> - *    \todo Improve the frame interval estimation algorithm.
> - *
> - * 2. Keep track of current delays for different types of actions. The delays
> - *    for different actions might differ during a capture session. Exposure time
> - *    effects the over all FPS and different ISP parameters might impacts its
> - *    processing time.
> - *
> - *    The action type delays shall be updated by the IPA in conjunction with
> - *    how it changes the capture parameters.
> - *
> - * 3. Schedule actions on the timeline. This is the process of taking a
> - *    FrameAction which contains an abstract description of what frame and
> - *    what type of action it contains and turning that into an time point
> - *    and make sure the action is executed at that time.
> - */
> -
> -Timeline::Timeline()
> -	: frameInterval_(0)
> -{
> -	timer_.timeout.connect(this, &Timeline::timeout);
> -}
> -
> -/**
> - * \brief Reset and stop the timeline
> - *
> - * The timeline needs to be reset when the timeline should no longer execute
> - * actions. A timeline should be reset between two capture sessions to prevent
> - * the old capture session to effect the second one.
> - */
> -void Timeline::reset()
> -{
> -	timer_.stop();
> -
> -	actions_.clear();
> -	history_.clear();
> -}
> -
> -/**
> - * \brief Schedule an action on the timeline
> - * \param[in] action FrameAction to schedule
> - *
> - * The act of scheduling an action to the timeline is the process of taking
> - * the properties of the action (type, frame and time offsets) and translating
> - * that to a time point using the current values for the action type timings
> - * value recorded in the timeline. If an action is scheduled too late, execute
> - * it immediately.
> - */
> -void Timeline::scheduleAction(std::unique_ptr<FrameAction> action)
> -{
> -	unsigned int lastFrame;
> -	utils::time_point lastTime;
> -
> -	if (history_.empty()) {
> -		lastFrame = 0;
> -		lastTime = std::chrono::steady_clock::now();
> -	} else {
> -		lastFrame = history_.back().first;
> -		lastTime = history_.back().second;
> -	}
> -
> -	/*
> -	 * Calculate when the action shall be schedule by first finding out how
> -	 * many frames in the future the action acts on and then add the actions
> -	 * frame offset. After the spatial frame offset is found out translate
> -	 * that to a time point by using the last estimated start of exposure
> -	 * (SOE) as the fixed offset. Lastly add the action time offset to the
> -	 * time point.
> -	 */
> -	int frame = action->frame() - lastFrame + frameOffset(action->type());
> -	utils::time_point deadline = lastTime + frame * frameInterval_
> -		+ timeOffset(action->type());
> -
> -	utils::time_point now = std::chrono::steady_clock::now();
> -	if (deadline < now) {
> -		LOG(Timeline, Warning)
> -			<< "Action scheduled too late "
> -			<< utils::time_point_to_string(deadline)
> -			<< ", run now " << utils::time_point_to_string(now);
> -		action->run();
> -	} else {
> -		actions_.emplace(deadline, std::move(action));
> -		updateDeadline();
> -	}
> -}
> -
> -void Timeline::notifyStartOfExposure(unsigned int frame, utils::time_point time)
> -{
> -	history_.push_back(std::make_pair(frame, time));
> -
> -	if (history_.size() <= HISTORY_DEPTH / 2)
> -		return;
> -
> -	while (history_.size() > HISTORY_DEPTH)
> -		history_.pop_front();
> -
> -	/* Update esitmated time between two start of exposures. */
> -	utils::duration sumExposures(0);
> -	unsigned int numExposures = 0;
> -
> -	utils::time_point lastTime;
> -	for (auto it = history_.begin(); it != history_.end(); it++) {
> -		if (it != history_.begin()) {
> -			sumExposures += it->second - lastTime;
> -			numExposures++;
> -		}
> -
> -		lastTime = it->second;
> -	}
> -
> -	frameInterval_ = sumExposures;
> -	if (numExposures)
> -		frameInterval_ /= numExposures;
> -}
> -
> -int Timeline::frameOffset(unsigned int type) const
> -{
> -	const auto it = delays_.find(type);
> -	if (it == delays_.end()) {
> -		LOG(Timeline, Error)
> -			<< "No frame offset set for action type " << type;
> -		return 0;
> -	}
> -
> -	return it->second.first;
> -}
> -
> -utils::duration Timeline::timeOffset(unsigned int type) const
> -{
> -	const auto it = delays_.find(type);
> -	if (it == delays_.end()) {
> -		LOG(Timeline, Error)
> -			<< "No time offset set for action type " << type;
> -		return utils::duration::zero();
> -	}
> -
> -	return it->second.second;
> -}
> -
> -void Timeline::setRawDelay(unsigned int type, int frame, utils::duration time)
> -{
> -	delays_[type] = std::make_pair(frame, time);
> -}
> -
> -void Timeline::updateDeadline()
> -{
> -	if (actions_.empty())
> -		return;
> -
> -	const utils::time_point &deadline = actions_.begin()->first;
> -
> -	if (timer_.isRunning() && deadline >= timer_.deadline())
> -		return;
> -
> -	if (deadline <= std::chrono::steady_clock::now()) {
> -		timeout(&timer_);
> -		return;
> -	}
> -
> -	timer_.start(deadline);
> -}
> -
> -void Timeline::timeout([[maybe_unused]] Timer *timer)
> -{
> -	utils::time_point now = std::chrono::steady_clock::now();
> -
> -	for (auto it = actions_.begin(); it != actions_.end();) {
> -		const utils::time_point &sched = it->first;
> -
> -		if (sched > now)
> -			break;
> -
> -		FrameAction *action = it->second.get();
> -
> -		action->run();
> -
> -		it = actions_.erase(it);
> -	}
> -
> -	updateDeadline();
> -}
> -
> -} /* namespace libcamera */
> diff --git a/src/libcamera/pipeline/rkisp1/timeline.h b/src/libcamera/pipeline/rkisp1/timeline.h
> deleted file mode 100644
> index 35a085159b8f545b..0000000000000000
> --- a/src/libcamera/pipeline/rkisp1/timeline.h
> +++ /dev/null
> @@ -1,71 +0,0 @@
> -/* SPDX-License-Identifier: LGPL-2.1-or-later */
> -/*
> - * Copyright (C) 2019, Google Inc.
> - *
> - * timeline.h - Timeline for per-frame controls
> - */
> -#ifndef __LIBCAMERA_TIMELINE_H__
> -#define __LIBCAMERA_TIMELINE_H__
> -
> -#include <list>
> -#include <map>
> -
> -#include "libcamera/internal/timer.h"
> -#include "libcamera/internal/utils.h"
> -
> -namespace libcamera {
> -
> -class FrameAction
> -{
> -public:
> -	FrameAction(unsigned int frame, unsigned int type)
> -		: frame_(frame), type_(type) {}
> -
> -	virtual ~FrameAction() = default;
> -
> -	unsigned int frame() const { return frame_; }
> -	unsigned int type() const { return type_; }
> -
> -	virtual void run() = 0;
> -
> -private:
> -	unsigned int frame_;
> -	unsigned int type_;
> -};
> -
> -class Timeline
> -{
> -public:
> -	Timeline();
> -	virtual ~Timeline() = default;
> -
> -	virtual void reset();
> -	virtual void scheduleAction(std::unique_ptr<FrameAction> action);
> -	virtual void notifyStartOfExposure(unsigned int frame, utils::time_point time);
> -
> -	utils::duration frameInterval() const { return frameInterval_; }
> -
> -protected:
> -	int frameOffset(unsigned int type) const;
> -	utils::duration timeOffset(unsigned int type) const;
> -
> -	void setRawDelay(unsigned int type, int frame, utils::duration time);
> -
> -	std::map<unsigned int, std::pair<int, utils::duration>> delays_;
> -
> -private:
> -	static constexpr unsigned int HISTORY_DEPTH = 10;
> -
> -	void timeout(Timer *timer);
> -	void updateDeadline();
> -
> -	std::list<std::pair<unsigned int, utils::time_point>> history_;
> -	std::multimap<utils::time_point, std::unique_ptr<FrameAction>> actions_;
> -	utils::duration frameInterval_;
> -
> -	Timer timer_;
> -};
> -
> -} /* namespace libcamera */
> -
> -#endif /* __LIBCAMERA_TIMELINE_H__ */

Patch
diff mbox series

diff --git a/src/libcamera/pipeline/rkisp1/meson.build b/src/libcamera/pipeline/rkisp1/meson.build
index 5cd40d949d543fa9..cad66535c25f8cc0 100644
--- a/src/libcamera/pipeline/rkisp1/meson.build
+++ b/src/libcamera/pipeline/rkisp1/meson.build
@@ -3,5 +3,4 @@ 
 libcamera_sources += files([
     'rkisp1.cpp',
     'rkisp1_path.cpp',
-    'timeline.cpp',
 ])
diff --git a/src/libcamera/pipeline/rkisp1/rkisp1.cpp b/src/libcamera/pipeline/rkisp1/rkisp1.cpp
index 3662a53ac4a43fcd..c2b61e88ec34aa60 100644
--- a/src/libcamera/pipeline/rkisp1/rkisp1.cpp
+++ b/src/libcamera/pipeline/rkisp1/rkisp1.cpp
@@ -33,7 +33,6 @@ 
 #include "libcamera/internal/v4l2_videodevice.h"
 
 #include "rkisp1_path.h"
-#include "timeline.h"
 
 namespace libcamera {
 
@@ -42,12 +41,6 @@  LOG_DEFINE_CATEGORY(RkISP1)
 class PipelineHandlerRkISP1;
 class RkISP1CameraData;
 
-enum RkISP1ActionType {
-	SetSensor,
-	SOE,
-	QueueBuffers,
-};
-
 struct RkISP1FrameInfo {
 	unsigned int frame;
 	Request *request;
@@ -80,41 +73,6 @@  private:
 	std::map<unsigned int, RkISP1FrameInfo *> frameInfo_;
 };
 
-class RkISP1Timeline : public Timeline
-{
-public:
-	RkISP1Timeline()
-		: Timeline()
-	{
-		setDelay(SetSensor, -1, 5);
-		setDelay(SOE, 0, -1);
-		setDelay(QueueBuffers, -1, 10);
-	}
-
-	void bufferReady(FrameBuffer *buffer)
-	{
-		/*
-		 * Calculate SOE by taking the end of DMA set by the kernel and applying
-		 * the time offsets provideprovided by the IPA to find the best estimate
-		 * of SOE.
-		 */
-
-		ASSERT(frameOffset(SOE) == 0);
-
-		utils::time_point soe = std::chrono::time_point<utils::clock>()
-			+ std::chrono::nanoseconds(buffer->metadata().timestamp)
-			+ timeOffset(SOE);
-
-		notifyStartOfExposure(buffer->metadata().sequence, soe);
-	}
-
-	void setDelay(unsigned int type, int frame, int msdelay)
-	{
-		utils::duration delay = std::chrono::milliseconds(msdelay);
-		setRawDelay(type, frame, delay);
-	}
-};
-
 class RkISP1CameraData : public CameraData
 {
 public:
@@ -140,7 +98,6 @@  public:
 	unsigned int frame_;
 	std::vector<IPABuffer> ipaBuffers_;
 	RkISP1Frames frameInfo_;
-	RkISP1Timeline timeline_;
 
 	RkISP1MainPath *mainPath_;
 	RkISP1SelfPath *selfPath_;
@@ -887,8 +844,6 @@  void PipelineHandlerRkISP1::stop(Camera *camera)
 
 	data->ipa_->stop();
 
-	data->timeline_.reset();
-
 	data->frameInfo_.clear();
 
 	freeBuffers(camera);
diff --git a/src/libcamera/pipeline/rkisp1/timeline.cpp b/src/libcamera/pipeline/rkisp1/timeline.cpp
deleted file mode 100644
index 6b83bbe5b5892531..0000000000000000
--- a/src/libcamera/pipeline/rkisp1/timeline.cpp
+++ /dev/null
@@ -1,227 +0,0 @@ 
-/* SPDX-License-Identifier: LGPL-2.1-or-later */
-/*
- * Copyright (C) 2019, Google Inc.
- *
- * timeline.cpp - Timeline for per-frame control
- */
-
-#include "timeline.h"
-
-#include "libcamera/internal/log.h"
-
-/**
- * \file timeline.h
- * \brief Timeline for per-frame control
- */
-
-namespace libcamera {
-
-LOG_DEFINE_CATEGORY(Timeline)
-
-/**
- * \class FrameAction
- * \brief Action that can be schedule on a Timeline
- *
- * A frame action is an event schedule to be executed on a Timeline. A frame
- * action has two primal attributes a frame number and a type.
- *
- * The frame number describes the frame to which the action is associated. The
- * type is a numerical ID which identifies the action within the pipeline and
- * IPA protocol.
- */
-
-/**
- * \class Timeline
- * \brief Executor of FrameAction
- *
- * The timeline has three primary functions:
- *
- * 1. Keep track of the Start of Exposure (SOE) for every frame processed by
- *    the hardware. Using this information it shall keep an up-to-date estimate
- *    of the frame interval (time between two consecutive SOE events).
- *
- *    The estimated frame interval together with recorded SOE events are the
- *    foundation for how the timeline schedule FrameAction at specific points
- *    in time.
- *    \todo Improve the frame interval estimation algorithm.
- *
- * 2. Keep track of current delays for different types of actions. The delays
- *    for different actions might differ during a capture session. Exposure time
- *    effects the over all FPS and different ISP parameters might impacts its
- *    processing time.
- *
- *    The action type delays shall be updated by the IPA in conjunction with
- *    how it changes the capture parameters.
- *
- * 3. Schedule actions on the timeline. This is the process of taking a
- *    FrameAction which contains an abstract description of what frame and
- *    what type of action it contains and turning that into an time point
- *    and make sure the action is executed at that time.
- */
-
-Timeline::Timeline()
-	: frameInterval_(0)
-{
-	timer_.timeout.connect(this, &Timeline::timeout);
-}
-
-/**
- * \brief Reset and stop the timeline
- *
- * The timeline needs to be reset when the timeline should no longer execute
- * actions. A timeline should be reset between two capture sessions to prevent
- * the old capture session to effect the second one.
- */
-void Timeline::reset()
-{
-	timer_.stop();
-
-	actions_.clear();
-	history_.clear();
-}
-
-/**
- * \brief Schedule an action on the timeline
- * \param[in] action FrameAction to schedule
- *
- * The act of scheduling an action to the timeline is the process of taking
- * the properties of the action (type, frame and time offsets) and translating
- * that to a time point using the current values for the action type timings
- * value recorded in the timeline. If an action is scheduled too late, execute
- * it immediately.
- */
-void Timeline::scheduleAction(std::unique_ptr<FrameAction> action)
-{
-	unsigned int lastFrame;
-	utils::time_point lastTime;
-
-	if (history_.empty()) {
-		lastFrame = 0;
-		lastTime = std::chrono::steady_clock::now();
-	} else {
-		lastFrame = history_.back().first;
-		lastTime = history_.back().second;
-	}
-
-	/*
-	 * Calculate when the action shall be schedule by first finding out how
-	 * many frames in the future the action acts on and then add the actions
-	 * frame offset. After the spatial frame offset is found out translate
-	 * that to a time point by using the last estimated start of exposure
-	 * (SOE) as the fixed offset. Lastly add the action time offset to the
-	 * time point.
-	 */
-	int frame = action->frame() - lastFrame + frameOffset(action->type());
-	utils::time_point deadline = lastTime + frame * frameInterval_
-		+ timeOffset(action->type());
-
-	utils::time_point now = std::chrono::steady_clock::now();
-	if (deadline < now) {
-		LOG(Timeline, Warning)
-			<< "Action scheduled too late "
-			<< utils::time_point_to_string(deadline)
-			<< ", run now " << utils::time_point_to_string(now);
-		action->run();
-	} else {
-		actions_.emplace(deadline, std::move(action));
-		updateDeadline();
-	}
-}
-
-void Timeline::notifyStartOfExposure(unsigned int frame, utils::time_point time)
-{
-	history_.push_back(std::make_pair(frame, time));
-
-	if (history_.size() <= HISTORY_DEPTH / 2)
-		return;
-
-	while (history_.size() > HISTORY_DEPTH)
-		history_.pop_front();
-
-	/* Update esitmated time between two start of exposures. */
-	utils::duration sumExposures(0);
-	unsigned int numExposures = 0;
-
-	utils::time_point lastTime;
-	for (auto it = history_.begin(); it != history_.end(); it++) {
-		if (it != history_.begin()) {
-			sumExposures += it->second - lastTime;
-			numExposures++;
-		}
-
-		lastTime = it->second;
-	}
-
-	frameInterval_ = sumExposures;
-	if (numExposures)
-		frameInterval_ /= numExposures;
-}
-
-int Timeline::frameOffset(unsigned int type) const
-{
-	const auto it = delays_.find(type);
-	if (it == delays_.end()) {
-		LOG(Timeline, Error)
-			<< "No frame offset set for action type " << type;
-		return 0;
-	}
-
-	return it->second.first;
-}
-
-utils::duration Timeline::timeOffset(unsigned int type) const
-{
-	const auto it = delays_.find(type);
-	if (it == delays_.end()) {
-		LOG(Timeline, Error)
-			<< "No time offset set for action type " << type;
-		return utils::duration::zero();
-	}
-
-	return it->second.second;
-}
-
-void Timeline::setRawDelay(unsigned int type, int frame, utils::duration time)
-{
-	delays_[type] = std::make_pair(frame, time);
-}
-
-void Timeline::updateDeadline()
-{
-	if (actions_.empty())
-		return;
-
-	const utils::time_point &deadline = actions_.begin()->first;
-
-	if (timer_.isRunning() && deadline >= timer_.deadline())
-		return;
-
-	if (deadline <= std::chrono::steady_clock::now()) {
-		timeout(&timer_);
-		return;
-	}
-
-	timer_.start(deadline);
-}
-
-void Timeline::timeout([[maybe_unused]] Timer *timer)
-{
-	utils::time_point now = std::chrono::steady_clock::now();
-
-	for (auto it = actions_.begin(); it != actions_.end();) {
-		const utils::time_point &sched = it->first;
-
-		if (sched > now)
-			break;
-
-		FrameAction *action = it->second.get();
-
-		action->run();
-
-		it = actions_.erase(it);
-	}
-
-	updateDeadline();
-}
-
-} /* namespace libcamera */
diff --git a/src/libcamera/pipeline/rkisp1/timeline.h b/src/libcamera/pipeline/rkisp1/timeline.h
deleted file mode 100644
index 35a085159b8f545b..0000000000000000
--- a/src/libcamera/pipeline/rkisp1/timeline.h
+++ /dev/null
@@ -1,71 +0,0 @@ 
-/* SPDX-License-Identifier: LGPL-2.1-or-later */
-/*
- * Copyright (C) 2019, Google Inc.
- *
- * timeline.h - Timeline for per-frame controls
- */
-#ifndef __LIBCAMERA_TIMELINE_H__
-#define __LIBCAMERA_TIMELINE_H__
-
-#include <list>
-#include <map>
-
-#include "libcamera/internal/timer.h"
-#include "libcamera/internal/utils.h"
-
-namespace libcamera {
-
-class FrameAction
-{
-public:
-	FrameAction(unsigned int frame, unsigned int type)
-		: frame_(frame), type_(type) {}
-
-	virtual ~FrameAction() = default;
-
-	unsigned int frame() const { return frame_; }
-	unsigned int type() const { return type_; }
-
-	virtual void run() = 0;
-
-private:
-	unsigned int frame_;
-	unsigned int type_;
-};
-
-class Timeline
-{
-public:
-	Timeline();
-	virtual ~Timeline() = default;
-
-	virtual void reset();
-	virtual void scheduleAction(std::unique_ptr<FrameAction> action);
-	virtual void notifyStartOfExposure(unsigned int frame, utils::time_point time);
-
-	utils::duration frameInterval() const { return frameInterval_; }
-
-protected:
-	int frameOffset(unsigned int type) const;
-	utils::duration timeOffset(unsigned int type) const;
-
-	void setRawDelay(unsigned int type, int frame, utils::duration time);
-
-	std::map<unsigned int, std::pair<int, utils::duration>> delays_;
-
-private:
-	static constexpr unsigned int HISTORY_DEPTH = 10;
-
-	void timeout(Timer *timer);
-	void updateDeadline();
-
-	std::list<std::pair<unsigned int, utils::time_point>> history_;
-	std::multimap<utils::time_point, std::unique_ptr<FrameAction>> actions_;
-	utils::duration frameInterval_;
-
-	Timer timer_;
-};
-
-} /* namespace libcamera */
-
-#endif /* __LIBCAMERA_TIMELINE_H__ */