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

Last change on this file was 214, checked in by Sanahuja Guillaume, 4 years ago

matrix

File size: 2.4 KB
RevLine 
[10]1// %flair:license{
[15]2// This file is part of the Flair framework distributed under the
3// CECILL-C License, Version 1.0.
[10]4// %flair:license}
[7]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"
[214]20#include <Matrix.h>
[7]21#include <Layout.h>
22#include <LayoutPosition.h>
23
24using std::string;
25using namespace flair::core;
26using namespace flair::gui;
27
[15]28namespace flair {
29namespace filter {
[7]30
[15]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);
[157]36  SetIsReady(true);
[7]37}
38
[15]39TrajectoryGenerator1D::~TrajectoryGenerator1D() { delete pimpl_; }
[7]40
[214]41Matrix *TrajectoryGenerator1D::GetMatrix(void) const { return pimpl_->output; }
[7]42
[177]43void TrajectoryGenerator1D::StartTraj(float startPosition, float endPosition,float startVelocity) {
44  pimpl_->StartTraj(startPosition,endPosition,startVelocity);
[7]45}
46
[15]47// revoir l'interet du stop?
48void TrajectoryGenerator1D::StopTraj(void) { pimpl_->StopTraj(); }
[7]49
50bool TrajectoryGenerator1D::IsRunning(void) const {
[15]51  if (pimpl_->is_started == true) {
52    if (pimpl_->is_finished == true) {
53      return false;
[7]54    } else {
[15]55      return true;
[7]56    }
[15]57  } else {
58    return false;
59  }
[7]60}
61
62float TrajectoryGenerator1D::Position(void) const {
[15]63  return pimpl_->output->Value(0, 0);
[7]64}
65
66void TrajectoryGenerator1D::Reset(void) {
[15]67  if (IsRunning() == false) {
68    pimpl_->Reset();
69  } else {
70    Err("impossible while running\n");
71  }
[7]72}
73
74void TrajectoryGenerator1D::SetPositionOffset(float value) {
[15]75  pimpl_->pos_off = value;
[7]76}
77
78float TrajectoryGenerator1D::Speed(void) const {
[15]79  return pimpl_->output->Value(1, 0);
[7]80}
81
82void TrajectoryGenerator1D::SetSpeedOffset(float value) {
[15]83  pimpl_->vel_off = value;
[7]84}
85
86void TrajectoryGenerator1D::Update(Time time) {
[15]87  pimpl_->Update(time);
88  ProcessUpdate(pimpl_->output);
[7]89}
90
[205]91float TrajectoryGenerator1D::GetPercentageOfCompletion(void) const {
92  return pimpl_->GetPercentageOfCompletion();
93}
94
[7]95} // end namespace filter
96} // end namespace flair
Note: See TracBrowser for help on using the repository browser.