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 <Matrix.h>
|
---|
21 | #include <Layout.h>
|
---|
22 | #include <LayoutPosition.h>
|
---|
23 |
|
---|
24 | using std::string;
|
---|
25 | using namespace flair::core;
|
---|
26 | using namespace flair::gui;
|
---|
27 |
|
---|
28 | namespace flair {
|
---|
29 | namespace filter {
|
---|
30 |
|
---|
31 | TrajectoryGenerator1D::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 | SetIsReady(true);
|
---|
37 | }
|
---|
38 |
|
---|
39 | TrajectoryGenerator1D::~TrajectoryGenerator1D() { delete pimpl_; }
|
---|
40 |
|
---|
41 | Matrix *TrajectoryGenerator1D::GetMatrix(void) const { return pimpl_->output; }
|
---|
42 |
|
---|
43 | void TrajectoryGenerator1D::StartTraj(float startPosition, float endPosition,float startVelocity) {
|
---|
44 | pimpl_->StartTraj(startPosition,endPosition,startVelocity);
|
---|
45 | }
|
---|
46 |
|
---|
47 | // revoir l'interet du stop?
|
---|
48 | void TrajectoryGenerator1D::StopTraj(void) { pimpl_->StopTraj(); }
|
---|
49 |
|
---|
50 | bool TrajectoryGenerator1D::IsRunning(void) const {
|
---|
51 | if (pimpl_->is_started == true) {
|
---|
52 | if (pimpl_->is_finished == true) {
|
---|
53 | return false;
|
---|
54 | } else {
|
---|
55 | return true;
|
---|
56 | }
|
---|
57 | } else {
|
---|
58 | return false;
|
---|
59 | }
|
---|
60 | }
|
---|
61 |
|
---|
62 | float TrajectoryGenerator1D::Position(void) const {
|
---|
63 | return pimpl_->output->Value(0, 0);
|
---|
64 | }
|
---|
65 |
|
---|
66 | void TrajectoryGenerator1D::Reset(void) {
|
---|
67 | if (IsRunning() == false) {
|
---|
68 | pimpl_->Reset();
|
---|
69 | } else {
|
---|
70 | Err("impossible while running\n");
|
---|
71 | }
|
---|
72 | }
|
---|
73 |
|
---|
74 | void TrajectoryGenerator1D::SetPositionOffset(float value) {
|
---|
75 | pimpl_->pos_off = value;
|
---|
76 | }
|
---|
77 |
|
---|
78 | float TrajectoryGenerator1D::Speed(void) const {
|
---|
79 | return pimpl_->output->Value(1, 0);
|
---|
80 | }
|
---|
81 |
|
---|
82 | void TrajectoryGenerator1D::SetSpeedOffset(float value) {
|
---|
83 | pimpl_->vel_off = value;
|
---|
84 | }
|
---|
85 |
|
---|
86 | void TrajectoryGenerator1D::Update(Time time) {
|
---|
87 | pimpl_->Update(time);
|
---|
88 | ProcessUpdate(pimpl_->output);
|
---|
89 | }
|
---|
90 |
|
---|
91 | float TrajectoryGenerator1D::GetPercentageOfCompletion(void) const {
|
---|
92 | return pimpl_->GetPercentageOfCompletion();
|
---|
93 | }
|
---|
94 |
|
---|
95 | } // end namespace filter
|
---|
96 | } // end namespace flair
|
---|