Changeset 13 in flair-dev for trunk/include/FlairFilter


Ignore:
Timestamp:
Apr 8, 2016, 3:39:24 PM (9 years ago)
Author:
Bayard Gildas
Message:

formatting script + include reformatted

Location:
trunk/include/FlairFilter
Files:
15 edited

Legend:

Unmodified
Added
Removed
  • trunk/include/FlairFilter/Ahrs.h

    r9 r13  
    1818
    1919namespace flair {
    20     namespace core {
    21         class Euler;
    22         class Vector3D;
    23         class ImuData;
    24         class Quaternion;
    25         class AhrsData;
    26     }
    27     namespace gui {
    28         class Tab;
    29         class DataPlot1D;
    30     }
    31     namespace sensor {
    32         class Imu;
    33     }
     20namespace core {
     21class Euler;
     22class Vector3D;
     23class ImuData;
     24class Quaternion;
     25class AhrsData;
     26}
     27namespace gui {
     28class Tab;
     29class DataPlot1D;
     30}
     31namespace sensor {
     32class Imu;
     33}
    3434}
    3535
    3636class Ahrs_impl;
    3737
    38 namespace flair { namespace filter {
    39     /*! \class Ahrs
    40     *
    41     * \brief Abstract class for AHRS
    42     *
    43     * Use this class to define a custom AHRS. This class is child
    44     * of an Imu class, which will provide measurements. \n
    45     *
    46     */
    47     class Ahrs : public core::IODevice {
    48         public:
    49             /*!
    50             * \brief Constructor
    51             *
    52             * Construct an Ahrs.
    53             *
    54             * \param parent parent
    55             * \param name name
    56             */
    57             Ahrs(const sensor::Imu* parent,std::string name);
     38namespace flair {
     39namespace filter {
     40/*! \class Ahrs
     41*
     42* \brief Abstract class for AHRS
     43*
     44* Use this class to define a custom AHRS. This class is child
     45* of an Imu class, which will provide measurements. \n
     46*
     47*/
     48class Ahrs : public core::IODevice {
     49public:
     50  /*!
     51  * \brief Constructor
     52  *
     53  * Construct an Ahrs.
     54  *
     55  * \param parent parent
     56  * \param name name
     57  */
     58  Ahrs(const sensor::Imu *parent, std::string name);
    5859
    59             /*!
    60             * \brief Destructor
    61             *
    62             */
    63             ~Ahrs();
     60  /*!
     61  * \brief Destructor
     62  *
     63  */
     64  ~Ahrs();
    6465
    65             /*!
    66             * \brief Get parent Imu
    67             *
    68             * This function is identical to (Imu*)Parent()
    69             */
    70             const sensor::Imu *GetImu(void) const;
     66  /*!
     67  * \brief Get parent Imu
     68  *
     69  * This function is identical to (Imu*)Parent()
     70  */
     71  const sensor::Imu *GetImu(void) const;
    7172
    72             /*!
    73             * \brief Get ahrs datas
    74             *
    75             * \return AhrsData
    76             */
    77             const core::AhrsData *GetDatas(void) const;
     73  /*!
     74  * \brief Get ahrs datas
     75  *
     76  * \return AhrsData
     77  */
     78  const core::AhrsData *GetDatas(void) const;
    7879
    79             /*!
    80             * \brief Lock the graphical user interface
    81             *
    82             * When locked, parameters cannot be modified.
    83             *
    84             */
    85             void LockUserInterface(void) const;
     80  /*!
     81  * \brief Lock the graphical user interface
     82  *
     83  * When locked, parameters cannot be modified.
     84  *
     85  */
     86  void LockUserInterface(void) const;
    8687
    87             /*!
    88             * \brief Unlock the graphical user interface
    89             *
    90             */
    91             void UnlockUserInterface(void) const;
     88  /*!
     89  * \brief Unlock the graphical user interface
     90  *
     91  */
     92  void UnlockUserInterface(void) const;
    9293
    93             /*!
    94             * \brief Use default plot
    95             *
    96             * Plot the datas defined in imudata,
    97             * and datas defined in Imu::imudata.
    98             *
    99             */
    100             void UseDefaultPlot(void);
     94  /*!
     95  * \brief Use default plot
     96  *
     97  * Plot the datas defined in imudata,
     98  * and datas defined in Imu::imudata.
     99  *
     100  */
     101  void UseDefaultPlot(void);
    101102
    102             /*!
    103             * \brief Add plot
    104             *
    105             * Add plot of an AhrsData to the default plot
    106             *
    107             * \param ahrsData ahrs datas to plot
    108             * \param color color to use
    109             */
    110             void AddPlot(const core::AhrsData *ahrsData,gui::DataPlot::Color_t color);
     103  /*!
     104  * \brief Add plot
     105  *
     106  * Add plot of an AhrsData to the default plot
     107  *
     108  * \param ahrsData ahrs datas to plot
     109  * \param color color to use
     110  */
     111  void AddPlot(const core::AhrsData *ahrsData, gui::DataPlot::Color_t color);
    111112
    112             /*!
    113             * \brief Roll plot
    114             *
    115             * Use this plot to add own curves.
    116             *
    117             * \return plot
    118             *
    119             */
    120             gui::DataPlot1D *RollPlot(void)const ;
     113  /*!
     114  * \brief Roll plot
     115  *
     116  * Use this plot to add own curves.
     117  *
     118  * \return plot
     119  *
     120  */
     121  gui::DataPlot1D *RollPlot(void) const;
    121122
    122             /*!
    123             * \brief Pitch plot
    124             *
    125             * Use this plot to add own curves.
    126             *
    127             * \return plot
    128             *
    129             */
    130             gui::DataPlot1D *PitchPlot(void) const;
     123  /*!
     124  * \brief Pitch plot
     125  *
     126  * Use this plot to add own curves.
     127  *
     128  * \return plot
     129  *
     130  */
     131  gui::DataPlot1D *PitchPlot(void) const;
    131132
    132             /*!
    133             * \brief Yaw plot
    134             *
    135             * Use this plot to add own curves.
    136             *
    137             * \return plot
    138             *
    139             */
    140             gui::DataPlot1D *YawPlot(void) const;
     133  /*!
     134  * \brief Yaw plot
     135  *
     136  * Use this plot to add own curves.
     137  *
     138  * \return plot
     139  *
     140  */
     141  gui::DataPlot1D *YawPlot(void) const;
    141142
    142             /*!
    143             * \brief Rotation speed around x axis plot
    144             *
    145             * Use this plot to add own curves.
    146             *
    147             * \return plot
    148             *
    149             */
    150             gui::DataPlot1D *WXPlot(void) const;
     143  /*!
     144  * \brief Rotation speed around x axis plot
     145  *
     146  * Use this plot to add own curves.
     147  *
     148  * \return plot
     149  *
     150  */
     151  gui::DataPlot1D *WXPlot(void) const;
    151152
    152             /*!
    153             * \brief Rotation speed around y axis plot
    154             *
    155             * Use this plot to add own curves.
    156             *
    157             * \return plot
    158             *
    159             */
    160             gui::DataPlot1D *WYPlot(void) const;
     153  /*!
     154  * \brief Rotation speed around y axis plot
     155  *
     156  * Use this plot to add own curves.
     157  *
     158  * \return plot
     159  *
     160  */
     161  gui::DataPlot1D *WYPlot(void) const;
    161162
    162             /*!
    163             * \brief Rotation speed around z axis plot
    164             *
    165             * Use this plot to add own curves.
    166             *
    167             * \return plot
    168             *
    169             */
    170             gui::DataPlot1D *WZPlot(void) const;
     163  /*!
     164  * \brief Rotation speed around z axis plot
     165  *
     166  * Use this plot to add own curves.
     167  *
     168  * \return plot
     169  *
     170  */
     171  gui::DataPlot1D *WZPlot(void) const;
    171172
    172         protected:
    173             /*!
    174             * \brief Get ahrs datas
    175             *
    176             * \param ahrsData ahrs datas
    177             */
    178             void GetDatas(core::AhrsData **ahrsData) const;
     173protected:
     174  /*!
     175  * \brief Get ahrs datas
     176  *
     177  * \param ahrsData ahrs datas
     178  */
     179  void GetDatas(core::AhrsData **ahrsData) const;
    179180
    180         private:
    181             class Ahrs_impl *pimpl_;
    182     };
     181private:
     182  class Ahrs_impl *pimpl_;
     183};
    183184} // end namespace filter
    184185} // end namespace flair
  • trunk/include/FlairFilter/ButterworthLowPass.h

    r9 r13  
    1616#include <IODevice.h>
    1717
    18 namespace flair
    19 {
    20     namespace core
    21     {
    22         class cvmatrix;
    23     }
    24     namespace gui
    25     {
    26         class LayoutPosition;
    27     }
     18namespace flair {
     19namespace core {
     20class cvmatrix;
     21}
     22namespace gui {
     23class LayoutPosition;
     24}
    2825}
    2926
    3027class ButterworthLowPass_impl;
    3128
    32 namespace flair
    33 {
    34 namespace filter
    35 {
    36     /*! \class ButterworthLowPass
    37     *
    38     * \brief Class defining a Butterworth low pass filter
    39     */
    40     class ButterworthLowPass : public core::IODevice
    41     {
    42         public:
    43             /*!
    44             * \brief Constructor
    45             *
    46             * Construct a ButterworthLowPass at position. \n
    47             * After calling this function, position will be deleted as it is no longer usefull. \n
    48             * The filter is automatically updated when parent's
    49             * IODevice::ProcessUpdate is called.
    50             *
    51             * \param parent parent
    52             * \param position position to display settings
    53             * \param name name
    54             * \param order order of the filter
    55             */
    56             ButterworthLowPass(const IODevice* parent,const gui::LayoutPosition* position,std::string name,int order);
     29namespace flair {
     30namespace filter {
     31/*! \class ButterworthLowPass
     32*
     33* \brief Class defining a Butterworth low pass filter
     34*/
     35class ButterworthLowPass : public core::IODevice {
     36public:
     37  /*!
     38  * \brief Constructor
     39  *
     40  * Construct a ButterworthLowPass at position. \n
     41  * After calling this function, position will be deleted as it is no longer
     42  *usefull. \n
     43  * The filter is automatically updated when parent's
     44  * IODevice::ProcessUpdate is called.
     45  *
     46  * \param parent parent
     47  * \param position position to display settings
     48  * \param name name
     49  * \param order order of the filter
     50  */
     51  ButterworthLowPass(const IODevice *parent,
     52                     const gui::LayoutPosition *position, std::string name,
     53                     int order);
    5754
    58             /*!
    59             * \brief Constructor
    60             *
    61             * Construct a ButterworthLowPass at position. \n
    62             * The ButterworthLowPass will automatically be child of position->getLayout() Layout. After calling this function,
    63             * position will be deleted as it is no longer usefull. \n
    64             * The filter is updated manually with UpdateFrom method. \n
    65             *
    66             * \param position position to display settings
    67             * \param name name
    68             * \param order order of the filter
    69             */
    70             ButterworthLowPass(const gui::LayoutPosition* position,std::string name,int order);
     55  /*!
     56  * \brief Constructor
     57  *
     58  * Construct a ButterworthLowPass at position. \n
     59  * The ButterworthLowPass will automatically be child of position->getLayout()
     60  *Layout. After calling this function,
     61  * position will be deleted as it is no longer usefull. \n
     62  * The filter is updated manually with UpdateFrom method. \n
     63  *
     64  * \param position position to display settings
     65  * \param name name
     66  * \param order order of the filter
     67  */
     68  ButterworthLowPass(const gui::LayoutPosition *position, std::string name,
     69                     int order);
    7170
    72             /*!
    73             * \brief Destructor
    74             *
    75             */
    76             ~ButterworthLowPass();
     71  /*!
     72  * \brief Destructor
     73  *
     74  */
     75  ~ButterworthLowPass();
    7776
    78             /*!
    79             * \brief Output value
    80             *
    81             * \return filtered output
    82             */
    83             float Output(void) const;
     77  /*!
     78  * \brief Output value
     79  *
     80  * \return filtered output
     81  */
     82  float Output(void) const;
    8483
    85             /*!
    86             * \brief Output matrix
    87             *
    88             * \return filtered output
    89             */
    90             core::cvmatrix* Matrix(void)const ;
     84  /*!
     85  * \brief Output matrix
     86  *
     87  * \return filtered output
     88  */
     89  core::cvmatrix *Matrix(void) const;
    9190
    92             /*!
    93             * \brief Update using provided datas
    94             *
    95             * Reimplemented from IODevice.
    96             *
    97             * \param data data from the parent to process
    98             */
    99             void UpdateFrom(const core::io_data *data);
     91  /*!
     92  * \brief Update using provided datas
     93  *
     94  * Reimplemented from IODevice.
     95  *
     96  * \param data data from the parent to process
     97  */
     98  void UpdateFrom(const core::io_data *data);
    10099
    101         private:
    102 
    103             class ButterworthLowPass_impl* pimpl_;
    104     };
     100private:
     101  class ButterworthLowPass_impl *pimpl_;
     102};
    105103} // end namespace filter
    106104} // end namespace flair
  • trunk/include/FlairFilter/ControlLaw.h

    r9 r13  
    1717
    1818namespace flair {
    19     namespace gui {
    20         class LayoutPosition;
    21     }
    22     namespace core {
    23         class cvmatrix;
    24     }
     19namespace gui {
     20class LayoutPosition;
     21}
     22namespace core {
     23class cvmatrix;
     24}
    2525}
    2626
    27 namespace flair { namespace filter {
    28     /*! \class ControlLaw
    29     *
    30     * \brief Base class for control law
    31     * input must be created by reimplemented class.\n
    32     * output is created by this class, it is of size (nb_out,1) and type float.\n
    33     * see constructor for nb_out
    34     */
    35     class ControlLaw : public core::IODevice {
    36         public:
    37             /*!
    38             * \brief Constructor
    39             *
    40             * Construct a ControlLaw
    41             *
    42             * \param parent parent
    43             * \param name name
    44             * \param nb_out number of output
    45             */
    46             ControlLaw(const core::Object* parent,std::string name,uint32_t nb_out=1);
     27namespace flair {
     28namespace filter {
     29/*! \class ControlLaw
     30*
     31* \brief Base class for control law
     32* input must be created by reimplemented class.\n
     33* output is created by this class, it is of size (nb_out,1) and type float.\n
     34* see constructor for nb_out
     35*/
     36class ControlLaw : public core::IODevice {
     37public:
     38  /*!
     39  * \brief Constructor
     40  *
     41  * Construct a ControlLaw
     42  *
     43  * \param parent parent
     44  * \param name name
     45  * \param nb_out number of output
     46  */
     47  ControlLaw(const core::Object *parent, std::string name, uint32_t nb_out = 1);
    4748
    48             /*!
    49             * \brief Destructor
    50             *
    51             */
    52             ~ControlLaw();
     49  /*!
     50  * \brief Destructor
     51  *
     52  */
     53  ~ControlLaw();
    5354
    54             /*!
    55             * \brief Output value
    56             *
    57             * \param index output index, between 0 and nb_out-1
    58             *
    59             * \return output value
    60             */
    61             float Output(uint32_t index=0) const;
     55  /*!
     56  * \brief Output value
     57  *
     58  * \param index output index, between 0 and nb_out-1
     59  *
     60  * \return output value
     61  */
     62  float Output(uint32_t index = 0) const;
    6263
    63             /*!
    64             * \brief Use default plot
    65             *
    66             * Plot the output value at given position. \n
    67             * Only Output(1,1) is plotted. \n
    68             * In case of a mutliple output ControlLaw, this function should be reimplemented. \n
    69             * After calling this function, position will be deleted as it is no longer usefull. \n
    70             *
    71             * \param position position to display plot
    72             */
    73             virtual void UseDefaultPlot(const gui::LayoutPosition* position);
     64  /*!
     65  * \brief Use default plot
     66  *
     67  * Plot the output value at given position. \n
     68  * Only Output(1,1) is plotted. \n
     69  * In case of a mutliple output ControlLaw, this function should be
     70  *reimplemented. \n
     71  * After calling this function, position will be deleted as it is no longer
     72  *usefull. \n
     73  *
     74  * \param position position to display plot
     75  */
     76  virtual void UseDefaultPlot(const gui::LayoutPosition *position);
    7477
    75             /*!
    76             * \brief Update using provided datas
    77             *
    78             * Reimplemented class must fill input matrix before calling this.
    79             *
    80             * \param time time of the update
    81             */
    82             void Update(core::Time time);
     78  /*!
     79  * \brief Update using provided datas
     80  *
     81  * Reimplemented class must fill input matrix before calling this.
     82  *
     83  * \param time time of the update
     84  */
     85  void Update(core::Time time);
    8386
    84             /*!
    85             * \brief Reset the internal state of the control law
    86             *
    87             * Doesn't do anything by default
    88             *
    89             */
    90             virtual void Reset() {};
     87  /*!
     88  * \brief Reset the internal state of the control law
     89  *
     90  * Doesn't do anything by default
     91  *
     92  */
     93  virtual void Reset(){};
    9194
    92         protected:
    93             /*!
    94             * \brief input matrix
    95             *
    96             * This matrix must be created by the reimplemented class.
    97             *
    98             */
    99             core::cvmatrix *input;
     95protected:
     96  /*!
     97  * \brief input matrix
     98  *
     99  * This matrix must be created by the reimplemented class.
     100  *
     101  */
     102  core::cvmatrix *input;
    100103
    101             /*!
    102             * \brief output matrix
    103             *
    104             * This matrix is created by this class. Its size is (nb_out,1) and its type
    105             * is io_data::Float.
    106             *
    107             */
    108             core::cvmatrix *output;
     104  /*!
     105  * \brief output matrix
     106  *
     107  * This matrix is created by this class. Its size is (nb_out,1) and its type
     108  * is io_data::Float.
     109  *
     110  */
     111  core::cvmatrix *output;
    109112
    110         private:
    111             /*!
    112             * \brief Update using provided datas
    113             *
    114             * Reimplemented from IODevice.
    115             *
    116             * \param data data from the parent to process
    117             */
    118             virtual void UpdateFrom(const core::io_data *data)=0;
    119     };
     113private:
     114  /*!
     115  * \brief Update using provided datas
     116  *
     117  * Reimplemented from IODevice.
     118  *
     119  * \param data data from the parent to process
     120  */
     121  virtual void UpdateFrom(const core::io_data *data) = 0;
     122};
    120123} // end namespace filter
    121124} // end namespace flair
  • trunk/include/FlairFilter/EulerDerivative.h

    r9 r13  
    1616#include <IODevice.h>
    1717
    18 namespace flair
    19 {
    20     namespace core
    21     {
    22         class cvmatrix;
    23     }
    24     namespace gui
    25     {
    26         class LayoutPosition;
    27     }
     18namespace flair {
     19namespace core {
     20class cvmatrix;
     21}
     22namespace gui {
     23class LayoutPosition;
     24}
    2825}
    2926
    3027class EulerDerivative_impl;
    3128
    32 namespace flair
    33 {
    34 namespace filter
    35 {
    36     /*! \class EulerDerivative
    37     *
    38     * \brief Class defining an euler derivative
    39     */
     29namespace flair {
     30namespace filter {
     31/*! \class EulerDerivative
     32*
     33* \brief Class defining an euler derivative
     34*/
    4035
    41     class EulerDerivative : public core::IODevice
    42     {
    43         public:
    44             /*!
    45             * \brief Constructor
    46             *
    47             * Construct an EulerDerivative at given position. \n
    48             * After calling this function, position will be deleted as it is no longer usefull. \n
    49             * The filter is automatically updated when parent's
    50             * IODevice::ProcessUpdate is called. \n
    51             * The optional init_value parameters allow to specify
    52             * the size of the input datas and its inital values.
    53             * If unspecified, a 1*1 size is used, and values are
    54             * initialized with 0.
    55             *
    56             * \param parent parent
    57             * \param position position to display settings
    58             * \param name name
    59             * \param init_value initial value
    60             */
    61             EulerDerivative(const core::IODevice* parent,const gui::LayoutPosition* position,std::string name,const core::cvmatrix* init_value=NULL);
     36class EulerDerivative : public core::IODevice {
     37public:
     38  /*!
     39  * \brief Constructor
     40  *
     41  * Construct an EulerDerivative at given position. \n
     42  * After calling this function, position will be deleted as it is no longer
     43  *usefull. \n
     44  * The filter is automatically updated when parent's
     45  * IODevice::ProcessUpdate is called. \n
     46  * The optional init_value parameters allow to specify
     47  * the size of the input datas and its inital values.
     48  * If unspecified, a 1*1 size is used, and values are
     49  * initialized with 0.
     50  *
     51  * \param parent parent
     52  * \param position position to display settings
     53  * \param name name
     54  * \param init_value initial value
     55  */
     56  EulerDerivative(const core::IODevice *parent,
     57                  const gui::LayoutPosition *position, std::string name,
     58                  const core::cvmatrix *init_value = NULL);
    6259
    63             /*!
    64             * \brief Destructor
    65             *
    66             */
    67             ~EulerDerivative();
     60  /*!
     61  * \brief Destructor
     62  *
     63  */
     64  ~EulerDerivative();
    6865
    69             /*!
    70             * \brief Output value
    71             *
    72             * \param row row element
    73             * \param col column element
    74             *
    75             * \return element value
    76             */
    77             float Output(int row, int col) const;
     66  /*!
     67  * \brief Output value
     68  *
     69  * \param row row element
     70  * \param col column element
     71  *
     72  * \return element value
     73  */
     74  float Output(int row, int col) const;
    7875
    79             /*!
    80             * \brief Output matrix
    81             *
    82             * \return filtered output
    83             */
    84             core::cvmatrix *Matrix(void) const;
     76  /*!
     77  * \brief Output matrix
     78  *
     79  * \return filtered output
     80  */
     81  core::cvmatrix *Matrix(void) const;
    8582
    86         private:
    87             /*!
    88             * \brief Update using provided datas
    89             *
    90             * Reimplemented from IODevice.
    91             *
    92             * \param data data from the parent to process
    93             */
    94             void UpdateFrom(const core::io_data *data);
     83private:
     84  /*!
     85  * \brief Update using provided datas
     86  *
     87  * Reimplemented from IODevice.
     88  *
     89  * \param data data from the parent to process
     90  */
     91  void UpdateFrom(const core::io_data *data);
    9592
    96             class EulerDerivative_impl* pimpl_;
    97     };
     93  class EulerDerivative_impl *pimpl_;
     94};
    9895} // end namespace filter
    9996} // end namespace flair
  • trunk/include/FlairFilter/Gx3_25_ahrs.h

    r9 r13  
    1717#include <Gx3_25_imu.h>
    1818
    19 namespace flair
    20 {
    21 namespace filter
    22 {
    23     /*! \class Gx3_25_ahrs
    24     *
    25     * \brief Class for 3dmgx3-25 ahrs
    26     *
    27     * This class constructs a Gx3_25_imu as Imu of this Ahrs.
    28     */
    29     class Gx3_25_ahrs : public Ahrs
    30     {
    31         public:
    32             /*!
    33             * \brief Constructor
    34             *
    35             * Construct an Ahrs for 3dmgx3-25
    36             *
    37             * \param parent parent
    38             * \param name name
    39             * \param serialport Imu SerialPort
    40             * \param command command for the Gx3_25_imu continuous mode
    41             * \param priority priority of the Gx3_25_imu Thread
    42             */
    43             Gx3_25_ahrs(const core::FrameworkManager* parent,std::string name,core::SerialPort *serialport,sensor::Gx3_25_imu::Command_t command,uint8_t priority);
     19namespace flair {
     20namespace filter {
     21/*! \class Gx3_25_ahrs
     22*
     23* \brief Class for 3dmgx3-25 ahrs
     24*
     25* This class constructs a Gx3_25_imu as Imu of this Ahrs.
     26*/
     27class Gx3_25_ahrs : public Ahrs {
     28public:
     29  /*!
     30  * \brief Constructor
     31  *
     32  * Construct an Ahrs for 3dmgx3-25
     33  *
     34  * \param parent parent
     35  * \param name name
     36  * \param serialport Imu SerialPort
     37  * \param command command for the Gx3_25_imu continuous mode
     38  * \param priority priority of the Gx3_25_imu Thread
     39  */
     40  Gx3_25_ahrs(const core::FrameworkManager *parent, std::string name,
     41              core::SerialPort *serialport,
     42              sensor::Gx3_25_imu::Command_t command, uint8_t priority);
    4443
    45             /*!
    46             * \brief Destructor
    47             *
    48             */
    49             ~Gx3_25_ahrs();
     44  /*!
     45  * \brief Destructor
     46  *
     47  */
     48  ~Gx3_25_ahrs();
    5049
    51             /*!
    52             * \brief Start Gx3_25_imu Thread
    53             *
    54             */
    55             void Start(void);
     50  /*!
     51  * \brief Start Gx3_25_imu Thread
     52  *
     53  */
     54  void Start(void);
    5655
    57         private:
    58             /*!
    59             * \brief Update using provided datas
    60             *
    61             * Reimplemented from IODevice.
    62             *
    63             * \param data data from the parent to process
    64             */
    65             void UpdateFrom(const core::io_data *data);
    66     };
     56private:
     57  /*!
     58  * \brief Update using provided datas
     59  *
     60  * Reimplemented from IODevice.
     61  *
     62  * \param data data from the parent to process
     63  */
     64  void UpdateFrom(const core::io_data *data);
     65};
    6766} // end namespace filter
    6867} // end namespace flair
  • trunk/include/FlairFilter/JoyReference.h

    r9 r13  
    1717#include <stdint.h>
    1818
    19 namespace flair
    20 {
    21     namespace core {
    22         class Quaternion;
    23         class AhrsData;
    24     }
    25     namespace gui {
    26         class LayoutPosition;
    27     }
     19namespace flair {
     20namespace core {
     21class Quaternion;
     22class AhrsData;
    2823}
     24namespace gui {
     25class LayoutPosition;
     26}
     27}
    2928
    3029class JoyReference_impl;
    3130
    32 namespace flair { namespace filter {
    33     /*! \class JoyReference
    34     *
    35     * \brief Class creating references from a joystick
    36     */
    37     class JoyReference : public core::IODevice
    38     {
    39         public:
    40             /*!
    41             * \brief Constructor
    42             *
    43             * Construct a JoyReference at given position. \n
    44             * The JoyReference will automatically be child of position->getLayout() Layout. After calling this function,
    45             * position will be deleted as it is no longer usefull. \n
    46             * JoyReference compute reference in quaternion, wz, altitude and altitude speed.
    47             *
    48             * \param position position
    49             * \param name name
    50             */
    51             JoyReference(const gui::LayoutPosition* position,std::string name);
    52 
    53             /*!
    54             * \brief Destructor
    55             *
    56             */
    57             ~JoyReference();
    58 
    59             /*!
    60             * \brief Set roll axis value
    61             *
    62             * \param value value
    63             */
    64             void SetRollAxis(float value);
    65 
    66             /*!
    67             * \brief Set pitch axis value
    68             *
    69             * \param value value
    70             */
    71             void SetPitchAxis(float value);
    72 
    73             /*!
    74             * \brief Set yaw axis value
    75             *
    76             * \param value value
    77             */
    78             void SetYawAxis(float value);
    79 
    80             /*!
    81             * \brief Set thrust axis value
    82             *
    83             * \param value value
    84             */
    85             void SetAltitudeAxis(float value);
    86 
    87             /*!
    88             * \brief Get orientation reference
    89             *
    90             * \return reference
    91             */
    92             core::AhrsData* GetReferenceOrientation(void) const;
    93 
    94             /*!
    95             * \brief Get z reference
    96             *
    97             * \return reference
    98             */
    99             float ZRef(void) const;
    100 
    101             /*!
    102             * \brief Get z derivative reference
    103             *
    104             * \return reference
    105             */
    106             float DzRef(void) const;
    107 
    108             /*!
    109             * \brief Get roll trim
    110             *
    111             * \return trim value
    112             */
    113             float RollTrim(void) const;
    114 
    115             /*!
    116             * \brief Get pitch trim
    117             *
    118             * \return trim value
    119             */
    120             float PitchTrim(void) const;
    121 
    122             /*!
    123             * \brief Set yaw reference
    124             *
    125             * Yaw part of the output quaternion is obtained by integrating the wz desired angular speed.\n
    126             * This method reset the yaw.
    127             *
    128             * \param value value
    129             */
    130             void SetYawRef(float value);
    131 
    132             /*!
    133             * \brief Set yaw reference
    134             *
    135             * Yaw part of the output quaternion is obtained by integrating the wz desired angular speed.\n
    136             * This method reset the yaw.
    137             *
    138             * \param value value, only the yaw part of the quaternion is used
    139             */
    140             void SetYawRef(core::Quaternion const &value);
    141 
    142             /*!
    143             * \brief Set z reference
    144             *
    145             * Altitude of the output is obtained by integrating the vz desired altitude speed.\n
    146             * This method reset z.
    147             *
    148             * \param value value
    149             */
    150             void SetZRef(float value);
    151 
    152             /*!
    153             * \brief Trim up roll
    154             *
    155             * Roll trim value is increased by one
    156             */
    157             void RollTrimUp(void);
    158 
    159             /*!
    160             * \brief Trim down roll
    161             *
    162             * Roll trim value is decreased by one
    163             */
    164             void RollTrimDown(void);
    165 
    166             /*!
    167             * \brief Trim up pitch
    168             *
    169             * Pitch trim value is increased by one
    170             */
    171             void PitchTrimUp(void);
    172 
    173             /*!
    174             * \brief Trim down pitch
    175             *
    176             * Pitch trim value is decreased by one
    177             */
    178             void PitchTrimDown(void);
    179 
    180             /*!
    181             * \brief Update references
    182             *
    183             * Calls UpdateFrom with values entered manually.
    184             *
    185             * \param time time
    186             */
    187             void Update(core::Time time);
    188 
    189         private:
    190             /*!
    191             * \brief Update using provided datas
    192             *
    193             * Reimplemented from IODevice.
    194             *
    195             * \param data data from the parent to process
    196             */
    197             void UpdateFrom(const core::io_data *data);
    198 
    199             class JoyReference_impl* pimpl_;
    200     };
     31namespace flair {
     32namespace filter {
     33/*! \class JoyReference
     34*
     35* \brief Class creating references from a joystick
     36*/
     37class JoyReference : public core::IODevice {
     38public:
     39  /*!
     40  * \brief Constructor
     41  *
     42  * Construct a JoyReference at given position. \n
     43  * The JoyReference will automatically be child of position->getLayout()
     44  *Layout. After calling this function,
     45  * position will be deleted as it is no longer usefull. \n
     46  * JoyReference compute reference in quaternion, wz, altitude and altitude
     47  *speed.
     48  *
     49  * \param position position
     50  * \param name name
     51  */
     52  JoyReference(const gui::LayoutPosition *position, std::string name);
     53
     54  /*!
     55  * \brief Destructor
     56  *
     57  */
     58  ~JoyReference();
     59
     60  /*!
     61  * \brief Set roll axis value
     62  *
     63  * \param value value
     64  */
     65  void SetRollAxis(float value);
     66
     67  /*!
     68  * \brief Set pitch axis value
     69  *
     70  * \param value value
     71  */
     72  void SetPitchAxis(float value);
     73
     74  /*!
     75  * \brief Set yaw axis value
     76  *
     77  * \param value value
     78  */
     79  void SetYawAxis(float value);
     80
     81  /*!
     82  * \brief Set thrust axis value
     83  *
     84  * \param value value
     85  */
     86  void SetAltitudeAxis(float value);
     87
     88  /*!
     89  * \brief Get orientation reference
     90  *
     91  * \return reference
     92  */
     93  core::AhrsData *GetReferenceOrientation(void) const;
     94
     95  /*!
     96  * \brief Get z reference
     97  *
     98  * \return reference
     99  */
     100  float ZRef(void) const;
     101
     102  /*!
     103  * \brief Get z derivative reference
     104  *
     105  * \return reference
     106  */
     107  float DzRef(void) const;
     108
     109  /*!
     110  * \brief Get roll trim
     111  *
     112  * \return trim value
     113  */
     114  float RollTrim(void) const;
     115
     116  /*!
     117  * \brief Get pitch trim
     118  *
     119  * \return trim value
     120  */
     121  float PitchTrim(void) const;
     122
     123  /*!
     124  * \brief Set yaw reference
     125  *
     126  * Yaw part of the output quaternion is obtained by integrating the wz desired
     127  *angular speed.\n
     128  * This method reset the yaw.
     129  *
     130  * \param value value
     131  */
     132  void SetYawRef(float value);
     133
     134  /*!
     135  * \brief Set yaw reference
     136  *
     137  * Yaw part of the output quaternion is obtained by integrating the wz desired
     138  *angular speed.\n
     139  * This method reset the yaw.
     140  *
     141  * \param value value, only the yaw part of the quaternion is used
     142  */
     143  void SetYawRef(core::Quaternion const &value);
     144
     145  /*!
     146  * \brief Set z reference
     147  *
     148  * Altitude of the output is obtained by integrating the vz desired altitude
     149  *speed.\n
     150  * This method reset z.
     151  *
     152  * \param value value
     153  */
     154  void SetZRef(float value);
     155
     156  /*!
     157  * \brief Trim up roll
     158  *
     159  * Roll trim value is increased by one
     160  */
     161  void RollTrimUp(void);
     162
     163  /*!
     164  * \brief Trim down roll
     165  *
     166  * Roll trim value is decreased by one
     167  */
     168  void RollTrimDown(void);
     169
     170  /*!
     171  * \brief Trim up pitch
     172  *
     173  * Pitch trim value is increased by one
     174  */
     175  void PitchTrimUp(void);
     176
     177  /*!
     178  * \brief Trim down pitch
     179  *
     180  * Pitch trim value is decreased by one
     181  */
     182  void PitchTrimDown(void);
     183
     184  /*!
     185  * \brief Update references
     186  *
     187  * Calls UpdateFrom with values entered manually.
     188  *
     189  * \param time time
     190  */
     191  void Update(core::Time time);
     192
     193private:
     194  /*!
     195  * \brief Update using provided datas
     196  *
     197  * Reimplemented from IODevice.
     198  *
     199  * \param data data from the parent to process
     200  */
     201  void UpdateFrom(const core::io_data *data);
     202
     203  class JoyReference_impl *pimpl_;
     204};
    201205} // end namespace sensor
    202206} // end namespace flair
  • trunk/include/FlairFilter/LowPassFilter.h

    r9 r13  
    1616#include <IODevice.h>
    1717
    18 namespace flair
    19 {
    20     namespace core
    21     {
    22         class cvmatrix;
    23     }
    24     namespace gui
    25     {
    26         class Layout;
    27         class LayoutPosition;
    28     }
     18namespace flair {
     19namespace core {
     20class cvmatrix;
     21}
     22namespace gui {
     23class Layout;
     24class LayoutPosition;
     25}
    2926}
    3027
    3128class LowPassFilter_impl;
    3229
    33 namespace flair
    34 {
    35 namespace filter
    36 {
    37     /*! \class LowPassFilter
    38     *
    39     * \brief Class defining a first order low pass filter
    40     */
    41     class LowPassFilter : public core::IODevice
    42     {
    43         public:
    44             /*!
    45             * \brief Constructor
    46             *
    47             * Construct a LowPassFilter at position. \n
    48             * After calling this function, position will be deleted as it is no longer usefull. \n
    49             * The filter is automatically updated when parent's
    50             * IODevice::ProcessUpdate is called. \n
    51             * The optional init_value parameters allow to specify
    52             * the size of the input datas and its inital values.
    53             * If unspecified, a 1*1 size is used, and values are
    54             * initialized with 0.
    55             *
    56             * \param parent parent
    57             * \param position position to display settings
    58             * \param name name
    59             * \param init_value initial value
    60             */
    61             LowPassFilter(const core::IODevice* parent,const gui::LayoutPosition* position,std::string name,const core::cvmatrix* init_value=NULL);
     30namespace flair {
     31namespace filter {
     32/*! \class LowPassFilter
     33*
     34* \brief Class defining a first order low pass filter
     35*/
     36class LowPassFilter : public core::IODevice {
     37public:
     38  /*!
     39  * \brief Constructor
     40  *
     41  * Construct a LowPassFilter at position. \n
     42  * After calling this function, position will be deleted as it is no longer
     43  *usefull. \n
     44  * The filter is automatically updated when parent's
     45  * IODevice::ProcessUpdate is called. \n
     46  * The optional init_value parameters allow to specify
     47  * the size of the input datas and its inital values.
     48  * If unspecified, a 1*1 size is used, and values are
     49  * initialized with 0.
     50  *
     51  * \param parent parent
     52  * \param position position to display settings
     53  * \param name name
     54  * \param init_value initial value
     55  */
     56  LowPassFilter(const core::IODevice *parent,
     57                const gui::LayoutPosition *position, std::string name,
     58                const core::cvmatrix *init_value = NULL);
    6259
    63             /*!
    64             * \brief Destructor
    65             *
    66             */
    67             ~LowPassFilter();
     60  /*!
     61  * \brief Destructor
     62  *
     63  */
     64  ~LowPassFilter();
    6865
    69             /*!
    70             * \brief Output value
    71             *
    72             * \param row row element
    73             * \param col column element
    74             *
    75             * \return element value
    76             */
    77             float Output(int row, int col) const;
     66  /*!
     67  * \brief Output value
     68  *
     69  * \param row row element
     70  * \param col column element
     71  *
     72  * \return element value
     73  */
     74  float Output(int row, int col) const;
    7875
    79             /*!
    80             * \brief Output matrix
    81             *
    82             * \return filtered output
    83             */
    84             core::cvmatrix* Matrix(void) const;
     76  /*!
     77  * \brief Output matrix
     78  *
     79  * \return filtered output
     80  */
     81  core::cvmatrix *Matrix(void) const;
    8582
    86         private:
    87             /*!
    88             * \brief Update using provided datas
    89             *
    90             * Reimplemented from IODevice.
    91             *
    92             * \param data data from the parent to process
    93             */
    94             void UpdateFrom(const core::io_data *data);
     83private:
     84  /*!
     85  * \brief Update using provided datas
     86  *
     87  * Reimplemented from IODevice.
     88  *
     89  * \param data data from the parent to process
     90  */
     91  void UpdateFrom(const core::io_data *data);
    9592
    96             class LowPassFilter_impl* pimpl_;
    97     };
     93  class LowPassFilter_impl *pimpl_;
     94};
    9895} // end namespace filter
    9996} // end namespace flair
  • trunk/include/FlairFilter/NestedSat.h

    r9 r13  
    1616#include <ControlLaw.h>
    1717
    18 namespace flair
    19 {
    20     namespace gui
    21     {
    22         class Layout;
    23         class LayoutPosition;
    24     }
     18namespace flair {
     19namespace gui {
     20class Layout;
     21class LayoutPosition;
     22}
    2523}
    2624
    2725class NestedSat_impl;
    2826
    29 namespace flair
    30 {
    31 namespace filter
    32 {
    33     /*! \class NestedSat
    34     *
    35     * \brief  Class defining a PID with saturations
    36     *
    37     * The output of this control law is calculated
    38     * as follows: \n
    39     * p_ref=Sat(p_ref,k*sat_ref) \n
    40     * d_ref=Sat[(p_ref-p)*kp,k*sat_dref] \n
    41     * law=Sat[(d-d_ref)*kd,sat_u] \n
    42     * where p, p_ref and d are input values (see SetValues()), \n
    43     * where sat_ref, sat_dref and sat_u are settings availables on the ground station, \n
    44     * where k is a conversion factor (see ConvertSatFromDegToRad()).
    45     */
    46     class NestedSat : public ControlLaw
    47     {
    48         friend class ::NestedSat_impl;
     27namespace flair {
     28namespace filter {
     29/*! \class NestedSat
     30*
     31* \brief  Class defining a PID with saturations
     32*
     33* The output of this control law is calculated
     34* as follows: \n
     35* p_ref=Sat(p_ref,k*sat_ref) \n
     36* d_ref=Sat[(p_ref-p)*kp,k*sat_dref] \n
     37* law=Sat[(d-d_ref)*kd,sat_u] \n
     38* where p, p_ref and d are input values (see SetValues()), \n
     39* where sat_ref, sat_dref and sat_u are settings availables on the ground
     40*station, \n
     41* where k is a conversion factor (see ConvertSatFromDegToRad()).
     42*/
     43class NestedSat : public ControlLaw {
     44  friend class ::NestedSat_impl;
    4945
    50         public:
    51             /*!
    52             * \brief Constructor
    53             *
    54             * Construct a NestedSat at given place position. \n
    55             * The NestedSat will automatically be child of position->getLayout() Layout. After calling this function,
    56             * position will be deleted as it is no longer usefull. \n
    57             *
    58             * \param position position to display settings
    59             * \param name name
    60             */
    61             NestedSat(const gui::LayoutPosition* position,std::string name);
     46public:
     47  /*!
     48  * \brief Constructor
     49  *
     50  * Construct a NestedSat at given place position. \n
     51  * The NestedSat will automatically be child of position->getLayout() Layout.
     52  *After calling this function,
     53  * position will be deleted as it is no longer usefull. \n
     54  *
     55  * \param position position to display settings
     56  * \param name name
     57  */
     58  NestedSat(const gui::LayoutPosition *position, std::string name);
    6259
    63             /*!
    64             * \brief Destructor
    65             *
    66             */
    67             ~NestedSat();
     60  /*!
     61  * \brief Destructor
     62  *
     63  */
     64  ~NestedSat();
    6865
    69             /*!
    70             * \brief Set input values
    71             *
    72             * \param p_ref proportional reference
    73             * \param p proportional value
    74             * \param d derivative value
    75             */
    76             void SetValues(float p_ref,float p,float d);
     66  /*!
     67  * \brief Set input values
     68  *
     69  * \param p_ref proportional reference
     70  * \param p proportional value
     71  * \param d derivative value
     72  */
     73  void SetValues(float p_ref, float p, float d);
    7774
    78             /*!
    79             * \brief Convert saturation parameters in radians
    80             *
    81             * If this function is called, saturation parameters
    82             * on the ground station will be interpreted as degrees. \n
    83             * Thus, an internal conversion from degrees to radians will
    84             * be done (k=PI/180).
    85             */
    86             void ConvertSatFromDegToRad(void);
     75  /*!
     76  * \brief Convert saturation parameters in radians
     77  *
     78  * If this function is called, saturation parameters
     79  * on the ground station will be interpreted as degrees. \n
     80  * Thus, an internal conversion from degrees to radians will
     81  * be done (k=PI/180).
     82  */
     83  void ConvertSatFromDegToRad(void);
    8784
    88         private:
    89             /*!
    90             * \brief Update using provided datas
    91             *
    92             * Reimplemented from IODevice.
    93             *
    94             * \param data data from the parent to process
    95             */
    96             void UpdateFrom(const core::io_data *data);
     85private:
     86  /*!
     87  * \brief Update using provided datas
     88  *
     89  * Reimplemented from IODevice.
     90  *
     91  * \param data data from the parent to process
     92  */
     93  void UpdateFrom(const core::io_data *data);
    9794
    98             NestedSat_impl* pimpl_;
    99     };
     95  NestedSat_impl *pimpl_;
     96};
    10097} // end namespace filter
    10198} // end namespace flair
  • trunk/include/FlairFilter/Pid.h

    r9 r13  
    1616#include <ControlLaw.h>
    1717
    18 namespace flair
    19 {
    20     namespace gui
    21     {
    22         class LayoutPosition;
    23     }
     18namespace flair {
     19namespace gui {
     20class LayoutPosition;
     21}
    2422}
    2523
    2624class Pid_impl;
    2725
    28 namespace flair
    29 {
    30 namespace filter
    31 {
    32     /*! \class Pid
    33     *
    34     * \brief Class defining a PID
    35     */
    36     class Pid : public ControlLaw
    37     {
    38         friend class ::Pid_impl;
     26namespace flair {
     27namespace filter {
     28/*! \class Pid
     29*
     30* \brief Class defining a PID
     31*/
     32class Pid : public ControlLaw {
     33  friend class ::Pid_impl;
    3934
    40         public:
    41             /*!
    42             * \brief Constructor
    43             *
    44             * Construct a PID at given position. \n
    45             * The PID will automatically be child of position->getLayout() Layout. After calling this function,
    46             * position will be deleted as it is no longer usefull. \n
    47             *
    48             * \param position position to display settings
    49             * \param name name
    50             */
    51             Pid(const gui::LayoutPosition* position,std::string name);
     35public:
     36  /*!
     37  * \brief Constructor
     38  *
     39  * Construct a PID at given position. \n
     40  * The PID will automatically be child of position->getLayout() Layout. After
     41  *calling this function,
     42  * position will be deleted as it is no longer usefull. \n
     43  *
     44  * \param position position to display settings
     45  * \param name name
     46  */
     47  Pid(const gui::LayoutPosition *position, std::string name);
    5248
    53             /*!
    54             * \brief Destructor
    55             *
    56             */
    57             ~Pid();
     49  /*!
     50  * \brief Destructor
     51  *
     52  */
     53  ~Pid();
    5854
    59             /*!
    60             * \brief Reset integral
    61             *
    62             */
    63             void Reset(void);
     55  /*!
     56  * \brief Reset integral
     57  *
     58  */
     59  void Reset(void);
    6460
    65             /*!
    66             * \brief Set input values
    67             *
    68             * \param p proportional value
    69             * \param d derivative value
    70             */
    71             void SetValues(float p,float d);
     61  /*!
     62  * \brief Set input values
     63  *
     64  * \param p proportional value
     65  * \param d derivative value
     66  */
     67  void SetValues(float p, float d);
    7268
    73             /*!
    74             * \brief Use default plot
    75             *
    76             * Plot the output values at position. \n
    77             * Plot consists of 4 curves: proportional part,
    78             * derivative part, integral part and
    79             * the sum of the three. \n
    80             * After calling this function, position will be deleted as it is no longer usefull. \n
    81             *
    82             * \param position position to display plot
    83             */
    84             void UseDefaultPlot(const gui::LayoutPosition* position);
     69  /*!
     70  * \brief Use default plot
     71  *
     72  * Plot the output values at position. \n
     73  * Plot consists of 4 curves: proportional part,
     74  * derivative part, integral part and
     75  * the sum of the three. \n
     76  * After calling this function, position will be deleted as it is no longer
     77  *usefull. \n
     78  *
     79  * \param position position to display plot
     80  */
     81  void UseDefaultPlot(const gui::LayoutPosition *position);
    8582
    86         private:
    87             /*!
    88             * \brief Update using provided datas
    89             *
    90             * Reimplemented from IODevice.
    91             *
    92             * \param data data from the parent to process
    93             */
    94             void UpdateFrom(const core::io_data *data);
     83private:
     84  /*!
     85  * \brief Update using provided datas
     86  *
     87  * Reimplemented from IODevice.
     88  *
     89  * \param data data from the parent to process
     90  */
     91  void UpdateFrom(const core::io_data *data);
    9592
    96             Pid_impl* pimpl_;
    97     };
     93  Pid_impl *pimpl_;
     94};
    9895} // end namespace filter
    9996} // end namespace flair
  • trunk/include/FlairFilter/PidThrust.h

    r9 r13  
    1616#include <ControlLaw.h>
    1717
    18 namespace flair
    19 {
    20     namespace gui
    21     {
    22         class LayoutPosition;
    23     }
     18namespace flair {
     19namespace gui {
     20class LayoutPosition;
     21}
    2422}
    2523
    2624class PidThrust_impl;
    2725
    28 namespace flair
    29 {
    30 namespace filter
    31 {
    32     /*! \class PidThrust
    33     *
    34     * \brief Class defining a Pid for Thrust.\n
    35     * This Pid as an extra offset for compensating gravity.
    36     */
    37     class PidThrust : public ControlLaw
    38     {
    39         friend class ::PidThrust_impl;
     26namespace flair {
     27namespace filter {
     28/*! \class PidThrust
     29*
     30* \brief Class defining a Pid for Thrust.\n
     31* This Pid as an extra offset for compensating gravity.
     32*/
     33class PidThrust : public ControlLaw {
     34  friend class ::PidThrust_impl;
    4035
    41         public:
    42             /*!
    43             * \brief Constructor
    44             *
    45             * Construct a PidThrust at given position
    46             * The PidThrust will automatically be child of position->getLayout() Layout. After calling this function,
    47             * position will be deleted as it is no longer usefull. \n
    48             *
    49             * \param position position to display settings
    50             * \param name name
    51             */
    52             PidThrust(const gui::LayoutPosition* position,std::string name);
     36public:
     37  /*!
     38  * \brief Constructor
     39  *
     40  * Construct a PidThrust at given position
     41  * The PidThrust will automatically be child of position->getLayout() Layout.
     42  *After calling this function,
     43  * position will be deleted as it is no longer usefull. \n
     44  *
     45  * \param position position to display settings
     46  * \param name name
     47  */
     48  PidThrust(const gui::LayoutPosition *position, std::string name);
    5349
    54             /*!
    55             * \brief Destructor
    56             *
    57             */
    58             ~PidThrust();
     50  /*!
     51  * \brief Destructor
     52  *
     53  */
     54  ~PidThrust();
    5955
    60             /*!
    61             * \brief Reset integral and offset to 0
    62             *
    63             */
    64             void Reset(void);
     56  /*!
     57  * \brief Reset integral and offset to 0
     58  *
     59  */
     60  void Reset(void);
    6561
    66             /*!
    67             * \brief Reset integral to 0
    68             *
    69             */
    70             void ResetI(void);
     62  /*!
     63  * \brief Reset integral to 0
     64  *
     65  */
     66  void ResetI(void);
    7167
    72             /*!
    73             * \brief Reset offset to 0
    74             *
    75             */
    76             void ResetOffset(void);
     68  /*!
     69  * \brief Reset offset to 0
     70  *
     71  */
     72  void ResetOffset(void);
    7773
    78             /*!
    79             * \brief Set offset to specified value in ground station
    80             *
    81             */
    82             void SetOffset(void);
     74  /*!
     75  * \brief Set offset to specified value in ground station
     76  *
     77  */
     78  void SetOffset(void);
    8379
    84             /*!
    85             * \brief Get offset
    86             *
    87             * \return current offset
    88             */
    89             float GetOffset(void);
     80  /*!
     81  * \brief Get offset
     82  *
     83  * \return current offset
     84  */
     85  float GetOffset(void);
    9086
    91             /*!
    92             * \brief Step up the offset according to specified value in ground station
    93             *
    94             * \return false if offset is at its maximum (1) value, true otherwise
    95             */
    96             bool OffsetStepUp(void);
     87  /*!
     88  * \brief Step up the offset according to specified value in ground station
     89  *
     90  * \return false if offset is at its maximum (1) value, true otherwise
     91  */
     92  bool OffsetStepUp(void);
    9793
    98             /*!
    99             * \brief Step down the offset according to specified value in ground station
    100             *
    101             * \return false if offset is at its minimum (specified in ground station) value, true otherwise
    102             */
    103             bool OffsetStepDown(void);
     94  /*!
     95  * \brief Step down the offset according to specified value in ground station
     96  *
     97  * \return false if offset is at its minimum (specified in ground station)
     98  *value, true otherwise
     99  */
     100  bool OffsetStepDown(void);
    104101
    105             /*!
    106             * \brief Set input values
    107             *
    108             * \param p proportional value
    109             * \param d derivative value
    110             */
    111             void SetValues(float p,float d);
     102  /*!
     103  * \brief Set input values
     104  *
     105  * \param p proportional value
     106  * \param d derivative value
     107  */
     108  void SetValues(float p, float d);
    112109
    113             /*!
    114             * \brief Use default plot
    115             *
    116             * Plot the output values at position. \n
    117             * Plot consists of 4 curves: proportional part,
    118             * derivative part, integral part and
    119             * the sum of the three. \n
    120             * After calling this function, position will be deleted as it is no longer usefull. \n
    121             *
    122             * \param position position to display plot
    123             */
    124             void UseDefaultPlot(const gui::LayoutPosition* position);
     110  /*!
     111  * \brief Use default plot
     112  *
     113  * Plot the output values at position. \n
     114  * Plot consists of 4 curves: proportional part,
     115  * derivative part, integral part and
     116  * the sum of the three. \n
     117  * After calling this function, position will be deleted as it is no longer
     118  *usefull. \n
     119  *
     120  * \param position position to display plot
     121  */
     122  void UseDefaultPlot(const gui::LayoutPosition *position);
    125123
    126         private:
    127             /*!
    128             * \brief Update using provided datas
    129             *
    130             * Reimplemented from IODevice.
    131             *
    132             * \param data data from the parent to process
    133             */
    134             void UpdateFrom(const core::io_data *data);
     124private:
     125  /*!
     126  * \brief Update using provided datas
     127  *
     128  * Reimplemented from IODevice.
     129  *
     130  * \param data data from the parent to process
     131  */
     132  void UpdateFrom(const core::io_data *data);
    135133
    136             PidThrust_impl* pimpl_;
    137     };
     134  PidThrust_impl *pimpl_;
     135};
    138136} // end namespace filter
    139137} // end namespace flair
  • trunk/include/FlairFilter/SimuAhrs.h

    r9 r13  
    1717#include <stdint.h>
    1818
    19 namespace flair
    20 {
    21 namespace filter
    22 {
    23     /*! \class SimuAhrs
    24     *
    25     * \brief Class for a simulation Ahrs
    26     *
    27     * This class constructs a SimuImu as Imu of this Ahrs.
    28     */
    29     class SimuAhrs : public filter::Ahrs
    30     {
    31         public:
    32             /*!
    33             * \brief Constructor
    34             *
    35             * Construct a simulation Ahrs.
    36             *
    37             * \param parent parent
    38             * \param name name
    39             * \param dev_id number id of the simulated Ahrs
    40             * \param priority priority of the SimuImu Thread
    41             */
    42             SimuAhrs(const core::FrameworkManager* parent,std::string name,uint32_t dev_id,uint8_t priority);
     19namespace flair {
     20namespace filter {
     21/*! \class SimuAhrs
     22*
     23* \brief Class for a simulation Ahrs
     24*
     25* This class constructs a SimuImu as Imu of this Ahrs.
     26*/
     27class SimuAhrs : public filter::Ahrs {
     28public:
     29  /*!
     30  * \brief Constructor
     31  *
     32  * Construct a simulation Ahrs.
     33  *
     34  * \param parent parent
     35  * \param name name
     36  * \param dev_id number id of the simulated Ahrs
     37  * \param priority priority of the SimuImu Thread
     38  */
     39  SimuAhrs(const core::FrameworkManager *parent, std::string name,
     40           uint32_t dev_id, uint8_t priority);
    4341
    44             /*!
    45             * \brief Destructor
    46             *
    47             */
    48             ~SimuAhrs();
     42  /*!
     43  * \brief Destructor
     44  *
     45  */
     46  ~SimuAhrs();
    4947
    50              /*!
    51             * \brief Start SimuImu Thread
    52             *
    53             */
    54             void Start(void);
     48  /*!
     49 * \brief Start SimuImu Thread
     50 *
     51 */
     52  void Start(void);
    5553
    56         private:
    57             /*!
    58             * \brief Update using provided datas
    59             *
    60             * Reimplemented from IODevice.
    61             *
    62             * \param data data from the parent to process
    63             */
    64             void UpdateFrom(const core::io_data *data);
    65     };
     54private:
     55  /*!
     56  * \brief Update using provided datas
     57  *
     58  * Reimplemented from IODevice.
     59  *
     60  * \param data data from the parent to process
     61  */
     62  void UpdateFrom(const core::io_data *data);
     63};
    6664} // end namespace filter
    6765} // end namespace flair
  • trunk/include/FlairFilter/TrajectoryGenerator1D.h

    r9 r13  
    1616#include <IODevice.h>
    1717
    18 namespace flair
    19 {
    20     namespace core
    21     {
    22         class cvmatrix;
    23     }
    24     namespace gui
    25     {
    26         class LayoutPosition;
    27     }
     18namespace flair {
     19namespace core {
     20class cvmatrix;
     21}
     22namespace gui {
     23class LayoutPosition;
     24}
    2825}
    2926
    3027class TrajectoryGenerator1D_impl;
    3128
    32 namespace flair
    33 {
    34 namespace filter
    35 {
    36     /*! \class TrajectoryGenerator1D
    37     *
    38     * \brief Class generating a trajectory in 1D
    39     *
    40     * This class generates position and velocity references, given
    41     * an absolute maximum velocity and an absolute acceleration. \n
    42     * When trajectory is started (see StartTraj()), position and velocity will increase
    43     * at the given acceleration. If the maximum velocity is reached,
    44     * velocity will not increase anymore. Then, velocity will decrease according
    45     * to the given acceleration until velocity is null and final position is reached. \n
    46     * Manual inputs can be introduced using SetPositionOffset() and SetSpeedOffset().
    47     *
    48     */
    49     class TrajectoryGenerator1D : public core::IODevice
    50     {
    51         public:
    52             /*!
    53             * \brief Constructor
    54             *
    55             * Construct a TrajectoryGenerator1D at given position. \n
    56             * The TrajectoryGenerator1D will automatically be child of position->getLayout() Layout. After calling this function,
    57             * position will be deleted as it is no longer usefull. \n
    58             *
    59             * \param position position to display settings
    60             * \param name name
    61             * \param unit unit of the position (for exemple m, deg, etc). Its only used for display on ground station.
    62             */
    63             TrajectoryGenerator1D(const gui::LayoutPosition* position,std::string name,std::string unit="");
     29namespace flair {
     30namespace filter {
     31/*! \class TrajectoryGenerator1D
     32*
     33* \brief Class generating a trajectory in 1D
     34*
     35* This class generates position and velocity references, given
     36* an absolute maximum velocity and an absolute acceleration. \n
     37* When trajectory is started (see StartTraj()), position and velocity will
     38*increase
     39* at the given acceleration. If the maximum velocity is reached,
     40* velocity will not increase anymore. Then, velocity will decrease according
     41* to the given acceleration until velocity is null and final position is
     42*reached. \n
     43* Manual inputs can be introduced using SetPositionOffset() and
     44*SetSpeedOffset().
     45*
     46*/
     47class TrajectoryGenerator1D : public core::IODevice {
     48public:
     49  /*!
     50  * \brief Constructor
     51  *
     52  * Construct a TrajectoryGenerator1D at given position. \n
     53  * The TrajectoryGenerator1D will automatically be child of
     54  *position->getLayout() Layout. After calling this function,
     55  * position will be deleted as it is no longer usefull. \n
     56  *
     57  * \param position position to display settings
     58  * \param name name
     59  * \param unit unit of the position (for exemple m, deg, etc). Its only used
     60  *for display on ground station.
     61  */
     62  TrajectoryGenerator1D(const gui::LayoutPosition *position, std::string name,
     63                        std::string unit = "");
    6464
    65             /*!
    66             * \brief Destructor
    67             *
    68             */
    69             ~TrajectoryGenerator1D();
     65  /*!
     66  * \brief Destructor
     67  *
     68  */
     69  ~TrajectoryGenerator1D();
    7070
    71             /*!
    72             * \brief Start trajectory
    73             *
    74             * \param start_pos start position
    75             * \param end_pos end position
    76             */
    77             void StartTraj(float start_pos,float end_pos);
     71  /*!
     72  * \brief Start trajectory
     73  *
     74  * \param start_pos start position
     75  * \param end_pos end position
     76  */
     77  void StartTraj(float start_pos, float end_pos);
    7878
    79             /*!
    80             * \brief Stop trajectory
    81             *
    82             */
    83             void StopTraj(void);
     79  /*!
     80  * \brief Stop trajectory
     81  *
     82  */
     83  void StopTraj(void);
    8484
    85             /*!
    86             * \brief Reset
    87             *
    88             * Reset all outputs to 0. This can be done only when IsRunning()==false.
    89             *
    90             */
    91             void Reset(void);
     85  /*!
     86  * \brief Reset
     87  *
     88  * Reset all outputs to 0. This can be done only when IsRunning()==false.
     89  *
     90  */
     91  void Reset(void);
    9292
    93             /*!
    94             * \brief Is trajectory running?
    95             *
    96             * \return true if trajectory is running
    97             */
    98             bool IsRunning(void) const;
     93  /*!
     94  * \brief Is trajectory running?
     95  *
     96  * \return true if trajectory is running
     97  */
     98  bool IsRunning(void) const;
    9999
    100             /*!
    101             * \brief Set position offset
    102             *
    103             * \param value position offset
    104             */
    105             void SetPositionOffset(float value);
     100  /*!
     101  * \brief Set position offset
     102  *
     103  * \param value position offset
     104  */
     105  void SetPositionOffset(float value);
    106106
    107             /*!
    108             * \brief Set speed offset
    109             *
    110             * \param value speed offset
    111             */
    112             void SetSpeedOffset(float value);
     107  /*!
     108  * \brief Set speed offset
     109  *
     110  * \param value speed offset
     111  */
     112  void SetSpeedOffset(float value);
    113113
    114             /*!
    115             * \brief Update using provided datas
    116             *
    117             * Uses values specified by StartTraj(),
    118             * SetPositionOffset() and SetSpeedOffset().
    119             *
    120             * \param time time of the update
    121             */
    122             void Update(core::Time time);
     114  /*!
     115  * \brief Update using provided datas
     116  *
     117  * Uses values specified by StartTraj(),
     118  * SetPositionOffset() and SetSpeedOffset().
     119  *
     120  * \param time time of the update
     121  */
     122  void Update(core::Time time);
    123123
    124             /*!
    125             * \brief Position
    126             *
    127             */
    128             float Position(void) const;
     124  /*!
     125  * \brief Position
     126  *
     127  */
     128  float Position(void) const;
    129129
    130             /*!
    131             * \brief Speed
    132             *
    133             */
    134             float Speed(void) const;
     130  /*!
     131  * \brief Speed
     132  *
     133  */
     134  float Speed(void) const;
    135135
    136             /*!
    137             * \brief Output matrix
    138             *
    139             * \return matrix
    140             */
    141             core::cvmatrix *Matrix(void) const;
     136  /*!
     137  * \brief Output matrix
     138  *
     139  * \return matrix
     140  */
     141  core::cvmatrix *Matrix(void) const;
    142142
    143         private:
    144             /*!
    145             * \brief Update using provided datas
    146             *
    147             * Reimplemented from IODevice. Nothing to do in this IODevice.
    148             *
    149             * \param data data from the parent to process
    150             */
    151             void UpdateFrom(const core::io_data *data){};
     143private:
     144  /*!
     145  * \brief Update using provided datas
     146  *
     147  * Reimplemented from IODevice. Nothing to do in this IODevice.
     148  *
     149  * \param data data from the parent to process
     150  */
     151  void UpdateFrom(const core::io_data *data){};
    152152
    153             TrajectoryGenerator1D_impl* pimpl_;
    154     };
     153  TrajectoryGenerator1D_impl *pimpl_;
     154};
    155155} // end namespace filter
    156156} // end namespace flair
  • trunk/include/FlairFilter/TrajectoryGenerator2DCircle.h

    r9 r13  
    1616#include <IODevice.h>
    1717
    18 namespace flair
    19 {
    20     namespace core
    21     {
    22         class cvmatrix;
    23         class Vector2D;
    24     }
    25     namespace gui
    26     {
    27         class LayoutPosition;
    28     }
     18namespace flair {
     19namespace core {
     20class cvmatrix;
     21class Vector2D;
     22}
     23namespace gui {
     24class LayoutPosition;
     25}
    2926}
    3027
    3128class TrajectoryGenerator2DCircle_impl;
    3229
    33 namespace flair
    34 {
    35 namespace filter
    36 {
    37     /*! \class TrajectoryGenerator2DCircle
    38     *
    39     * \brief Class generating a circle trajectory in 2D
    40     *
    41     * This class generates position and velocity references, given
    42     * a maximum velocity and an absolute acceleration, for a circle. \n
    43     * When trajectory is started (StartTraj), position and velocity will increase
    44     * at the given acceleration untill maximum velocity is reached. \n
    45     * When trajectory is asked to be finished (see FinishTraj()), position
    46     * and velocity will decrease at the given acceleration untill null velocity is reached. \n
    47     * Position and velocity of the center of the circle can be manually changed
    48     * through SetCenter() and SetCenterSpeed().
    49     */
    50     class TrajectoryGenerator2DCircle : public core::IODevice
    51     {
    52         public:
    53             /*!
    54             * \brief Constructor
    55             *
    56             * Construct a TrajectoryGenerator2DCircle at position. \n
    57             * The TrajectoryGenerator2DCircle will automatically be child of position->getLayout() Layout. After calling this function,
    58             * position will be deleted as it is no longer usefull. \n
    59             *
    60             * \param position position to display settings
    61             * \param name name
    62             */
    63             TrajectoryGenerator2DCircle(const gui::LayoutPosition* position,std::string name);
     30namespace flair {
     31namespace filter {
     32/*! \class TrajectoryGenerator2DCircle
     33*
     34* \brief Class generating a circle trajectory in 2D
     35*
     36* This class generates position and velocity references, given
     37* a maximum velocity and an absolute acceleration, for a circle. \n
     38* When trajectory is started (StartTraj), position and velocity will increase
     39* at the given acceleration untill maximum velocity is reached. \n
     40* When trajectory is asked to be finished (see FinishTraj()), position
     41* and velocity will decrease at the given acceleration untill null velocity is
     42*reached. \n
     43* Position and velocity of the center of the circle can be manually changed
     44* through SetCenter() and SetCenterSpeed().
     45*/
     46class TrajectoryGenerator2DCircle : public core::IODevice {
     47public:
     48  /*!
     49  * \brief Constructor
     50  *
     51  * Construct a TrajectoryGenerator2DCircle at position. \n
     52  * The TrajectoryGenerator2DCircle will automatically be child of
     53  *position->getLayout() Layout. After calling this function,
     54  * position will be deleted as it is no longer usefull. \n
     55  *
     56  * \param position position to display settings
     57  * \param name name
     58  */
     59  TrajectoryGenerator2DCircle(const gui::LayoutPosition *position,
     60                              std::string name);
    6461
    65             /*!
    66             * \brief Destructor
    67             *
    68             */
    69             ~TrajectoryGenerator2DCircle();
     62  /*!
     63  * \brief Destructor
     64  *
     65  */
     66  ~TrajectoryGenerator2DCircle();
    7067
    71             /*!
    72             * \brief Start trajectory
    73             *
    74             * \param start_pos start position
    75             * \param nb_lap number of laps, -1 for infinite
    76             */
    77             void StartTraj(const core::Vector2D &start_pos,float nb_lap=-1);
     68  /*!
     69  * \brief Start trajectory
     70  *
     71  * \param start_pos start position
     72  * \param nb_lap number of laps, -1 for infinite
     73  */
     74  void StartTraj(const core::Vector2D &start_pos, float nb_lap = -1);
    7875
    79             /*!
    80             * \brief Stop trajectory
    81             *
    82             * Stop abruptly the trajectory.
    83             */
    84             void StopTraj(void);
     76  /*!
     77  * \brief Stop trajectory
     78  *
     79  * Stop abruptly the trajectory.
     80  */
     81  void StopTraj(void);
    8582
    86             /*!
    87             * \brief Finish trajectory
    88             *
    89             * Finish smoothly the trajectory.
    90             */
    91             void FinishTraj(void);
     83  /*!
     84  * \brief Finish trajectory
     85  *
     86  * Finish smoothly the trajectory.
     87  */
     88  void FinishTraj(void);
    9289
    93             /*!
    94             * \brief Set center position
    95             *
    96             * \param value center position
    97             */
    98             void SetCenter(const core::Vector2D &value);
     90  /*!
     91  * \brief Set center position
     92  *
     93  * \param value center position
     94  */
     95  void SetCenter(const core::Vector2D &value);
    9996
    100             /*!
    101             * \brief Set center speed
    102             *
    103             * \param value center speed
    104             */
    105             void SetCenterSpeed(const core::Vector2D &value);
     97  /*!
     98  * \brief Set center speed
     99  *
     100  * \param value center speed
     101  */
     102  void SetCenterSpeed(const core::Vector2D &value);
    106103
    107             /*!
    108             * \brief Update using provided datas
    109             *
    110             * Uses values specified by StartTraj(),
    111             * SetCenter() and SetCenterSpeed().
    112             *
    113             * \param time time of the update
    114             */
    115             void Update(core::Time time);
     104  /*!
     105  * \brief Update using provided datas
     106  *
     107  * Uses values specified by StartTraj(),
     108  * SetCenter() and SetCenterSpeed().
     109  *
     110  * \param time time of the update
     111  */
     112  void Update(core::Time time);
    116113
    117             /*!
    118             * \brief Position
    119             *
    120             * \param point returned position
    121             */
    122             void GetPosition(core::Vector2D &point) const;
     114  /*!
     115  * \brief Position
     116  *
     117  * \param point returned position
     118  */
     119  void GetPosition(core::Vector2D &point) const;
    123120
    124             /*!
    125             * \brief Speed
    126             *
    127             * \param point returned speed
    128             */
    129             void GetSpeed(core::Vector2D &point) const;
     121  /*!
     122  * \brief Speed
     123  *
     124  * \param point returned speed
     125  */
     126  void GetSpeed(core::Vector2D &point) const;
    130127
    131             /*!
    132             * \brief Output matrix
    133             *
    134             * \return matrix
    135             */
    136             core::cvmatrix *Matrix(void) const;
     128  /*!
     129  * \brief Output matrix
     130  *
     131  * \return matrix
     132  */
     133  core::cvmatrix *Matrix(void) const;
    137134
    138             /*!
    139             * \brief Is trajectory running?
    140             *
    141             * \return true if trajectory is running
    142             */
    143             bool IsRunning(void) const;
     135  /*!
     136  * \brief Is trajectory running?
     137  *
     138  * \return true if trajectory is running
     139  */
     140  bool IsRunning(void) const;
    144141
    145         private:
    146             /*!
    147             * \brief Update using provided datas
    148             *
    149             * Reimplemented from IODevice. Nothing to do in this IODevice.
    150             *
    151             * \param data data from the parent to process
    152             */
    153             void UpdateFrom(const core::io_data *data){};
     142private:
     143  /*!
     144  * \brief Update using provided datas
     145  *
     146  * Reimplemented from IODevice. Nothing to do in this IODevice.
     147  *
     148  * \param data data from the parent to process
     149  */
     150  void UpdateFrom(const core::io_data *data){};
    154151
    155             TrajectoryGenerator2DCircle_impl* pimpl_;
    156 
    157     };
     152  TrajectoryGenerator2DCircle_impl *pimpl_;
     153};
    158154} // end namespace filter
    159155} // end namespace flair
  • trunk/include/FlairFilter/UavMultiplex.h

    r9 r13  
    1717#include <stdint.h>
    1818
    19 namespace flair
    20 {
    21     namespace core
    22     {
    23         class FrameworkManager;
    24         class io_data;
    25     }
    26     namespace gui
    27     {
    28         class TabWidget;
    29         class Layout;
    30     }
     19namespace flair {
     20namespace core {
     21class FrameworkManager;
     22class io_data;
    3123}
     24namespace gui {
     25class TabWidget;
     26class Layout;
     27}
     28}
    3229
    3330class UavMultiplex_impl;
    3431
    35 namespace flair
    36 {
    37 namespace filter
    38 {
    39     /*! \class UavMultiplex
    40     *
    41     * \brief Class defining uav multiplexing
    42     */
    43     class UavMultiplex : public core::IODevice
    44     {
    45         public:
    46             /*!
    47             * \brief Constructor
    48             *
    49             * Construct a uav multiplexing
    50             *
    51             * \param parent parent
    52             * \param name name
    53             */
    54             UavMultiplex(const core::FrameworkManager* parent,std::string name);
    55 
    56             /*!
    57             * \brief Destructor
    58             *
    59             */
    60             ~UavMultiplex();
    61 
    62             /*!
    63             * \brief Set roll torque
    64             *
    65             * roll torque is placed in input(0,0)
    66             *
    67             * \param value value between -1 and 1
    68             */
    69             void SetRoll(float value);
    70 
    71             /*!
    72             * \brief Set pitch torque
    73             *
    74             * pitch torque is placed in input(1,0)
    75             *
    76             * \param value value between -1 and 1
    77             */
    78             void SetPitch(float value);
    79 
    80             /*!
    81             * \brief Set yaw torque
    82             *
    83             * yaw torque is placed in input(2,0)
    84             *
    85             * \param value value between -1 and 1
    86             */
    87             void SetYaw(float value);
    88 
    89             /*!
    90             * \brief Set thrust
    91             *
    92             * thrust is placed in input(3,0)
    93             *
    94             * \param value value between 0 and 1
    95             */
    96             void SetThrust(float value);
    97 
    98             /*!
    99             * \brief Set roll trim
    100             *
    101             * trim is placed in input(4,0)
    102             *
    103             * \param value value
    104             */
    105             void SetRollTrim(float value);
    106 
    107             /*!
    108             * \brief Set pitch trim
    109             *
    110             * trim is placed in input(5,0)
    111             *
    112             * \param value value
    113             */
    114             void SetPitchTrim(float value);
    115 
    116             /*!
    117             * \brief Set yaw trim
    118             *
    119             * trim is placed in input(6,0)
    120             *
    121             * \param value value
    122             */
    123             void SetYawTrim(float value);
    124 
    125             /*!
    126             * \brief Update using provided datas
    127             *
    128             * Uses values specified by Set*().
    129             *
    130             * \param time time of the update
    131             */
    132             void Update(core::Time time);
    133 
    134             /*!
    135             * \brief Lock user interface
    136             *
    137             * User interface will be grayed out.\n
    138             * Use it do disallow changes when flying.
    139             *
    140             */
    141             void LockUserInterface(void) const;
    142 
    143             /*!
    144             * \brief Unlock user interface
    145             *
    146             * User interface will be enabled.\n
    147             *
    148             */
    149             void UnlockUserInterface(void) const;
    150 
    151             /*!
    152             * \brief Layout
    153             *
    154             * Layout to place custom widgets.\n
    155             *
    156             * \return the layout
    157             */
    158             gui::Layout* GetLayout(void) const;
    159 
    160             /*!
    161             * \brief Use default plot
    162             *
    163             * Derived class can implement this function do draw default plot.
    164             *
    165             */
    166             virtual void UseDefaultPlot(void){};
    167 
    168             /*!
    169             * \brief Motors count
    170             *
    171             * This function must be reimplemented, in order to get the number of motors.
    172             *
    173             * \return motors count
    174             */
    175             virtual uint8_t MotorsCount(void) const=0;
    176 
    177             /*!
    178             * \brief Multiplex value
    179             *
    180             * Get the mutliplexed value of a motor, if SetMultiplexComboBox() was used.\n
    181             *
    182             * \param index index of the motor, from 0 to MotorsCount()
    183             * \return multiplexed index of the motor
    184             */
    185             int MultiplexValue(int index) const;
    186 
    187             /*!
    188             * \brief Get TabWidget
    189             *
    190             * Usefull to add tabs.\n
    191             *
    192             * \return the TabWidget
    193             */
    194             gui::TabWidget* GetTabWidget(void) const;
    195 
    196         protected:
    197             /*!
    198             * \brief Set multiplex ComboBox
    199             *
    200             * Draws a ComboBox to define motor multiplexing. \n
    201             * This is used to change the order of the output motors.
    202             *
    203             * \param name description of the motor (ex front left)
    204             * \param index index of the motor, from 0 to MotorsCount()
    205             */
    206             void SetMultiplexComboBox(std::string name,int index);
    207 
    208         private:
    209             /*!
    210             * \brief Update using provided datas
    211             *
    212             * This function is automatically called by ProcessUpdate()
    213             * of the Object::Parent's if its Object::ObjectType is "IODevice". \n
    214             * This function must be reimplemented, in order to process the data from the parent.
    215             *
    216             * \param data data from the parent to process
    217             */
    218             virtual void UpdateFrom(const core::io_data *data)=0;
    219 
    220             UavMultiplex_impl *pimpl_;
    221     };
     32namespace flair {
     33namespace filter {
     34/*! \class UavMultiplex
     35*
     36* \brief Class defining uav multiplexing
     37*/
     38class UavMultiplex : public core::IODevice {
     39public:
     40  /*!
     41  * \brief Constructor
     42  *
     43  * Construct a uav multiplexing
     44  *
     45  * \param parent parent
     46  * \param name name
     47  */
     48  UavMultiplex(const core::FrameworkManager *parent, std::string name);
     49
     50  /*!
     51  * \brief Destructor
     52  *
     53  */
     54  ~UavMultiplex();
     55
     56  /*!
     57  * \brief Set roll torque
     58  *
     59  * roll torque is placed in input(0,0)
     60  *
     61  * \param value value between -1 and 1
     62  */
     63  void SetRoll(float value);
     64
     65  /*!
     66  * \brief Set pitch torque
     67  *
     68  * pitch torque is placed in input(1,0)
     69  *
     70  * \param value value between -1 and 1
     71  */
     72  void SetPitch(float value);
     73
     74  /*!
     75  * \brief Set yaw torque
     76  *
     77  * yaw torque is placed in input(2,0)
     78  *
     79  * \param value value between -1 and 1
     80  */
     81  void SetYaw(float value);
     82
     83  /*!
     84  * \brief Set thrust
     85  *
     86  * thrust is placed in input(3,0)
     87  *
     88  * \param value value between 0 and 1
     89  */
     90  void SetThrust(float value);
     91
     92  /*!
     93  * \brief Set roll trim
     94  *
     95  * trim is placed in input(4,0)
     96  *
     97  * \param value value
     98  */
     99  void SetRollTrim(float value);
     100
     101  /*!
     102  * \brief Set pitch trim
     103  *
     104  * trim is placed in input(5,0)
     105  *
     106  * \param value value
     107  */
     108  void SetPitchTrim(float value);
     109
     110  /*!
     111  * \brief Set yaw trim
     112  *
     113  * trim is placed in input(6,0)
     114  *
     115  * \param value value
     116  */
     117  void SetYawTrim(float value);
     118
     119  /*!
     120  * \brief Update using provided datas
     121  *
     122  * Uses values specified by Set*().
     123  *
     124  * \param time time of the update
     125  */
     126  void Update(core::Time time);
     127
     128  /*!
     129  * \brief Lock user interface
     130  *
     131  * User interface will be grayed out.\n
     132  * Use it do disallow changes when flying.
     133  *
     134  */
     135  void LockUserInterface(void) const;
     136
     137  /*!
     138  * \brief Unlock user interface
     139  *
     140  * User interface will be enabled.\n
     141  *
     142  */
     143  void UnlockUserInterface(void) const;
     144
     145  /*!
     146  * \brief Layout
     147  *
     148  * Layout to place custom widgets.\n
     149  *
     150  * \return the layout
     151  */
     152  gui::Layout *GetLayout(void) const;
     153
     154  /*!
     155  * \brief Use default plot
     156  *
     157  * Derived class can implement this function do draw default plot.
     158  *
     159  */
     160  virtual void UseDefaultPlot(void){};
     161
     162  /*!
     163  * \brief Motors count
     164  *
     165  * This function must be reimplemented, in order to get the number of motors.
     166  *
     167  * \return motors count
     168  */
     169  virtual uint8_t MotorsCount(void) const = 0;
     170
     171  /*!
     172  * \brief Multiplex value
     173  *
     174  * Get the mutliplexed value of a motor, if SetMultiplexComboBox() was used.\n
     175  *
     176  * \param index index of the motor, from 0 to MotorsCount()
     177  * \return multiplexed index of the motor
     178  */
     179  int MultiplexValue(int index) const;
     180
     181  /*!
     182  * \brief Get TabWidget
     183  *
     184  * Usefull to add tabs.\n
     185  *
     186  * \return the TabWidget
     187  */
     188  gui::TabWidget *GetTabWidget(void) const;
     189
     190protected:
     191  /*!
     192  * \brief Set multiplex ComboBox
     193  *
     194  * Draws a ComboBox to define motor multiplexing. \n
     195  * This is used to change the order of the output motors.
     196  *
     197  * \param name description of the motor (ex front left)
     198  * \param index index of the motor, from 0 to MotorsCount()
     199  */
     200  void SetMultiplexComboBox(std::string name, int index);
     201
     202private:
     203  /*!
     204  * \brief Update using provided datas
     205  *
     206  * This function is automatically called by ProcessUpdate()
     207  * of the Object::Parent's if its Object::ObjectType is "IODevice". \n
     208  * This function must be reimplemented, in order to process the data from the
     209  *parent.
     210  *
     211  * \param data data from the parent to process
     212  */
     213  virtual void UpdateFrom(const core::io_data *data) = 0;
     214
     215  UavMultiplex_impl *pimpl_;
     216};
    222217} // end namespace filter
    223218} // end namespace flair
  • trunk/include/FlairFilter/X4X8Multiplex.h

    r9 r13  
    1818class X4X8Multiplex_impl;
    1919
    20 namespace flair
    21 {
    22 namespace filter
    23 {
    24     /*! \class X4X8Multiplex
    25     *
    26     * \brief Class defining X4 and X8 multiplexing
    27     *
    28     * The output order of the motors can be changed through ground station.
    29     */
    30     class X4X8Multiplex : public UavMultiplex
    31     {
    32         friend class ::X4X8Multiplex_impl;
     20namespace flair {
     21namespace filter {
     22/*! \class X4X8Multiplex
     23*
     24* \brief Class defining X4 and X8 multiplexing
     25*
     26* The output order of the motors can be changed through ground station.
     27*/
     28class X4X8Multiplex : public UavMultiplex {
     29  friend class ::X4X8Multiplex_impl;
    3330
    34         public:
    35              /*!
    36             \enum UavType_t
    37             \brief type of UAV
    38             */
    39             typedef enum {
    40                 X4,/*!< 4 motors: front left, front right, rear left, rear right */
    41                 X8/*!< 8 motors: top front left, top front right, top rear left, top rear right, bottom front left, bottom front right, bottom rear left, bottom rear right */
    42                 } UavType_t;
     31public:
     32  /*!
     33 \enum UavType_t
     34 \brief type of UAV
     35 */
     36  typedef enum {
     37    X4, /*!< 4 motors: front left, front right, rear left, rear right */
     38    X8  /*!< 8 motors: top front left, top front right, top rear left, top rear
     39           right, bottom front left, bottom front right, bottom rear left, bottom
     40           rear right */
     41  } UavType_t;
    4342
    44             /*!
    45             \enum MotorNames_t
    46             \brief Motor names
    47             */
    48             typedef enum {
    49                 TopFrontLeft=0,/*!< Top front left, X4 or X8 */
    50                 TopFrontRight=1,/*!< Top front right, X4 or X8 */
    51                 TopRearLeft=2,/*!< Top rear left, X4 or X8 */
    52                 TopRearRight=3,/*!< Top rear right, X4 or X8 */
    53                 BottomFrontLeft=4,/*!< Bottom front left, X8 */
    54                 BottomFrontRight=5,/*!< Bottom front right, X8 */
    55                 BottomRearLeft=6,/*!< Bottom rear left, X8 */
    56                 BottomRearRight=7,/*!< Bottom rear right, X8 */
    57                 } MotorNames_t;
     43  /*!
     44  \enum MotorNames_t
     45  \brief Motor names
     46  */
     47  typedef enum {
     48    TopFrontLeft = 0,     /*!< Top front left, X4 or X8 */
     49    TopFrontRight = 1,    /*!< Top front right, X4 or X8 */
     50    TopRearLeft = 2,      /*!< Top rear left, X4 or X8 */
     51    TopRearRight = 3,     /*!< Top rear right, X4 or X8 */
     52    BottomFrontLeft = 4,  /*!< Bottom front left, X8 */
     53    BottomFrontRight = 5, /*!< Bottom front right, X8 */
     54    BottomRearLeft = 6,   /*!< Bottom rear left, X8 */
     55    BottomRearRight = 7,  /*!< Bottom rear right, X8 */
     56  } MotorNames_t;
    5857
    59             /*!
    60             * \brief Constructor
    61             *
    62             * Construct a X4 and X8 multiplexing
    63             *
    64             * \param parent parent
    65             * \param name name
    66             * \param type type
    67             */
    68             X4X8Multiplex(const core::FrameworkManager* parent,std::string name,UavType_t type);
     58  /*!
     59  * \brief Constructor
     60  *
     61  * Construct a X4 and X8 multiplexing
     62  *
     63  * \param parent parent
     64  * \param name name
     65  * \param type type
     66  */
     67  X4X8Multiplex(const core::FrameworkManager *parent, std::string name,
     68                UavType_t type);
    6969
    70             /*!
    71             * \brief Destructor
    72             *
    73             */
    74             ~X4X8Multiplex();
     70  /*!
     71  * \brief Destructor
     72  *
     73  */
     74  ~X4X8Multiplex();
    7575
    76             /*!
    77             * \brief Use default plot
    78             *
    79             * Plot the output values.
    80             *
    81             */
    82             void UseDefaultPlot(void);
     76  /*!
     77  * \brief Use default plot
     78  *
     79  * Plot the output values.
     80  *
     81  */
     82  void UseDefaultPlot(void);
    8383
    84             /*!
    85             * \brief Motors count
    86             *
    87             * Reimplemented from UavMultiplex.
    88             *
    89             * \return motors count
    90             */
    91             uint8_t MotorsCount(void) const;
     84  /*!
     85  * \brief Motors count
     86  *
     87  * Reimplemented from UavMultiplex.
     88  *
     89  * \return motors count
     90  */
     91  uint8_t MotorsCount(void) const;
    9292
    93         private:
    94             /*!
    95             * \brief Update using provided datas
    96             *
    97             * Reimplemented from IODevice.
    98             *
    99             * \param data data from the parent to process
    100             */
    101             void UpdateFrom(const core::io_data *data);
     93private:
     94  /*!
     95  * \brief Update using provided datas
     96  *
     97  * Reimplemented from IODevice.
     98  *
     99  * \param data data from the parent to process
     100  */
     101  void UpdateFrom(const core::io_data *data);
    102102
    103             X4X8Multiplex_impl *pimpl_;
    104 
    105     };
     103  X4X8Multiplex_impl *pimpl_;
     104};
    106105} // end namespace filter
    107106} // end namespace flair
Note: See TracChangeset for help on using the changeset viewer.