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

Last change on this file since 10 was 10, checked in by Sanahuja Guillaume, 6 years ago

lic

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 { namespace filter {
29
30TrajectoryGenerator1D::TrajectoryGenerator1D(const LayoutPosition* position,string name,string unit) : IODevice(position->getLayout(),name) {
31    pimpl_=new TrajectoryGenerator1D_impl(this,position,name,unit);
32    AddDataToLog(pimpl_->output);
33}
34
35TrajectoryGenerator1D::~TrajectoryGenerator1D() {
36    delete pimpl_;
37}
38
39cvmatrix *TrajectoryGenerator1D::Matrix(void) const {
40    return pimpl_->output;
41}
42
43void TrajectoryGenerator1D::StartTraj(float start_pos,float end_pos) {
44    pimpl_->StartTraj(start_pos,end_pos);
45}
46
47//revoir l'interet du stop?
48void TrajectoryGenerator1D::StopTraj(void) {
49    pimpl_->StopTraj();
50}
51
52bool TrajectoryGenerator1D::IsRunning(void) const {
53    if(pimpl_->is_started==true) {
54        if(pimpl_->is_finished==true) {
55            return false;
56        } else {
57            return true;
58        }
59    } else {
60        return false;
61    }
62}
63
64float TrajectoryGenerator1D::Position(void) const {
65    return pimpl_->output->Value(0,0);
66}
67
68void TrajectoryGenerator1D::Reset(void) {
69    if(IsRunning()==false) {
70        pimpl_->Reset();
71    } else {
72        Err("impossible while running\n");
73    }
74}
75
76void TrajectoryGenerator1D::SetPositionOffset(float value) {
77    pimpl_->pos_off=value;
78}
79
80float TrajectoryGenerator1D::Speed(void) const {
81    return pimpl_->output->Value(1,0);
82}
83
84void TrajectoryGenerator1D::SetSpeedOffset(float value) {
85    pimpl_->vel_off=value;
86}
87
88void TrajectoryGenerator1D::Update(Time time) {
89    pimpl_->Update(time);
90    ProcessUpdate(pimpl_->output);
91}
92
93} // end namespace filter
94} // end namespace flair
Note: See TracBrowser for help on using the repository browser.