Skip to content

Commit 2e84cf3

Browse files
committed
Removed CameraData where it is not needed anymore
1 parent 639ed02 commit 2e84cf3

8 files changed

+5
-31
lines changed

src/dbot/tracker/builder/rbc_particle_filter_tracker_builder.hpp

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -77,18 +77,15 @@ class RbcParticleFilterTrackerBuilder
7777
/**
7878
* \brief Creates a RbcParticleFilterTrackerBuilder
7979
* \param param Builder and sub-builder parameters
80-
* \param camera_data Tracker camera data object
8180
*/
8281
RbcParticleFilterTrackerBuilder(
8382
const std::shared_ptr<StateTransitionBuilder>& state_transition_builder,
8483
const std::shared_ptr<ObservationModelBuilder>& obsrv_model_builder,
8584
const std::shared_ptr<ObjectModel>& object_model,
86-
const std::shared_ptr<CameraData>& camera_data,
8785
const Parameters& params)
8886
: state_transition_builder_(state_transition_builder),
8987
obsrv_model_builder_(obsrv_model_builder),
9088
object_model_(object_model),
91-
camera_data_(camera_data),
9289
params_(params)
9390
{
9491
}
@@ -103,7 +100,6 @@ class RbcParticleFilterTrackerBuilder
103100
auto tracker = std::make_shared<RbcParticleFilterObjectTracker>(
104101
filter,
105102
object_model_,
106-
camera_data_,
107103
params_.evaluation_count,
108104
params_.moving_average_update_rate);
109105

@@ -162,7 +158,6 @@ class RbcParticleFilterTrackerBuilder
162158
std::shared_ptr<StateTransitionBuilder> state_transition_builder_;
163159
std::shared_ptr<ObservationModelBuilder> obsrv_model_builder_;
164160
std::shared_ptr<ObjectModel> object_model_;
165-
std::shared_ptr<CameraData> camera_data_;
166161
Parameters params_;
167162
};
168163
}

src/dbot/tracker/builder/rms_gaussian_filter_tracker_builder.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@ RmsGaussianFilterTrackerBuilder::build()
4141
auto filter = create_filter(object_model);
4242

4343
auto tracker = std::make_shared<RmsGaussianFilterObjectTracker>(
44-
filter, object_model, camera_data_, param_.update_rate);
44+
filter, object_model, param_.update_rate);
4545

4646
return tracker;
4747
}

src/dbot/tracker/object_tracker.cpp

