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