Skip to content

Commit 7b1e04d

Browse files
committed
renaming: object_tracker -> tracker
1 parent 8c2249f commit 7b1e04d

File tree

7 files changed

+22
-23
lines changed

7 files changed

+22
-23
lines changed

CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -162,7 +162,7 @@ set(dbot_SOURCES
162162
${dbot_SOURCE_DIR}/simple_shader_provider.cpp
163163
${dbot_SOURCE_DIR}/default_shader_provider.cpp
164164
${dbot_SOURCE_DIR}/file_shader_provider.cpp
165-
${dbot_SOURCE_DIR}/tracker/object_tracker.cpp
165+
${dbot_SOURCE_DIR}/tracker/tracker.cpp
166166
${dbot_SOURCE_DIR}/tracker/particle_tracker.cpp
167167
${dbot_SOURCE_DIR}/tracker/gaussian_tracker.cpp
168168
${dbot_SOURCE_DIR}/builder/rb_sensor_builder.cpp

source/dbot/tracker/gaussian_tracker.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@ GaussianTracker::GaussianTracker(
3030
const std::shared_ptr<ObjectModel>& object_model,
3131
double update_rate,
3232
bool center_object_frame)
33-
: ObjectTracker(object_model, update_rate, center_object_frame),
33+
: Tracker(object_model, update_rate, center_object_frame),
3434
filter_(filter),
3535
belief_(filter_->create_belief())
3636
{

source/dbot/tracker/gaussian_tracker.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@
2929

3030
#pragma once
3131

32-
#include <dbot/tracker/object_tracker.hpp>
32+
#include <dbot/tracker/tracker.hpp>
3333
#include <dbot/model/depth_pixel_model.hpp>
3434

3535
#include <fl/util/types.hpp>
@@ -40,7 +40,7 @@
4040

4141
namespace dbot
4242
{
43-
class GaussianTracker : public ObjectTracker
43+
class GaussianTracker : public Tracker
4444
{
4545
public:
4646
/* ---------------------------------------------------------------------- */

source/dbot/tracker/particle_tracker.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@ ParticleTracker::ParticleTracker(
3131
int evaluation_count,
3232
double update_rate,
3333
bool center_object_frame)
34-
: ObjectTracker(object_model, update_rate, center_object_frame),
34+
: Tracker(object_model, update_rate, center_object_frame),
3535
filter_(filter),
3636
evaluation_count_(evaluation_count)
3737
{

source/dbot/tracker/particle_tracker.hpp

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -32,22 +32,21 @@
3232

3333
#include <fl/model/transition/interface/transition_function.hpp>
3434

35-
#include <dbot/tracker/object_tracker.hpp>
35+
#include <dbot/tracker/tracker.hpp>
3636
#include <dbot/filter/rao_blackwell_coordinate_particle_filter.hpp>
3737

3838
namespace dbot
3939
{
4040
/**
4141
* \brief ParticleTracker
4242
*/
43-
class ParticleTracker : public ObjectTracker
43+
class ParticleTracker : public Tracker
4444
{
4545
public:
4646
typedef fl::TransitionFunction<State, Noise, Input> Transition;
4747
typedef RbSensor<State> Sensor;
4848

49-
typedef RaoBlackwellCoordinateParticleFilter<Transition,
50-
Sensor> Filter;
49+
typedef RaoBlackwellCoordinateParticleFilter<Transition, Sensor> Filter;
5150

5251
public:
5352
/**

source/dbot/tracker/object_tracker.cpp renamed to source/dbot/tracker/tracker.cpp

Lines changed: 11 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -12,11 +12,11 @@
1212
*/
1313

1414
#include <fl/util/profiling.hpp>
15-
#include <dbot/tracker/object_tracker.hpp>
15+
#include <dbot/tracker/tracker.hpp>
1616

1717
namespace dbot
1818
{
19-
ObjectTracker::ObjectTracker(const std::shared_ptr<ObjectModel> &object_model,
19+
Tracker::Tracker(const std::shared_ptr<ObjectModel> &object_model,
2020
double update_rate,
2121
bool center_object_frame)
2222
: object_model_(object_model),
@@ -26,7 +26,7 @@ ObjectTracker::ObjectTracker(const std::shared_ptr<ObjectModel> &object_model,
2626
{
2727
}
2828

29-
void ObjectTracker::initialize(const std::vector<State>& initial_states)
29+
void Tracker::initialize(const std::vector<State>& initial_states)
3030
{
3131
std::lock_guard<std::mutex> lock(mutex_);
3232

@@ -39,8 +39,8 @@ void ObjectTracker::initialize(const std::vector<State>& initial_states)
3939
moving_average_ = to_model_coordinate_system(on_initialize(states));
4040
}
4141

42-
void ObjectTracker::move_average(const ObjectTracker::State& new_state,
43-
ObjectTracker::State& moving_average,
42+
void Tracker::move_average(const Tracker::State& new_state,
43+
Tracker::State& moving_average,
4444
double update_rate)
4545
{
4646
for (int i = 0; i < moving_average.count(); i++)
@@ -68,7 +68,7 @@ void ObjectTracker::move_average(const ObjectTracker::State& new_state,
6868
}
6969
}
7070

71-
auto ObjectTracker::track(const Obsrv& image) -> State
71+
auto Tracker::track(const Obsrv& image) -> State
7272
{
7373
std::lock_guard<std::mutex> lock(mutex_);
7474

@@ -79,8 +79,8 @@ auto ObjectTracker::track(const Obsrv& image) -> State
7979
return moving_average_;
8080
}
8181

82-
auto ObjectTracker::to_center_coordinate_system(
83-
const ObjectTracker::State& state) -> State
82+
auto Tracker::to_center_coordinate_system(
83+
const Tracker::State& state) -> State
8484
{
8585
if (!center_object_frame_) return state;
8686

@@ -96,8 +96,8 @@ auto ObjectTracker::to_center_coordinate_system(
9696
}
9797

9898

99-
auto ObjectTracker::to_model_coordinate_system(
100-
const ObjectTracker::State& state) -> State
99+
auto Tracker::to_model_coordinate_system(
100+
const Tracker::State& state) -> State
101101
{
102102
if (!center_object_frame_) return state;
103103

@@ -112,7 +112,7 @@ auto ObjectTracker::to_model_coordinate_system(
112112
return model_state;
113113
}
114114

115-
ObjectTracker::Input ObjectTracker::zero_input() const
115+
Tracker::Input Tracker::zero_input() const
116116
{
117117
return Input::Zero(1);
118118
}

source/dbot/tracker/object_tracker.hpp renamed to source/dbot/tracker/tracker.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@ namespace dbot
3838
/**
3939
* \brief Abstract ObjectTracker context
4040
*/
41-
class ObjectTracker
41+
class Tracker
4242
{
4343
public:
4444
typedef osr::FreeFloatingRigidBodiesState<> State;
@@ -57,11 +57,11 @@ class ObjectTracker
5757
* \param update_rate
5858
* Moving average update rate
5959
*/
60-
ObjectTracker(const std::shared_ptr<ObjectModel>& object_model,
60+
Tracker(const std::shared_ptr<ObjectModel>& object_model,
6161
double update_rate,
6262
bool center_object_frame);
6363

64-
virtual ~ObjectTracker() { }
64+
virtual ~Tracker() { }
6565

6666
/**
6767
* \brief Hook function which is called during tracking

0 commit comments

Comments
 (0)