Skip to content

Commit dce659f

Browse files
committed
renaming types: ObsrvModel -> Sensor, ObservationModel -> Sensor, ObservationFunction -> SensorFunction etc.
ProcessModel -> Transition, TransitionModel -> Transition etc.
1 parent 524812c commit dce659f

17 files changed

+86
-86
lines changed

source/dbot/builder/object_transition_model_builder.hpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -56,18 +56,18 @@ struct ObjectStateTrait
5656
};
5757

5858
template <typename State>
59-
class ObjectTransitionModelBuilder
60-
: public StateTransitionFunctionBuilder<
59+
class ObjectTransitionBuilder
60+
: public TransitionFunctionBuilder<
6161
State,
6262
typename ObjectStateTrait<State>::Noise,
6363
typename ObjectStateTrait<State>::Input>
6464
{
6565
public:
66-
typedef fl::StateTransitionFunction<State,
66+
typedef fl::TransitionFunction<State,
6767
typename ObjectStateTrait<State>::Noise,
6868
typename ObjectStateTrait<State>::Input>
6969
Model;
70-
typedef fl::LinearStateTransitionModel<
70+
typedef fl::LinearTransition<
7171
State,
7272
typename ObjectStateTrait<State>::Noise,
7373
typename ObjectStateTrait<State>::Input> DerivedModel;
@@ -80,7 +80,7 @@ class ObjectTransitionModelBuilder
8080
int part_count;
8181
};
8282

