source: flair-src/trunk/lib/FlairFilter/src/TrajectoryGenerator1D.cpp @ 15

Last change on this file since 15 was 15, checked in by Bayard Gildas, 5 years ago

sources reformatted with flair-format-dir script

File size: 2.2 KB
Line 
1// %flair:license{
2// This file is part of the Flair framework distributed under the
3// CECILL-C License, Version 1.0.
4// %flair:license}
5//  created:    2011/05/01
6//  filename:   TrajectoryGenerator1D.cpp
7//
8//  author:     Guillaume Sanahuja
9//              Copyright Heudiasyc UMR UTC/CNRS 7253
10//
11//  version:    $Id: $
12//
13//  purpose:    Class generating a trajectory in 1D
14//
15//
16/*********************************************************************/
17
18#include "TrajectoryGenerator1D.h"
19#include "TrajectoryGenerator1D_impl.h"
20#include <cvmatrix.h>
21#include <Layout.h>
22#include <LayoutPosition.h>
23
24using std::string;
25using namespace flair::core;
26using namespace flair::gui;
27
28namespace flair {
29namespace filter {
30
31TrajectoryGenerator1D::TrajectoryGenerator1D(const LayoutPosition *position,
32                                             string name, string unit)
33    : IODevice(position->getLayout(), name) {
34  pimpl_ = new TrajectoryGenerator1D_impl(this, position, name, unit);
35  AddDataToLog(pimpl_->output);
36}
37
38TrajectoryGenerator1D::~TrajectoryGenerator1D() { delete pimpl_; }
39
40cvmatrix *TrajectoryGenerator1D::Matrix(void) const { return pimpl_->output; }
41
42void TrajectoryGenerator1D::StartTraj(float start_pos, float end_pos) {
43  pimpl_->StartTraj(start_pos, end_pos);
44}
45
46// revoir l'interet du stop?
47void TrajectoryGenerator1D::StopTraj(void) { pimpl_->StopTraj(); }
48
49bool TrajectoryGenerator1D::IsRunning(void) const {
50  if (pimpl_->is_started == true) {
51    if (pimpl_->is_finished == true) {
52      return false;
53    } else {
54      return true;
55    }
56  } else {
57    return false;
58  }
59}
60
61float TrajectoryGenerator1D::Position(void) const {
62  return pimpl_->output->Value(0, 0);
63}
64
65void TrajectoryGenerator1D::Reset(void) {
66  if (IsRunning() == false) {
67    pimpl_->Reset();
68  } else {
69    Err("impossible while running\n");
70  }
71}
72
73void TrajectoryGenerator1D::SetPositionOffset(float value) {
74  pimpl_->pos_off = value;
75}
76
77float TrajectoryGenerator1D::Speed(void) const {
78  return pimpl_->output->Value(1, 0);
79}
80
81void TrajectoryGenerator1D::SetSpeedOffset(float value) {
82  pimpl_->vel_off = value;
83}
84
85void TrajectoryGenerator1D::Update(Time time) {
86  pimpl_->Update(time);
87  ProcessUpdate(pimpl_->output);
88}
89
90} // end namespace filter
91} // end namespace flair
Note: See TracBrowser for help on using the repository browser.