[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"
|
---|
| 20 | #include <cvmatrix.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 |
|
---|
[15] | 28 | namespace flair {
|
---|
| 29 | namespace filter {
|
---|
[7] | 30 |
|
---|
[15] | 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);
|
---|
[7] | 36 | }
|
---|
| 37 |
|
---|
[15] | 38 | TrajectoryGenerator1D::~TrajectoryGenerator1D() { delete pimpl_; }
|
---|
[7] | 39 |
|
---|
[15] | 40 | cvmatrix *TrajectoryGenerator1D::Matrix(void) const { return pimpl_->output; }
|
---|
[7] | 41 |
|
---|
[15] | 42 | void TrajectoryGenerator1D::StartTraj(float start_pos, float end_pos) {
|
---|
| 43 | pimpl_->StartTraj(start_pos, end_pos);
|
---|
[7] | 44 | }
|
---|
| 45 |
|
---|
[15] | 46 | // revoir l'interet du stop?
|
---|
| 47 | void TrajectoryGenerator1D::StopTraj(void) { pimpl_->StopTraj(); }
|
---|
[7] | 48 |
|
---|
| 49 | bool TrajectoryGenerator1D::IsRunning(void) const {
|
---|
[15] | 50 | if (pimpl_->is_started == true) {
|
---|
| 51 | if (pimpl_->is_finished == true) {
|
---|
| 52 | return false;
|
---|
[7] | 53 | } else {
|
---|
[15] | 54 | return true;
|
---|
[7] | 55 | }
|
---|
[15] | 56 | } else {
|
---|
| 57 | return false;
|
---|
| 58 | }
|
---|
[7] | 59 | }
|
---|
| 60 |
|
---|
| 61 | float TrajectoryGenerator1D::Position(void) const {
|
---|
[15] | 62 | return pimpl_->output->Value(0, 0);
|
---|
[7] | 63 | }
|
---|
| 64 |
|
---|
| 65 | void TrajectoryGenerator1D::Reset(void) {
|
---|
[15] | 66 | if (IsRunning() == false) {
|
---|
| 67 | pimpl_->Reset();
|
---|
| 68 | } else {
|
---|
| 69 | Err("impossible while running\n");
|
---|
| 70 | }
|
---|
[7] | 71 | }
|
---|
| 72 |
|
---|
| 73 | void TrajectoryGenerator1D::SetPositionOffset(float value) {
|
---|
[15] | 74 | pimpl_->pos_off = value;
|
---|
[7] | 75 | }
|
---|
| 76 |
|
---|
| 77 | float TrajectoryGenerator1D::Speed(void) const {
|
---|
[15] | 78 | return pimpl_->output->Value(1, 0);
|
---|
[7] | 79 | }
|
---|
| 80 |
|
---|
| 81 | void TrajectoryGenerator1D::SetSpeedOffset(float value) {
|
---|
[15] | 82 | pimpl_->vel_off = value;
|
---|
[7] | 83 | }
|
---|
| 84 |
|
---|
| 85 | void TrajectoryGenerator1D::Update(Time time) {
|
---|
[15] | 86 | pimpl_->Update(time);
|
---|
| 87 | ProcessUpdate(pimpl_->output);
|
---|
[7] | 88 | }
|
---|
| 89 |
|
---|
| 90 | } // end namespace filter
|
---|
| 91 | } // end namespace flair
|
---|