83-
ObjectTransitionModelBuilder(const Parameters& param) : param_(param) {}
83+
ObjectTransitionBuilder(const Parameters& param) : param_(param) {}
8484
virtual std::shared_ptr<Model> build() const
8585
{
8686
auto model = std::shared_ptr<DerivedModel>(

source/dbot/builder/rb_observation_model_builder.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,5 +35,5 @@
3535

3636
namespace dbot
3737
{
38-
template class RbObservationModelBuilder<osr::FreeFloatingRigidBodiesState<>>;
38+
template class RbSensorBuilder<osr::FreeFloatingRigidBodiesState<>>;
3939
}

source/dbot/builder/rb_observation_model_builder.h

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -59,7 +59,7 @@ class NoGpuSupportException : public std::exception
5959
};
6060

6161
template <typename State>
62-
class RbObservationModelBuilder
62+
class RbSensorBuilder
6363
{
6464
public:
6565
struct Parameters
@@ -92,10 +92,10 @@ class RbObservationModelBuilder
9292
std::string geometry_shader_file;
9393
};
9494

95-
typedef RbObservationModel<State> Model;
95+
typedef RbSensor<State> Model;
9696

9797
public:
98-
RbObservationModelBuilder(const std::shared_ptr<ObjectModel>& object_model,
98+
RbSensorBuilder(const std::shared_ptr<ObjectModel>& object_model,
9999
const std::shared_ptr<CameraData>& camera_data,
100100
const Parameters& params);
101101

source/dbot/builder/rb_observation_model_builder.hpp

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@
4040
namespace dbot
4141
{
4242
template <typename State>
43-
RbObservationModelBuilder<State>::RbObservationModelBuilder(
43+
RbSensorBuilder<State>::RbSensorBuilder(
4444
const std::shared_ptr<ObjectModel>& object_model,
4545
const std::shared_ptr<CameraData>& camera_data,
4646
const Parameters& params)
@@ -49,7 +49,7 @@ RbObservationModelBuilder<State>::RbObservationModelBuilder(
4949
}
5050

5151
template <typename State>
52-
auto RbObservationModelBuilder<State>::build() const -> std::shared_ptr<Model>
52+
auto RbSensorBuilder<State>::build() const -> std::shared_ptr<Model>
5353
{
5454
std::shared_ptr<Model> obsrv_model;
5555

@@ -66,7 +66,7 @@ auto RbObservationModelBuilder<State>::build() const -> std::shared_ptr<Model>
6666
}
6767

6868
template <typename State>
69-
auto RbObservationModelBuilder<State>::create_gpu_based_model() const
69+
auto RbSensorBuilder<State>::create_gpu_based_model() const
7070
-> std::shared_ptr<Model>
7171
{
7272
#ifdef DBOT_BUILD_GPU
@@ -96,7 +96,7 @@ auto RbObservationModelBuilder<State>::create_gpu_based_model() const
9696
}
9797

9898
template <typename State>
99-
auto RbObservationModelBuilder<State>::create_shader_provider() const
99+
auto RbSensorBuilder<State>::create_shader_provider() const
100100
-> std::shared_ptr<ShaderProvider>
101101
{
102102
if (params_.use_custom_shaders)
@@ -111,7 +111,7 @@ auto RbObservationModelBuilder<State>::create_shader_provider() const
111111
}
112112

113113
template <typename State>
114-
auto RbObservationModelBuilder<State>::create_cpu_based_model() const
114+
auto RbSensorBuilder<State>::create_cpu_based_model() const
115115
-> std::shared_ptr<Model>
116116
{
117117
auto pixel_model = create_pixel_model();
@@ -133,7 +133,7 @@ auto RbObservationModelBuilder<State>::create_cpu_based_model() const
133133
}
134134

135135
template <typename State>
136-
auto RbObservationModelBuilder<State>::create_pixel_model() const
136+
auto RbSensorBuilder<State>::create_pixel_model() const
137137
-> std::shared_ptr<KinectPixelModel>
138138
{
139139
std::shared_ptr<KinectPixelModel> kinect_pixel_observation_model(
@@ -144,7 +144,7 @@ auto RbObservationModelBuilder<State>::create_pixel_model() const
144144
}
145145

146146
template <typename State>
147-
auto RbObservationModelBuilder<State>::create_occlusion_process() const
147+
auto RbSensorBuilder<State>::create_occlusion_process() const
148148
-> std::shared_ptr<OcclusionModel>
149149
{
150150
std::shared_ptr<OcclusionModel> occlusion_process(
@@ -155,7 +155,7 @@ auto RbObservationModelBuilder<State>::create_occlusion_process() const
155155
}
156156

157157
template <typename State>
158-
auto RbObservationModelBuilder<State>::create_renderer() const
158+
auto RbSensorBuilder<State>::create_renderer() const
159159
-> std::shared_ptr<RigidBodyRenderer>
160160
{
161161
std::shared_ptr<RigidBodyRenderer> renderer(new RigidBodyRenderer(

source/dbot/builder/rbc_particle_filter_tracker_builder.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,7 @@
2828
//namespace dbot
2929
//{
3030
//RbcParticleFilterTrackerBuilder::RbcParticleFilterTrackerBuilder(
31-
// const std::shared_ptr<StateTransitionFunctionBuilder>&
31+
// const std::shared_ptr<TransitionFunctionBuilder>&
3232
// state_transition_builder,
3333
// const CameraData& camera_data)
3434
// : state_transition_builder_(state_transition_builder),
@@ -44,7 +44,7 @@
4444
// double max_kl_divergence) -> std::shared_ptr<Filter>
4545

4646
//auto RbcParticleFilterTrackerBuilder::create_object_transition_model() const
47-
// -> std::shared_ptr<StateTransition>
47+
// -> std::shared_ptr<Transition>
4848

4949

5050
//ObjectModel RbcParticleFilterTrackerBuilder::create_object_model(

source/dbot/builder/rbc_particle_filter_tracker_builder.hpp

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -52,18 +52,18 @@ class RbcParticleFilterTrackerBuilder
5252
typedef typename Tracker::Input Input;
5353

5454
/* == Model Builder Interfaces ========================================== */
55-
typedef StateTransitionFunctionBuilder<State, Noise, Input>
56-
StateTransitionBuilder;
57-
typedef RbObservationModelBuilder<State> ObservationModelBuilder;
55+
typedef TransitionFunctionBuilder<State, Noise, Input>
56+
TransitionBuilder;
57+
typedef RbSensorBuilder<State> SensorBuilder;
5858

5959
/* == Model Interfaces ================================================== */
60-
typedef fl::StateTransitionFunction<State, Noise, Input> StateTransition;
61-
typedef RbObservationModel<State> ObservationModel;
62-
typedef typename ObservationModel::Observation Obsrv;
60+
typedef fl::TransitionFunction<State, Noise, Input> Transition;
61+
typedef RbSensor<State> Sensor;
62+
typedef typename Sensor::Observation Obsrv;
6363

6464
/* == Filter algorithm ================================================== */
65-
typedef RaoBlackwellCoordinateParticleFilter<StateTransition,
66-
ObservationModel> Filter;
65+
typedef RaoBlackwellCoordinateParticleFilter<Transition,
66+
Sensor> Filter;
6767

6868
/* == Tracker parameters ================================================ */
6969
struct Parameters
@@ -79,8 +79,8 @@ class RbcParticleFilterTrackerBuilder
7979
* \param param Builder and sub-builder parameters
8080
*/
8181
RbcParticleFilterTrackerBuilder(
82-
const std::shared_ptr<StateTransitionBuilder>& state_transition_builder,
83-
const std::shared_ptr<ObservationModelBuilder>& obsrv_model_builder,
82+
const std::shared_ptr<TransitionBuilder>& state_transition_builder,
83+
const std::shared_ptr<SensorBuilder>& obsrv_model_builder,
8484
const std::shared_ptr<ObjectModel>& object_model,
8585
const Parameters& params)
8686
: state_transition_builder_(state_transition_builder),
@@ -155,8 +155,8 @@ class RbcParticleFilterTrackerBuilder
155155
}
156156

157157
protected:
158-
std::shared_ptr<StateTransitionBuilder> state_transition_builder_;
159-
std::shared_ptr<ObservationModelBuilder> obsrv_model_builder_;
158+
std::shared_ptr<TransitionBuilder> state_transition_builder_;
159+
std::shared_ptr<SensorBuilder> obsrv_model_builder_;
160160
std::shared_ptr<ObjectModel> object_model_;
161161
Parameters params_;
162162
};

source/dbot/builder/rms_gaussian_filter_tracker_builder.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -78,7 +78,7 @@ auto RmsGaussianFilterTrackerBuilder::create_filter(
7878
auto RmsGaussianFilterTrackerBuilder::create_obsrv_model(
7979
const std::shared_ptr<ObjectModel>& object_model,
8080
const std::shared_ptr<CameraData>& camera_data,
81-
const Parameters::Observation& param) const -> ObservationModel
81+
const Parameters::Observation& param) const -> Sensor
8282
{
8383
typedef RmsGaussianFilterObjectTracker::PixelModel PixelModel;
8484
typedef RmsGaussianFilterObjectTracker::TailModel TailModel;
@@ -95,7 +95,7 @@ auto RmsGaussianFilterTrackerBuilder::create_obsrv_model(
9595
auto body_tail_pixel_model =
9696
BodyTailModel(pixel_obsrv_model, tail_obsrv_model, param.tail_weight);
9797

98-
return ObservationModel(body_tail_pixel_model, camera_data->pixels());
98+
return Sensor(body_tail_pixel_model, camera_data->pixels());
9999
}
100100

101101
std::shared_ptr<ObjectModel>
@@ -109,10 +109,10 @@ RmsGaussianFilterTrackerBuilder::create_object_model(
109109
}
110110

111111
auto RmsGaussianFilterTrackerBuilder::create_object_transition_model(
112-
const ObjectTransitionModelBuilder<RmsGaussianFilterTrackerBuilder::State>::
113-
Parameters& param) const -> StateTransition
112+
const ObjectTransitionBuilder<RmsGaussianFilterTrackerBuilder::State>::
113+
Parameters& param) const -> Transition
114114
{
115-
ObjectTransitionModelBuilder<State> process_builder(param);
115+
ObjectTransitionBuilder<State> process_builder(param);
116116
auto process = process_builder.build_model();
117117

118118
return process;

source/dbot/builder/rms_gaussian_filter_tracker_builder.hpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -50,8 +50,8 @@ class RmsGaussianFilterTrackerBuilder
5050
typedef RmsGaussianFilterObjectTracker::Obsrv Obsrv;
5151
typedef RmsGaussianFilterObjectTracker::Filter Filter;
5252
typedef RmsGaussianFilterObjectTracker::Quadrature Quadrature;
53-
typedef RmsGaussianFilterObjectTracker::StateTransition StateTransition;
54-
typedef RmsGaussianFilterObjectTracker::ObservationModel ObservationModel;
53+
typedef RmsGaussianFilterObjectTracker::Transition Transition;
54+
typedef RmsGaussianFilterObjectTracker::Sensor Sensor;
5555

5656
struct Parameters
5757
{
@@ -71,7 +71,7 @@ class RmsGaussianFilterTrackerBuilder
7171

7272
ObjectResourceIdentifier ori;
7373
Observation observation;
74-
ObjectTransitionModelBuilder<State>::Parameters
74+
ObjectTransitionBuilder<State>::Parameters
7575
object_transition;
7676
};
7777

@@ -101,8 +101,8 @@ class RmsGaussianFilterTrackerBuilder
101101
* \brief Creates a Linear object transition function used in the
102102
* filter
103103
*/
104-
StateTransition create_object_transition_model(
105-
const ObjectTransitionModelBuilder<State>::Parameters& param)
104+
Transition create_object_transition_model(
105+
const ObjectTransitionBuilder<State>::Parameters& param)
106106
const;
107107

108108
/**
@@ -112,7 +112,7 @@ class RmsGaussianFilterTrackerBuilder
112112
* \throws NoGpuSupportException if compile with DBOT_BUILD_GPU=OFF and
113113
* attempting to build a tracker with GPU support
114114
*/
115-
ObservationModel create_obsrv_model(
115+
Sensor create_obsrv_model(
116116
const std::shared_ptr<ObjectModel>& object_model,
117117
const std::shared_ptr<CameraData>& camera_data,
118118
const Parameters::Observation& param) const;

source/dbot/builder/state_transition_function_builder.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -29,10 +29,10 @@ namespace dbot
2929
{
3030

3131
template <typename State, typename Noise, typename Input>
32-
class StateTransitionFunctionBuilder
32+
class TransitionFunctionBuilder
3333
{
3434
public:
35-
typedef fl::StateTransitionFunction<State, Noise, Input> Model;
35+
typedef fl::TransitionFunction<State, Noise, Input> Model;
3636

3737
public:
3838
virtual std::shared_ptr<Model> build() const = 0;

source/dbot/filter/rao_blackwell_coordinate_particle_filter.hpp

Lines changed: 11 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -41,27 +41,27 @@
4141

4242
namespace dbot
4343
{
44-
template <typename ProcessModel, typename ObservationModel>
44+
template <typename Transition, typename Sensor>
4545
class RaoBlackwellCoordinateParticleFilter
4646
{
4747
public:
48-
typedef typename ProcessModel::State State;
49-
typedef typename ProcessModel::Input Input;
50-
typedef typename ProcessModel::Noise Noise;
48+
typedef typename Transition::State State;
49+
typedef typename Transition::Input Input;
50+
typedef typename Transition::Noise Noise;
5151

5252
typedef Eigen::Array<State, -1, 1> StateArray;
5353
typedef Eigen::Array<fl::Real, -1, 1> RealArray;
5454
typedef Eigen::Array<int, -1, 1> IntArray;
5555

56-
typedef typename ObservationModel::Observation Observation;
56+
typedef typename Sensor::Observation Observation;
5757

5858
typedef fl::DiscreteDistribution<State> Belief;
5959

6060
public:
6161
/// constructor and destructor *********************************************
6262
RaoBlackwellCoordinateParticleFilter(
63-
const std::shared_ptr<ProcessModel> process_model,
64-
const std::shared_ptr<ObservationModel> observation_model,
63+
const std::shared_ptr<Transition> process_model,
64+
const std::shared_ptr<Sensor> observation_model,
6565
const std::vector<std::vector<int>>& sampling_blocks,
6666
const fl::Real& max_kl_divergence = 0)
6767
: observation_model_(observation_model),
@@ -172,12 +172,12 @@ class RaoBlackwellCoordinateParticleFilter
172172
observation_model_->reset();
173173
}
174174

175-
std::shared_ptr<ObservationModel> observation_model()
175+
std::shared_ptr<Sensor> observation_model()
176176
{
177177
return observation_model_;
178178
}
179179

180-
std::shared_ptr<ProcessModel> process_model()
180+
std::shared_ptr<Transition> process_model()
181181
{
182182
return process_model_;
183183
}
@@ -192,8 +192,8 @@ class RaoBlackwellCoordinateParticleFilter
192192
RealArray loglikes_;
193193

194194
// models
195-
std::shared_ptr<ObservationModel> observation_model_;
196-
std::shared_ptr<ProcessModel> process_model_;
195+
std::shared_ptr<Sensor> observation_model_;
196+
std::shared_ptr<Transition> process_model_;
197197

198198
// parameters
199199
std::vector<std::vector<int>> sampling_blocks_;

0 commit comments

Comments
 (0)