Lines changed: 0 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -17,10 +17,8 @@
1717
namespace dbot
1818
{
1919
ObjectTracker::ObjectTracker(const std::shared_ptr<ObjectModel> &object_model,
20-
const std::shared_ptr<CameraData> &camera_data,
2120
double update_rate)
2221
: object_model_(object_model),
23-
camera_data_(camera_data),
2422
update_rate_(update_rate),
2523
moving_average_(object_model_->count_parts())
2624
{
@@ -39,11 +37,6 @@ void ObjectTracker::initialize(const std::vector<State>& initial_states)
3937
moving_average_ = to_model_coordinate_system(on_initialize(states));
4038
}
4139

42-
const std::shared_ptr<CameraData>& ObjectTracker::camera_data() const
43-
{
44-
return camera_data_;
45-
}
46-
4740
void ObjectTracker::move_average(const ObjectTracker::State& new_state,
4841
ObjectTracker::State& moving_average,
4942
double update_rate)

src/dbot/tracker/object_tracker.hpp

Lines changed: 0 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,6 @@
2626
#include <memory>
2727
#include <mutex>
2828

29-
#include <dbot/util/camera_data.hpp>
3029
#include <dbot/util/object_model.hpp>
3130

3231
#include <osr/pose_vector.hpp>
@@ -55,13 +54,10 @@ class ObjectTracker
5554
* Rbc particle filter instance
5655
* \param object_model
5756
* Object model instance
58-
* \param camera_data
59-
* Camera data container
6057
* \param update_rate
6158
* Moving average update rate
6259
*/
6360
ObjectTracker(const std::shared_ptr<ObjectModel>& object_model,
64-
const std::shared_ptr<CameraData>& camera_data,
6561
double update_rate);
6662

6763
virtual ~ObjectTracker() { }
@@ -110,11 +106,6 @@ class ObjectTracker
110106
*/
111107
State to_model_coordinate_system(const State& state);
112108

113-
/**
114-
* \brief Returns camera data
115-
*/
116-
const std::shared_ptr<CameraData> &camera_data() const;
117-
118109
/**
119110
* \brief Updates the moving average with the new state using the specified
120111
* update rate. The update rate is the weight on the new state. That
@@ -139,7 +130,6 @@ class ObjectTracker
139130

140131
protected:
141132
std::shared_ptr<ObjectModel> object_model_;
142-
std::shared_ptr<CameraData> camera_data_;
143133
State moving_average_;
144134
double update_rate_;
145135
std::mutex mutex_;

src/dbot/tracker/rbc_particle_filter_object_tracker.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -28,10 +28,9 @@ namespace dbot
2828
RbcParticleFilterObjectTracker::RbcParticleFilterObjectTracker(
2929
const std::shared_ptr<Filter>& filter,
3030
const std::shared_ptr<ObjectModel>& object_model,
31-
const std::shared_ptr<dbot::CameraData>& camera_data,
3231
int evaluation_count,
3332
double update_rate)
34-
: ObjectTracker(object_model, camera_data, update_rate),
33+
: ObjectTracker(object_model, update_rate),
3534
filter_(filter),
3635
evaluation_count_(evaluation_count)
3736
{
@@ -41,7 +40,7 @@ auto RbcParticleFilterObjectTracker::on_initialize(
4140
const std::vector<State>& initial_states) -> State
4241
{
4342
filter_->set_particles(initial_states);
44-
filter_->filter(camera_data_->depth_image_vector(), zero_input());
43+
// filter_->filter(camera_data_->depth_image_vector(), zero_input());
4544
filter_->resample(evaluation_count_ / object_model_->count_parts());
4645

4746
State delta_mean = filter_->belief().mean();

src/dbot/tracker/rbc_particle_filter_object_tracker.hpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,6 @@ class RbcParticleFilterObjectTracker : public ObjectTracker
6565
RbcParticleFilterObjectTracker(
6666
const std::shared_ptr<Filter>& filter,
6767
const std::shared_ptr<ObjectModel>& object_model,
68-
const std::shared_ptr<CameraData>& camera_data,
6968
int evaluation_count,
7069
double update_rate);
7170

src/dbot/tracker/rms_gaussian_filter_object_tracker.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -28,9 +28,8 @@ namespace dbot
2828
RmsGaussianFilterObjectTracker::RmsGaussianFilterObjectTracker(
2929
const std::shared_ptr<Filter>& filter,
3030
const std::shared_ptr<ObjectModel>& object_model,
31-
const std::shared_ptr<CameraData>& camera_data,
3231
double update_rate)
33-
: ObjectTracker(object_model, camera_data, update_rate),
32+
: ObjectTracker(object_model, update_rate),
3433
filter_(filter),
3534
belief_(filter_->create_belief())
3635
{

src/dbot/tracker/rms_gaussian_filter_object_tracker.hpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@
3030
#pragma once
3131

3232
#include <dbot/tracker/object_tracker.hpp>
33-
#include <dbot/model/observation/depth_pixel_observation_model.hpp>
33+
#include <dbot/model/depth_pixel_observation_model.hpp>
3434

3535
#include <fl/util/types.hpp>
3636
#include <fl/model/process/linear_state_transition_model.hpp>
@@ -94,7 +94,6 @@ class RmsGaussianFilterObjectTracker : public ObjectTracker
9494
RmsGaussianFilterObjectTracker(
9595
const std::shared_ptr<Filter>& filter,
9696
const std::shared_ptr<ObjectModel>& object_model,
97-
const std::shared_ptr<CameraData>& camera_data,
9897
double update_rate);
9998

10099
/**

0 commit comments

Comments
 (0)