Changeset 13 in flair-dev for trunk


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

formatting script + include reformatted

Location:
trunk
Files:
1 added
127 edited

Legend:

Unmodified
Added
Removed
  • trunk/include/FlairCore/AhrsData.h

    r2 r13  
    1818#include <Quaternion.h>
    1919
    20 namespace flair { namespace core {
     20namespace flair {
     21namespace core {
    2122
    22     /*! \class AhrsData
    23     *
    24     * \brief Class defining AHRS datas
    25     *
    26     * AHRS datas consist of quaternion and rotational angles values. \n
    27     *
    28     */
    29     class AhrsData: public io_data {
    30         public:
    31             class Type: public DataType {
    32             public:
    33                 Type(const ScalarType &inElementDataType):
    34                     elementDataType(inElementDataType) {}
    35                 const ScalarType  &GetElementDataType() const {return elementDataType;}
    36                 std::string GetDescription() const {return "ahrs data";}
    37                 size_t GetSize() const {
    38                     return 7*elementDataType.GetSize();
    39                 }
    40             private:
    41                 const ScalarType &elementDataType;
    42             };
     23/*! \class AhrsData
     24*
     25* \brief Class defining AHRS datas
     26*
     27* AHRS datas consist of quaternion and rotational angles values. \n
     28*
     29*/
     30class AhrsData : public io_data {
     31public:
     32  class Type : public DataType {
     33  public:
     34    Type(const ScalarType &inElementDataType)
     35        : elementDataType(inElementDataType) {}
     36    const ScalarType &GetElementDataType() const { return elementDataType; }
     37    std::string GetDescription() const { return "ahrs data"; }
     38    size_t GetSize() const { return 7 * elementDataType.GetSize(); }
    4339
    44             /*!
    45             \enum PlotableData_t
    46             \brief Datas wich can be plotted in a DataPlot1D
    47             */
    48             typedef enum {
    49                 Roll/*! roll */, Pitch/*! pitch */, Yaw/*! yaw */,
    50                 RollDeg/*! roll degree*/, PitchDeg/*! pitch degree */, YawDeg/*! yaw degree */,
    51                 Q0/*! quaternion 0 */, Q1/*! quaternion 1 */, Q2/*! quaternion 2 */, Q3/*! quaternion 3 */,
    52                 Wx/*! x filtered angular rate */, Wy/*! y filtered angular rate */, Wz/*! z filtered angular rate */,
    53                 WxDeg/*! x filtered angular rate degree*/, WyDeg/*! y filtered angular rate degree*/, WzDeg/*! z filtered angular rate degree*/,
    54                 } PlotableData_t;
     40  private:
     41    const ScalarType &elementDataType;
     42  };
    5543
    56             /*!
    57             * \brief Constructor
    58             *
    59             * Construct an io_data representing AHRS datas. \n
    60             *
    61             * \param parent parent
    62             * \param name name
    63             * \param n number of samples
    64             */
    65             AhrsData(const Object* parent,std::string name="",int n=1);
     44  /*!
     45  \enum PlotableData_t
     46  \brief Datas wich can be plotted in a DataPlot1D
     47  */
     48  typedef enum {
     49    Roll /*! roll */,
     50    Pitch /*! pitch */,
     51    Yaw /*! yaw */,
     52    RollDeg /*! roll degree*/,
     53    PitchDeg /*! pitch degree */,
     54    YawDeg /*! yaw degree */,
     55    Q0 /*! quaternion 0 */,
     56    Q1 /*! quaternion 1 */,
     57    Q2 /*! quaternion 2 */,
     58    Q3 /*! quaternion 3 */,
     59    Wx /*! x filtered angular rate */,
     60    Wy /*! y filtered angular rate */,
     61    Wz /*! z filtered angular rate */,
     62    WxDeg /*! x filtered angular rate degree*/,
     63    WyDeg /*! y filtered angular rate degree*/,
     64    WzDeg /*! z filtered angular rate degree*/,
     65  } PlotableData_t;
    6666
    67             /*!
    68             * \brief Destructor
    69             *
    70             */
    71             ~AhrsData();
     67  /*!
     68  * \brief Constructor
     69  *
     70  * Construct an io_data representing AHRS datas. \n
     71  *
     72  * \param parent parent
     73  * \param name name
     74  * \param n number of samples
     75  */
     76  AhrsData(const Object *parent, std::string name = "", int n = 1);
    7277
    73             /*!
    74             * \brief Element
    75             *
    76             * Get a pointer to a specific element. This pointer can be used for plotting.
    77             *
    78             * \param plotableData data type
    79             *
    80             * \return pointer to the element
    81             */
    82             IODataElement *Element(PlotableData_t plotableData) const;
     78  /*!
     79  * \brief Destructor
     80  *
     81  */
     82  ~AhrsData();
    8383
    84             /*!
    85             * \brief Set quaternion
    86             *
    87             * This method is mutex protected.
    88             *
    89             * \param quaternion quaternion
    90             *
    91             */
    92             void SetQuaternion(const Quaternion &quaternion);
     84  /*!
     85  * \brief Element
     86  *
     87  * Get a pointer to a specific element. This pointer can be used for plotting.
     88  *
     89  * \param plotableData data type
     90  *
     91  * \return pointer to the element
     92  */
     93  IODataElement *Element(PlotableData_t plotableData) const;
    9394
    94             /*!
    95             * \brief Get quaternion
    96             *
    97             * This method is mutex protected.
    98             *
    99             * \return quaternion
    100             *
    101             */
    102             Quaternion GetQuaternion(void) const;
     95  /*!
     96  * \brief Set quaternion
     97  *
     98  * This method is mutex protected.
     99  *
     100  * \param quaternion quaternion
     101  *
     102  */
     103  void SetQuaternion(const Quaternion &quaternion);
    103104
    104             /*!
    105             * \brief Set angular rates
    106             *
    107             * This method is mutex protected.
    108             *
    109             * \param angularRates angular rates
    110             *
    111             */
    112             void SetAngularRates(const Vector3D &angularRates);
     105  /*!
     106  * \brief Get quaternion
     107  *
     108  * This method is mutex protected.
     109  *
     110  * \return quaternion
     111  *
     112  */
     113  Quaternion GetQuaternion(void) const;
    113114
    114             /*!
    115             * \brief Get angular rates
    116             *
    117             * This method is mutex protected.
    118             *
    119             * \return angular rates
    120             *
    121             */
    122             Vector3D GetAngularRates(void) const;
     115  /*!
     116  * \brief Set angular rates
     117  *
     118  * This method is mutex protected.
     119  *
     120  * \param angularRates angular rates
     121  *
     122  */
     123  void SetAngularRates(const Vector3D &angularRates);
    123124
    124             /*!
    125             * \brief Get both quaternion and angular rates
    126             *
    127             * This method is mutex protected.
    128             *
    129             * \param quaternion quaternion
    130             * \param angularRates angular rates
    131             *
    132             */
    133             void GetQuaternionAndAngularRates(Quaternion &quaternion,Vector3D &angularRates) const;
     125  /*!
     126  * \brief Get angular rates
     127  *
     128  * This method is mutex protected.
     129  *
     130  * \return angular rates
     131  *
     132  */
     133  Vector3D GetAngularRates(void) const;
    134134
    135             /*!
    136             * \brief Set both quaternion and angular rates
    137             *
    138             * This method is mutex protected.
    139             *
    140             * \param quaternion quaternion
    141             * \param angularRates angular rates
    142             *
    143             */
    144             void SetQuaternionAndAngularRates(const Quaternion &quaternion,const Vector3D &angularRates);
     135  /*!
     136  * \brief Get both quaternion and angular rates
     137  *
     138  * This method is mutex protected.
     139  *
     140  * \param quaternion quaternion
     141  * \param angularRates angular rates
     142  *
     143  */
     144  void GetQuaternionAndAngularRates(Quaternion &quaternion,
     145                                    Vector3D &angularRates) const;
    145146
    146             const Type &GetDataType() const {return dataType;}
    147         private:
    148             /*!
    149             * \brief Copy datas
    150             *
    151             * Reimplemented from io_data. \n
    152             * See io_data::CopyDatas.
    153             *
    154             * \param dst destination buffer
    155             */
    156             void CopyDatas(char *dst) const;
     147  /*!
     148  * \brief Set both quaternion and angular rates
     149  *
     150  * This method is mutex protected.
     151  *
     152  * \param quaternion quaternion
     153  * \param angularRates angular rates
     154  *
     155  */
     156  void SetQuaternionAndAngularRates(const Quaternion &quaternion,
     157                                    const Vector3D &angularRates);
    157158
    158             void Queue(char **dst,const void *src,size_t size) const;
     159  const Type &GetDataType() const { return dataType; }
    159160
    160             /*!
    161             * \brief %Quaternion
    162             *
    163             */
    164             Quaternion quaternion;
     161private:
     162  /*!
     163  * \brief Copy datas
     164  *
     165  * Reimplemented from io_data. \n
     166  * See io_data::CopyDatas.
     167  *
     168  * \param dst destination buffer
     169  */
     170  void CopyDatas(char *dst) const;
    165171
    166             /*!
    167             * \brief Angular rates
    168             *
    169             */
    170             Vector3D angularRates;
     172  void Queue(char **dst, const void *src, size_t size) const;
    171173
    172             Type dataType;
    173     };
     174  /*!
     175  * \brief %Quaternion
     176  *
     177  */
     178  Quaternion quaternion;
     179
     180  /*!
     181  * \brief Angular rates
     182  *
     183  */
     184  Vector3D angularRates;
     185
     186  Type dataType;
     187};
    174188
    175189} // end namespace core
  • trunk/include/FlairCore/Box.h

    r2 r13  
    1616#include <Widget.h>
    1717
    18 namespace flair
    19 {
    20 namespace gui
    21 {
     18namespace flair {
     19namespace gui {
    2220
    23     class Layout;
    24     class LayoutPosition;
     21class Layout;
     22class LayoutPosition;
    2523
    26     /*! \class Box
    27     *
    28     * \brief Abstract class to display a box on the ground station
    29     *
    30     * This is an abstract class to display boxes (like CheckBox, SpinBox, etc). \n
    31     * To access reimplemented box's value, use Box::GetMutex and Box::ReleaseMutex. \n
    32     * Note that this mutex is in reality the one from the parent Layout. To minimize memory
    33     * footprint, each Box does not have its own Mutex.
    34     */
    35     class Box: public Widget
    36     {
    37         public:
    38             /*!
    39             * \brief Constructor
    40             *
    41             * Construct a Box. \n
    42             * Type must agree with predifined (hard coded) types
    43             * in ground station code. \n
    44             * The Box will automatically be child of position->getLayout() Layout. After calling this method,
    45             * position will be deleted as it is no longer usefull.
    46             *
    47             * \param position position
    48             * \param name name
    49             * \param type type
    50             */
    51             Box(const LayoutPosition* position,std::string name,std::string type);
     24/*! \class Box
     25*
     26* \brief Abstract class to display a box on the ground station
     27*
     28* This is an abstract class to display boxes (like CheckBox, SpinBox, etc). \n
     29* To access reimplemented box's value, use Box::GetMutex and Box::ReleaseMutex.
     30*\n
     31* Note that this mutex is in reality the one from the parent Layout. To minimize
     32*memory
     33* footprint, each Box does not have its own Mutex.
     34*/
     35class Box : public Widget {
     36public:
     37  /*!
     38  * \brief Constructor
     39  *
     40  * Construct a Box. \n
     41  * Type must agree with predifined (hard coded) types
     42  * in ground station code. \n
     43  * The Box will automatically be child of position->getLayout() Layout. After
     44  *calling this method,
     45  * position will be deleted as it is no longer usefull.
     46  *
     47  * \param position position
     48  * \param name name
     49  * \param type type
     50  */
     51  Box(const LayoutPosition *position, std::string name, std::string type);
    5252
    53             /*!
    54             * \brief Destructor
    55             *
    56             */
    57             ~Box();
     53  /*!
     54  * \brief Destructor
     55  *
     56  */
     57  ~Box();
    5858
    59             /*!
    60             * \brief Has the value changed since last call?
    61             *
    62             * This method returns the value of an internal flag
    63             * which is set through SetValueChanged(). \n
    64             * After calling this method, the internal flag is
    65             * set to false.
    66             *
    67             * \return true is valued has changed since last call
    68             */
    69             bool ValueChanged(void);
     59  /*!
     60  * \brief Has the value changed since last call?
     61  *
     62  * This method returns the value of an internal flag
     63  * which is set through SetValueChanged(). \n
     64  * After calling this method, the internal flag is
     65  * set to false.
     66  *
     67  * \return true is valued has changed since last call
     68  */
     69  bool ValueChanged(void);
    7070
    71         protected:
    72             /*!
    73             * \brief Set the value changed flag
    74             *
    75             * The reimplemented class must call this method when Box's value is changed. \n
    76             * This method must be called with Mutex locked. Indeed, as reimplemented class
    77             * also has to lock the Mutex to change the Box value, this mecanism avoid two successives
    78             * lock and unlock.
    79             *
    80             */
    81             void SetValueChanged(void);
     71protected:
     72  /*!
     73  * \brief Set the value changed flag
     74  *
     75  * The reimplemented class must call this method when Box's value is changed.
     76  *\n
     77  * This method must be called with Mutex locked. Indeed, as reimplemented class
     78  * also has to lock the Mutex to change the Box value, this mecanism avoid two
     79  *successives
     80  * lock and unlock.
     81  *
     82  */
     83  void SetValueChanged(void);
    8284
    83             /*!
    84             * \brief Get Mutex
    85             *
    86             * This method must be called before changing Box's value or
    87             * calling SetValueChanged().
    88             *
    89             */
    90             void GetMutex(void) const;
     85  /*!
     86  * \brief Get Mutex
     87  *
     88  * This method must be called before changing Box's value or
     89  * calling SetValueChanged().
     90  *
     91  */
     92  void GetMutex(void) const;
    9193
    92             /*!
    93             * \brief Release Mutex
    94             *
    95              * This method must be called after changing Box's value or
    96             *  calling SetValueChanged().
    97             *
    98             */
    99             void ReleaseMutex(void) const;
     94  /*!
     95  * \brief Release Mutex
     96  *
     97   * This method must be called after changing Box's value or
     98  *  calling SetValueChanged().
     99  *
     100  */
     101  void ReleaseMutex(void) const;
    100102
    101 
    102         private:
    103             bool value_changed;
    104     };
     103private:
     104  bool value_changed;
     105};
    105106
    106107} // end namespace gui
  • trunk/include/FlairCore/CheckBox.h

    r2 r13  
    1616#include <Box.h>
    1717
    18 namespace flair
    19 {
    20 namespace gui
    21 {
     18namespace flair {
     19namespace gui {
    2220
    23     class LayoutPosition;
     21class LayoutPosition;
    2422
    25     /*! \class CheckBox
    26     *
    27     * \brief Class displaying a QCheckBox on the ground station
    28     *
    29     */
    30     class CheckBox: public Box
    31     {
    32         public:
    33             /*!
    34             * \brief Constructor
    35             *
    36             * Construct a QCheckBox at given position.
    37             *
    38             * \param position position to display the QCheckBox
    39             * \param name name
    40             * \param default_value default value if not in the xml config file
    41             */
    42             CheckBox(const LayoutPosition* position,std::string name,bool default_value=true);
     23/*! \class CheckBox
     24*
     25* \brief Class displaying a QCheckBox on the ground station
     26*
     27*/
     28class CheckBox : public Box {
     29public:
     30  /*!
     31  * \brief Constructor
     32  *
     33  * Construct a QCheckBox at given position.
     34  *
     35  * \param position position to display the QCheckBox
     36  * \param name name
     37  * \param default_value default value if not in the xml config file
     38  */
     39  CheckBox(const LayoutPosition *position, std::string name,
     40           bool default_value = true);
    4341
    44             /*!
    45             * \brief Destructor
    46             *
    47             */
    48             ~CheckBox();
     42  /*!
     43  * \brief Destructor
     44  *
     45  */
     46  ~CheckBox();
    4947
    50             /*!
    51             * \brief Is checked?
    52             *
    53             * \return true if checked
    54             */
    55             bool IsChecked(void) const;
     48  /*!
     49  * \brief Is checked?
     50  *
     51  * \return true if checked
     52  */
     53  bool IsChecked(void) const;
    5654
    57             /*!
    58             * \brief Value
    59             *
    60             * \return 1 if checked, 0 otherwise
    61             */
    62             int Value(void) const;
     55  /*!
     56  * \brief Value
     57  *
     58  * \return 1 if checked, 0 otherwise
     59  */
     60  int Value(void) const;
    6361
    64         private:
    65             /*!
    66             * \brief XmlEvent from ground station
    67             *
    68             * Reimplemented from Widget.
    69             *
    70             */
    71             void XmlEvent(void);
     62private:
     63  /*!
     64  * \brief XmlEvent from ground station
     65  *
     66  * Reimplemented from Widget.
     67  *
     68  */
     69  void XmlEvent(void);
    7270
    73             bool box_value;
    74     };
     71  bool box_value;
     72};
    7573
    7674} // end namespace gui
  • trunk/include/FlairCore/ComboBox.h

    r2 r13  
    1616#include <Box.h>
    1717
    18 namespace flair
    19 {
    20 namespace gui
    21 {
     18namespace flair {
     19namespace gui {
    2220
    23     class LayoutPosition;
     21class LayoutPosition;
    2422
    25     /*! \class ComboBox
    26     *
    27     * \brief Class displaying a QComboBox on the ground station
    28     *
    29     */
    30     class ComboBox: public Box
    31     {
    32         public:
    33             /*!
    34             * \brief Constructor
    35             *
    36             * Construct a QComboBox at given position.
    37             *
    38             * \param position position to display the QComboBox
    39             * \param name name
    40             */
    41             ComboBox(const LayoutPosition* position,std::string name);
     23/*! \class ComboBox
     24*
     25* \brief Class displaying a QComboBox on the ground station
     26*
     27*/
     28class ComboBox : public Box {
     29public:
     30  /*!
     31  * \brief Constructor
     32  *
     33  * Construct a QComboBox at given position.
     34  *
     35  * \param position position to display the QComboBox
     36  * \param name name
     37  */
     38  ComboBox(const LayoutPosition *position, std::string name);
    4239
    43             /*!
    44             * \brief Destructor
    45             *
    46             */
    47             ~ComboBox();
     40  /*!
     41  * \brief Destructor
     42  *
     43  */
     44  ~ComboBox();
    4845
    49              /*!
    50             * \brief Add an item
    51             *
    52             * Add an item to the end of the list.
    53             *
    54             * \param name item nam
    55             */
    56             void AddItem(std::string name);
     46  /*!
     47 * \brief Add an item
     48 *
     49 * Add an item to the end of the list.
     50 *
     51 * \param name item nam
     52 */
     53  void AddItem(std::string name);
    5754
    58             /*!
    59             * \brief Currend index
    60             *
    61             * Index of the currently selected item. Items are numbered starting to 0.
    62             *
    63             * \return index number
    64             */
    65             int CurrentIndex(void) const;
     55  /*!
     56  * \brief Currend index
     57  *
     58  * Index of the currently selected item. Items are numbered starting to 0.
     59  *
     60  * \return index number
     61  */
     62  int CurrentIndex(void) const;
    6663
    67         private:
    68             /*!
    69             * \brief XmlEvent from ground station
    70             *
    71             * Reimplemented from Widget.
    72             *
    73             */
    74             void XmlEvent(void);
     64private:
     65  /*!
     66  * \brief XmlEvent from ground station
     67  *
     68  * Reimplemented from Widget.
     69  *
     70  */
     71  void XmlEvent(void);
    7572
    76             int box_value;
    77     };
     73  int box_value;
     74};
    7875
    7976} // end namespace gui
  • trunk/include/FlairCore/ConditionVariable.h

    r2 r13  
    1818class ConditionVariable_impl;
    1919
    20 namespace flair
    21 {
    22 namespace core
    23 {
     20namespace flair {
     21namespace core {
    2422
    25     /*! \class ConditionVariable
    26     *
    27     * \brief Class defining a condition variable
    28     *
    29     */
     23/*! \class ConditionVariable
     24*
     25* \brief Class defining a condition variable
     26*
     27*/
    3028
    31     class ConditionVariable: public Mutex
    32     {
    33         public:
    34             /*!
    35             * \brief Constructor
    36             *
    37             * Construct a condition variable with its associated mutex.
    38             *
    39             * \param parent parent
    40             * \param name name
    41             */
    42             ConditionVariable(const Object* parent,std::string name);
     29class ConditionVariable : public Mutex {
     30public:
     31  /*!
     32  * \brief Constructor
     33  *
     34  * Construct a condition variable with its associated mutex.
     35  *
     36  * \param parent parent
     37  * \param name name
     38  */
     39  ConditionVariable(const Object *parent, std::string name);
    4340
    44             /*!
    45             * \brief Destructor
    46             *
    47             */
    48             ~ConditionVariable();
     41  /*!
     42  * \brief Destructor
     43  *
     44  */
     45  ~ConditionVariable();
    4946
    50             /*!
    51             * \brief Block on the condition variable
    52             *
    53             * This method must be called with mutex locked (see Mutex::GetMutex) by the calling thread or undefined behaviour will result. \n
    54             * It atomically releases mutex and causes the calling thread to block on the condition variable. \n
    55             * Only one thread can be blocked at the same time. \n
    56             * Upon successful return, the mutex has been locked and is owned by the calling thread which should unlock it (see Mutex::ReleaseMutex).
    57             */
    58             void CondWait(void);
     47  /*!
     48  * \brief Block on the condition variable
     49  *
     50  * This method must be called with mutex locked (see Mutex::GetMutex) by the
     51  *calling thread or undefined behaviour will result. \n
     52  * It atomically releases mutex and causes the calling thread to block on the
     53  *condition variable. \n
     54  * Only one thread can be blocked at the same time. \n
     55  * Upon successful return, the mutex has been locked and is owned by the
     56  *calling thread which should unlock it (see Mutex::ReleaseMutex).
     57  */
     58  void CondWait(void);
    5959
    60             /*!
    61             * \brief Block on the condition variable with a timeout
    62             *
    63             * This method must be called with mutex locked (see Mutex::GetMutex) by the calling thread or undefined behaviour will result. \n
    64             * It atomically releases mutex and causes the calling thread to block on the condition variable. \n
    65             * Only one thread can be blocked at the same time. \n
    66             * Upon successful return, the mutex has been locked and is owned by the calling thread which should unlock it (see Mutex::ReleaseMutex).
    67             *
    68             * \param date absolute date
    69             * \return true if the condition variable is signaled before the date specified in parameter elapses, false otherwise
    70             */
    71             bool CondWaitUntil(Time date);
     60  /*!
     61  * \brief Block on the condition variable with a timeout
     62  *
     63  * This method must be called with mutex locked (see Mutex::GetMutex) by the
     64  *calling thread or undefined behaviour will result. \n
     65  * It atomically releases mutex and causes the calling thread to block on the
     66  *condition variable. \n
     67  * Only one thread can be blocked at the same time. \n
     68  * Upon successful return, the mutex has been locked and is owned by the
     69  *calling thread which should unlock it (see Mutex::ReleaseMutex).
     70  *
     71  * \param date absolute date
     72  * \return true if the condition variable is signaled before the date specified
     73  *in parameter elapses, false otherwise
     74  */
     75  bool CondWaitUntil(Time date);
    7276
    73             /*!
    74             * \brief Unblock threads blocked on the condition variable
    75             *
    76             * This method should be called with mutex locked (see Mutex::GetMutex) by the calling thread. \n
    77             * In this case, upon return, the calling thread should unlock the mutex (see Mutex::ReleaseMutex).
    78             *
    79             */
    80             void CondSignal(void);
     77  /*!
     78  * \brief Unblock threads blocked on the condition variable
     79  *
     80  * This method should be called with mutex locked (see Mutex::GetMutex) by the
     81  *calling thread. \n
     82  * In this case, upon return, the calling thread should unlock the mutex (see
     83  *Mutex::ReleaseMutex).
     84  *
     85  */
     86  void CondSignal(void);
    8187
    82         private:
    83             class ConditionVariable_impl* pimpl_;
    84     };
     88private:
     89  class ConditionVariable_impl *pimpl_;
     90};
    8591
    8692} // end namespace core
  • trunk/include/FlairCore/ConnectedSocket.h

    r2 r13  
    1616#include <Object.h>
    1717
    18 namespace flair
    19 {
    20 namespace core
    21 {
     18namespace flair {
     19namespace core {
    2220
    23     /*! \class ConnectedSocket
    24     *
    25     * \brief Interface class encapsulating a connected socket. Preserves packets order and guaranty delivery.
    26     *
    27     */
    28     class ConnectedSocket: public Object {
    29     public:
    30         /*!
    31         * \brief Constructor
    32         *
    33         */
    34         ConnectedSocket(const Object* parent,const std::string name);
     21/*! \class ConnectedSocket
     22*
     23* \brief Interface class encapsulating a connected socket. Preserves packets
     24*order and guaranty delivery.
     25*
     26*/
     27class ConnectedSocket : public Object {
     28public:
     29  /*!
     30  * \brief Constructor
     31  *
     32  */
     33  ConnectedSocket(const Object *parent, const std::string name);
    3534
    36         /*!
    37         * \brief Destructor
    38         *
    39         */
    40         ~ConnectedSocket();
     35  /*!
     36  * \brief Destructor
     37  *
     38  */
     39  ~ConnectedSocket();
    4140
    42         /*!
    43         * \brief Returns a socket which listens on a specific port/address
    44         *
    45         * \param const Object* parentObject
    46         * \param const string name
    47         * \param unsigned int port
    48         * \param const localAddress (defaults to any)
    49         */
    50         virtual void Listen(const unsigned int port,const std::string localAddress="ANY")=0;
     41  /*!
     42  * \brief Returns a socket which listens on a specific port/address
     43  *
     44  * \param const Object* parentObject
     45  * \param const string name
     46  * \param unsigned int port
     47  * \param const localAddress (defaults to any)
     48  */
     49  virtual void Listen(const unsigned int port,
     50                      const std::string localAddress = "ANY") = 0;
    5151
    52         /*!
    53         * \brief Returns a socket on a new incoming connexion
    54         *
    55         * \param ConnectedSocket &listeningSocket
    56         */
    57         virtual ConnectedSocket *Accept(Time timeout)=0; //should throw an exception if not a listening socket
     52  /*!
     53  * \brief Returns a socket on a new incoming connexion
     54  *
     55  * \param ConnectedSocket &listeningSocket
     56  */
     57  virtual ConnectedSocket *Accept(
     58      Time timeout) = 0; // should throw an exception if not a listening socket
    5859
    59         /*!
    60         * \brief Returns a socket connected to a distant host
    61         *
    62         * \param const Object* parentObject
    63         * \param const string name
    64         * \param unsigned int port
    65         * \param const distantAddress
    66         * \param timeout timeout (in milliseconds)
    67         */
    68         virtual bool Connect(const unsigned int port,const std::string distantAddress,Time timeout)=0;
     60  /*!
     61  * \brief Returns a socket connected to a distant host
     62  *
     63  * \param const Object* parentObject
     64  * \param const string name
     65  * \param unsigned int port
     66  * \param const distantAddress
     67  * \param timeout timeout (in milliseconds)
     68  */
     69  virtual bool Connect(const unsigned int port,
     70                       const std::string distantAddress, Time timeout) = 0;
    6971
    70         /*!
    71         * \brief Send a message
    72         *
    73         * \param message message
    74         * \param message_len message length
    75         * \param timeout timeout (in milliseconds)
    76         */
    77         virtual ssize_t SendMessage(const char* message,size_t message_len,Time timeout)=0;
     72  /*!
     73  * \brief Send a message
     74  *
     75  * \param message message
     76  * \param message_len message length
     77  * \param timeout timeout (in milliseconds)
     78  */
     79  virtual ssize_t SendMessage(const char *message, size_t message_len,
     80                              Time timeout) = 0;
    7881
    79         /*!
    80         * \brief Receive a message
    81         *
    82         * Receive a message and wait up to timeout. \n
    83         *
    84         * \param buf buffer to put the message
    85         * \param buf_len buffer length
    86         * \param timeout timeout (in milliseconds)
    87         *
    88         * \return size of the received message
    89         */
    90         virtual ssize_t RecvMessage(char* buf,size_t buf_len,Time timeout)=0;
     82  /*!
     83  * \brief Receive a message
     84  *
     85  * Receive a message and wait up to timeout. \n
     86  *
     87  * \param buf buffer to put the message
     88  * \param buf_len buffer length
     89  * \param timeout timeout (in milliseconds)
     90  *
     91  * \return size of the received message
     92  */
     93  virtual ssize_t RecvMessage(char *buf, size_t buf_len, Time timeout) = 0;
    9194
    92         std::string ReadString(const size_t &stringLength, Time timeout);
    93         uint16_t ReadUInt16(Time const& timeout);
    94         void WriteUInt16(uint16_t const& data,Time const& timeout);
    95         uint32_t ReadUInt32(Time const& timeout);
    96         void WriteUInt32(uint32_t const& data,Time const& timeout);
     95  std::string ReadString(const size_t &stringLength, Time timeout);
     96  uint16_t ReadUInt16(Time const &timeout);
     97  void WriteUInt16(uint16_t const &data, Time const &timeout);
     98  uint32_t ReadUInt32(Time const &timeout);
     99  void WriteUInt32(uint32_t const &data, Time const &timeout);
    97100
    98         //!! See Socket.h for a more generic implementation of network/host endianness conversion
    99         virtual uint16_t NetworkToHost16(uint16_t data)=0;
    100         virtual uint16_t HostToNetwork16(uint16_t data)=0;
    101         virtual uint32_t NetworkToHost32(uint32_t data)=0;
    102         virtual uint32_t HostToNetwork32(uint32_t data)=0;
     101  //!! See Socket.h for a more generic implementation of network/host endianness
     102  // conversion
     103  virtual uint16_t NetworkToHost16(uint16_t data) = 0;
     104  virtual uint16_t HostToNetwork16(uint16_t data) = 0;
     105  virtual uint32_t NetworkToHost32(uint32_t data) = 0;
     106  virtual uint32_t HostToNetwork32(uint32_t data) = 0;
    103107};
    104108
  • trunk/include/FlairCore/DataPlot.h

    r2 r13  
    1818class DataPlot_impl;
    1919
    20 namespace flair
    21 {
    22     namespace core
    23     {
    24         class IODataElement;
    25     }
     20namespace flair {
     21namespace core {
     22class IODataElement;
    2623}
    27 namespace flair
    28 {
    29 namespace gui
    30 {
    31     class LayoutPosition;
     24}
     25namespace flair {
     26namespace gui {
     27class LayoutPosition;
    3228
    33     /*! \class DataPlot
    34     *
    35     * \brief Abstract class to display plots on ground station
    36     *
    37     */
    38     class DataPlot: public SendData
    39     {
    40         public:
    41             /*!
    42             \enum Color_t
    43             \brief Types of colors
    44             */
    45             typedef enum {
    46                 Red/*! red  */,
    47                 Blue/*! blue  */,
    48                 Green/*! green  */,
    49                 Yellow/*! yellow  */,
    50                 Black/*! black  */,
    51                 White/*! white  */,
    52                 } Color_t;
     29/*! \class DataPlot
     30*
     31* \brief Abstract class to display plots on ground station
     32*
     33*/
     34class DataPlot : public SendData {
     35public:
     36  /*!
     37  \enum Color_t
     38  \brief Types of colors
     39  */
     40  typedef enum {
     41    Red /*! red  */,
     42    Blue /*! blue  */,
     43    Green /*! green  */,
     44    Yellow /*! yellow  */,
     45    Black /*! black  */,
     46    White /*! white  */,
     47  } Color_t;
    5348
    54             /*!
    55             * \brief Constructor
    56             *
    57             * Type must agree with predifined (hard coded) types
    58             * in ground station code. After calling this constructor,
    59             * position will be deleted as it is no longer usefull.
    60             * The DataPlot will automatically be child of position->getLayout() Layout.
    61             *
    62             * \param position position
    63             * \param name nom
    64             * \param type type
    65             */
    66             DataPlot(const LayoutPosition* position,std::string name,std::string type);
     49  /*!
     50  * \brief Constructor
     51  *
     52  * Type must agree with predifined (hard coded) types
     53  * in ground station code. After calling this constructor,
     54  * position will be deleted as it is no longer usefull.
     55  * The DataPlot will automatically be child of position->getLayout() Layout.
     56  *
     57  * \param position position
     58  * \param name nom
     59  * \param type type
     60  */
     61  DataPlot(const LayoutPosition *position, std::string name, std::string type);
    6762
    68             /*!
    69             * \brief Destructor
    70             *
    71             */
    72             ~DataPlot();
     63  /*!
     64  * \brief Destructor
     65  *
     66  */
     67  ~DataPlot();
    7368
    74         protected:
    75             /*!
    76             * \brief Add an IODataElement to the plot.
    77             *
    78             * This method registers element for sending.
    79             *
    80             * \param element element to plot
    81             */
    82             void AddDataToSend(const core::IODataElement *element);
     69protected:
     70  /*!
     71  * \brief Add an IODataElement to the plot.
     72  *
     73  * This method registers element for sending.
     74  *
     75  * \param element element to plot
     76  */
     77  void AddDataToSend(const core::IODataElement *element);
    8378
    84         private:
    85             /*!
    86             * \brief Copy datas to specified buffer
    87             *
    88             * Reimplemented from SendData.
    89             *
    90             * \param buf output buffer
    91             */
    92             void CopyDatas(char* buf) const;
     79private:
     80  /*!
     81  * \brief Copy datas to specified buffer
     82  *
     83  * Reimplemented from SendData.
     84  *
     85  * \param buf output buffer
     86  */
     87  void CopyDatas(char *buf) const;
    9388
    94             /*!
    95             * \brief Extra Xml event
    96             *
    97             * Reimplemented from SendData.
    98             */
    99             void ExtraXmlEvent(void){};
     89  /*!
     90  * \brief Extra Xml event
     91  *
     92  * Reimplemented from SendData.
     93  */
     94  void ExtraXmlEvent(void){};
    10095
    101             class DataPlot_impl* pimpl_;
    102     };
     96  class DataPlot_impl *pimpl_;
     97};
    10398
    104     /*!
    105     * \brief Get RGB components from color type
    106     *
    107     *
    108     * \param color input color
    109     * \param r output component
    110     * \param g output component
    111     * \param b output component
    112     */
    113     void RGBFromColor(DataPlot::Color_t color,uint8_t &r,uint8_t &g,uint8_t &b);
     99/*!
     100* \brief Get RGB components from color type
     101*
     102*
     103* \param color input color
     104* \param r output component
     105* \param g output component
     106* \param b output component
     107*/
     108void RGBFromColor(DataPlot::Color_t color, uint8_t &r, uint8_t &g, uint8_t &b);
    114109
    115110} // end namespace gui
  • trunk/include/FlairCore/DataPlot1D.h

    r2 r13  
    1717#include <stdint.h>
    1818
    19 namespace flair
    20 {
    21 namespace core
    22 {
    23     class IODataElement;
     19namespace flair {
     20namespace core {
     21class IODataElement;
    2422}
    2523
    26 namespace gui
    27 {
     24namespace gui {
    2825
    29     class LayoutPosition;
     26class LayoutPosition;
    3027
    31     /*! \class DataPlot1D
    32     *
    33     * \brief Class displaying a 1D plot on the ground station
    34     *
    35     */
    36     class DataPlot1D: private DataPlot
    37     {
    38         public:
    39             /*!
    40             * \brief Constructor
    41             *
    42             * Construct a 1D plot at given position.
    43             *
    44             * \param position position to display the plot
    45             * \param name name
    46             * \param ymin default ymin of the plot
    47             * \param ymax default ymax of the plot
    48             */
    49             DataPlot1D(const LayoutPosition* position,std::string name,float ymin,float ymax);
     28/*! \class DataPlot1D
     29*
     30* \brief Class displaying a 1D plot on the ground station
     31*
     32*/
     33class DataPlot1D : private DataPlot {
     34public:
     35  /*!
     36  * \brief Constructor
     37  *
     38  * Construct a 1D plot at given position.
     39  *
     40  * \param position position to display the plot
     41  * \param name name
     42  * \param ymin default ymin of the plot
     43  * \param ymax default ymax of the plot
     44  */
     45  DataPlot1D(const LayoutPosition *position, std::string name, float ymin,
     46             float ymax);
    5047
    51             /*!
    52             * \brief Destructor
    53             *
    54             */
    55             ~DataPlot1D();
     48  /*!
     49  * \brief Destructor
     50  *
     51  */
     52  ~DataPlot1D();
    5653
    57             /*!
    58             * \brief Add a curve from an IODataElement to the plot.
    59             *
    60             * Curve's color can be selected by its name.
    61             *
    62             * \param element element to plot
    63             * \param color color of the curve
    64             * \param curve_name name of the curve for the legend, if unspecified, element->ObjectName() will be used
    65             */
    66             void AddCurve(const core::IODataElement* element,Color_t color,std::string curve_name="");
     54  /*!
     55  * \brief Add a curve from an IODataElement to the plot.
     56  *
     57  * Curve's color can be selected by its name.
     58  *
     59  * \param element element to plot
     60  * \param color color of the curve
     61  * \param curve_name name of the curve for the legend, if unspecified,
     62  *element->ObjectName() will be used
     63  */
     64  void AddCurve(const core::IODataElement *element, Color_t color,
     65                std::string curve_name = "");
    6766
    68             /*!
    69             * \brief Add a curve from an IODataElement to the plot.
    70             *
    71             * Curve's color can be selected by its RGB components.
    72             *
    73             * \param element element to plot
    74             * \param r red component of the curve
    75             * \param g green component of the curve
    76             * \param b blue component of the curve
    77             * \param curve_name name of the curve for the legend, if unspecified, element->ObjectName() will be used
    78             */
    79             void AddCurve(const core::IODataElement* element,uint8_t r=255,uint8_t g=0,uint8_t b=0,std::string curve_name="");
    80     };
     67  /*!
     68  * \brief Add a curve from an IODataElement to the plot.
     69  *
     70  * Curve's color can be selected by its RGB components.
     71  *
     72  * \param element element to plot
     73  * \param r red component of the curve
     74  * \param g green component of the curve
     75  * \param b blue component of the curve
     76  * \param curve_name name of the curve for the legend, if unspecified,
     77  *element->ObjectName() will be used
     78  */
     79  void AddCurve(const core::IODataElement *element, uint8_t r = 255,
     80                uint8_t g = 0, uint8_t b = 0, std::string curve_name = "");
     81};
    8182
    8283} // end namespace gui
  • trunk/include/FlairCore/DataPlot2D.h

    r2 r13  
    1717#include <stdint.h>
    1818
    19 namespace flair
    20 {
    21     namespace core
    22     {
    23         class IODataElement;
    24     }
     19namespace flair {
     20namespace core {
     21class IODataElement;
    2522}
    26 namespace flair
    27 {
    28 namespace gui
    29 {
     23}
     24namespace flair {
     25namespace gui {
    3026
    31     class LayoutPosition;
     27class LayoutPosition;
    3228
    33     /*! \class DataPlot2D
    34     *
    35     * \brief Class displaying a 2D plot on the ground station
    36     *
    37     */
    38     class DataPlot2D: private DataPlot
    39     {
    40         public:
    41             /*!
    42             * \brief Constructor
    43             *
    44             * Construct a 2D plot at given place position.
    45             *
    46             * \param position position to display the plot
    47             * \param name name
    48             * \param x_name name of x axis
    49             * \param xmin default xmin of the plot
    50             * \param xmax default xmax of the plot
    51             * \param y_name name of y axis
    52             * \param ymin default ymin of the plot
    53             * \param ymax default ymax of the plot
    54             */
    55             DataPlot2D(const LayoutPosition* position,std::string name,std::string x_name,float xmin,float xmax,std::string y_name,float ymin,float ymax);
     29/*! \class DataPlot2D
     30*
     31* \brief Class displaying a 2D plot on the ground station
     32*
     33*/
     34class DataPlot2D : private DataPlot {
     35public:
     36  /*!
     37  * \brief Constructor
     38  *
     39  * Construct a 2D plot at given place position.
     40  *
     41  * \param position position to display the plot
     42  * \param name name
     43  * \param x_name name of x axis
     44  * \param xmin default xmin of the plot
     45  * \param xmax default xmax of the plot
     46  * \param y_name name of y axis
     47  * \param ymin default ymin of the plot
     48  * \param ymax default ymax of the plot
     49  */
     50  DataPlot2D(const LayoutPosition *position, std::string name,
     51             std::string x_name, float xmin, float xmax, std::string y_name,
     52             float ymin, float ymax);
    5653
    57             /*!
    58             * \brief Destructor
    59             *
    60             */
    61             ~DataPlot2D();
     54  /*!
     55  * \brief Destructor
     56  *
     57  */
     58  ~DataPlot2D();
    6259
    63             /*!
    64             * \brief Add a curve from elements to the plot.
    65             *
    66             * Curve's color can be selected by its name.
    67             *
    68             * \param x_element element to plot for x coordinate
    69             * \param y_element element to plot for y coordinate
    70             * \param color color of the curve
    71             * \param curve_name name of the curve ofr the legend
    72             */
    73             void AddCurve(const core::IODataElement* x_element,const core::IODataElement* y_element,Color_t color,std::string curve_name="");
     60  /*!
     61  * \brief Add a curve from elements to the plot.
     62  *
     63  * Curve's color can be selected by its name.
     64  *
     65  * \param x_element element to plot for x coordinate
     66  * \param y_element element to plot for y coordinate
     67  * \param color color of the curve
     68  * \param curve_name name of the curve ofr the legend
     69  */
     70  void AddCurve(const core::IODataElement *x_element,
     71                const core::IODataElement *y_element, Color_t color,
     72                std::string curve_name = "");
    7473
    75             /*!
    76             * \brief Add a curve from elements to the plot.
    77             *
    78             * Curve's color can be selected by its RGB components.
    79             *
    80             * \param x_element element to plot for x coordinate
    81             * \param y_element element to plot for y coordinate
    82             * \param r red component of the curve
    83             * \param g green component of the curve
    84             * \param b blue component of the curve
    85             * \param curve_name name of the curve ofr the legend
    86             */
    87             void AddCurve(const core::IODataElement* x_element,const core::IODataElement* y_element,uint8_t r=255,uint8_t g=0,uint8_t b=0,std::string curve_name="");
    88     };
     74  /*!
     75  * \brief Add a curve from elements to the plot.
     76  *
     77  * Curve's color can be selected by its RGB components.
     78  *
     79  * \param x_element element to plot for x coordinate
     80  * \param y_element element to plot for y coordinate
     81  * \param r red component of the curve
     82  * \param g green component of the curve
     83  * \param b blue component of the curve
     84  * \param curve_name name of the curve ofr the legend
     85  */
     86  void AddCurve(const core::IODataElement *x_element,
     87                const core::IODataElement *y_element, uint8_t r = 255,
     88                uint8_t g = 0, uint8_t b = 0, std::string curve_name = "");
     89};
    8990
    9091} // end namespace gui
  • trunk/include/FlairCore/DoubleSpinBox.h

    r2 r13  
    1616#include <Box.h>
    1717
    18 namespace flair
    19 {
    20 namespace gui
    21 {
     18namespace flair {
     19namespace gui {
    2220
    23     class Layout;
     21class Layout;
    2422
    25     /*! \class DoubleSpinBox
    26     *
    27     * \brief Class displaying a QDoubleSpinBox on the ground station
    28     *
    29     */
    30     class DoubleSpinBox: public Box
    31     {
    32         public:
    33             /*!
    34             * \brief Constructor
    35             *
    36             * Construct a QDoubleSpinBox at given position. \n
    37             * The QDoubleSpinBox is saturated to min and max values.
    38             *
    39             * \param position position to display the QDoubleSpinBox
    40             * \param name name
    41             * \param min minimum value
    42             * \param max maximum value
    43             * \param step step
    44             * \param decimals number of decimals
    45             * \param default_value default value if not in the xml config file
    46             */
    47             DoubleSpinBox(const LayoutPosition* position,std::string name,double min,double max,double step,int decimals=2,double default_value=0);
     23/*! \class DoubleSpinBox
     24*
     25* \brief Class displaying a QDoubleSpinBox on the ground station
     26*
     27*/
     28class DoubleSpinBox : public Box {
     29public:
     30  /*!
     31  * \brief Constructor
     32  *
     33  * Construct a QDoubleSpinBox at given position. \n
     34  * The QDoubleSpinBox is saturated to min and max values.
     35  *
     36  * \param position position to display the QDoubleSpinBox
     37  * \param name name
     38  * \param min minimum value
     39  * \param max maximum value
     40  * \param step step
     41  * \param decimals number of decimals
     42  * \param default_value default value if not in the xml config file
     43  */
     44  DoubleSpinBox(const LayoutPosition *position, std::string name, double min,
     45                double max, double step, int decimals = 2,
     46                double default_value = 0);
    4847
    49             /*!
    50             * \brief Constructor
    51             *
    52             * Construct a QDoubleSpinBox at given position. \n
    53             * The QDoubleSpinBox is saturated to min and max values.
    54             *
    55             * \param position position to display the QDoubleSpinBox
    56             * \param name name
    57             * \param suffix suffix for the value (eg unit)
    58             * \param min minimum value
    59             * \param max maximum value
    60             * \param step step
    61             * \param decimals number of decimals
    62             * \param default_value default value if not in the xml config file
    63             */
    64             DoubleSpinBox(const LayoutPosition* position,std::string name,std::string suffix,double min,double max,double step,int decimals=2,double default_value=0);
     48  /*!
     49  * \brief Constructor
     50  *
     51  * Construct a QDoubleSpinBox at given position. \n
     52  * The QDoubleSpinBox is saturated to min and max values.
     53  *
     54  * \param position position to display the QDoubleSpinBox
     55  * \param name name
     56  * \param suffix suffix for the value (eg unit)
     57  * \param min minimum value
     58  * \param max maximum value
     59  * \param step step
     60  * \param decimals number of decimals
     61  * \param default_value default value if not in the xml config file
     62  */
     63  DoubleSpinBox(const LayoutPosition *position, std::string name,
     64                std::string suffix, double min, double max, double step,
     65                int decimals = 2, double default_value = 0);
    6566
    66             /*!
    67             * \brief Destructor
    68             *
    69             */
    70             ~DoubleSpinBox();
     67  /*!
     68  * \brief Destructor
     69  *
     70  */
     71  ~DoubleSpinBox();
    7172
    72             /*!
    73             * \brief Value
    74             *
    75             * \return value
    76             */
    77             double Value(void) const;
     73  /*!
     74  * \brief Value
     75  *
     76  * \return value
     77  */
     78  double Value(void) const;
    7879
    79         private:
    80             /*!
    81             * \brief XmlEvent from ground station
    82             *
    83             * Reimplemented from Widget.
    84             *
    85             */
    86             void XmlEvent(void);
     80private:
     81  /*!
     82  * \brief XmlEvent from ground station
     83  *
     84  * Reimplemented from Widget.
     85  *
     86  */
     87  void XmlEvent(void);
    8788
    88             double box_value;
    89     };
     89  double box_value;
     90};
    9091
    9192} // end namespace gui
  • trunk/include/FlairCore/Euler.h

    r2 r13  
    1414#define EULER_H
    1515
    16 namespace flair { namespace core {
    17     class Quaternion;
     16namespace flair {
     17namespace core {
     18class Quaternion;
    1819
    19     /*! \class Euler
    20     *
    21     * \brief Class defining euler angles
    22     *
    23     * Euler angles are expressed in radians.
    24     *
    25     */
    26     class Euler {
    27         public:
    28             /*!
    29             * \brief Constructor
    30             *
    31             * Construct euler angles using specified values.
    32             *
    33             * \param roll roll value
    34             * \param pitch pitch value
    35             * \param yaw yaw value
    36             */
    37             Euler(float roll=0,float pitch=0,float yaw=0);
     20/*! \class Euler
     21*
     22* \brief Class defining euler angles
     23*
     24* Euler angles are expressed in radians.
     25*
     26*/
     27class Euler {
     28public:
     29  /*!
     30  * \brief Constructor
     31  *
     32  * Construct euler angles using specified values.
     33  *
     34  * \param roll roll value
     35  * \param pitch pitch value
     36  * \param yaw yaw value
     37  */
     38  Euler(float roll = 0, float pitch = 0, float yaw = 0);
    3839
    39             /*!
    40             * \brief Destructor
    41             *
    42             */
    43             ~Euler();
     40  /*!
     41  * \brief Destructor
     42  *
     43  */
     44  ~Euler();
    4445
    45             /*!
    46             * \brief x axis rotation
    47             *
    48             * \param value rotation value in radians
    49             */
    50             //todo: passer par un quaternion
    51             //void RotateX(float value);
     46  /*!
     47  * \brief x axis rotation
     48  *
     49  * \param value rotation value in radians
     50  */
     51  // todo: passer par un quaternion
     52  // void RotateX(float value);
    5253
    53             /*!
    54             * \brief x axis rotation
    55             *
    56             * \param value rotation value in degrees
    57             */
    58             //void RotateXDeg(float value);
     54  /*!
     55  * \brief x axis rotation
     56  *
     57  * \param value rotation value in degrees
     58  */
     59  // void RotateXDeg(float value);
    5960
    60             /*!
    61             * \brief y axis rotation
    62             *
    63             * \param value rotation value in radians
    64             */
    65             //void RotateY(float value);
     61  /*!
     62  * \brief y axis rotation
     63  *
     64  * \param value rotation value in radians
     65  */
     66  // void RotateY(float value);
    6667
    67             /*!
    68             * \brief y axis rotation
    69             *
    70             * \param value rotation value in degrees
    71             */
    72             //void RotateYDeg(float value);
     68  /*!
     69  * \brief y axis rotation
     70  *
     71  * \param value rotation value in degrees
     72  */
     73  // void RotateYDeg(float value);
    7374
    74             /*!
    75             * \brief z axis rotation
    76             *
    77             * \param value rotation value in radians
    78             */
    79             //void RotateZ(float value);
     75  /*!
     76  * \brief z axis rotation
     77  *
     78  * \param value rotation value in radians
     79  */
     80  // void RotateZ(float value);
    8081
    81             /*!
    82             * \brief z axis rotation
    83             *
    84             * \param value rotation value in degrees
    85             */
    86             //void RotateZDeg(float value);
     82  /*!
     83  * \brief z axis rotation
     84  *
     85  * \param value rotation value in degrees
     86  */
     87  // void RotateZDeg(float value);
    8788
    88             /*!
    89             * \brief Convert to quaternion
    90             *
    91             * \param quaternion output quaternion
    92             */
    93             void ToQuaternion(Quaternion &quaternion) const;
     89  /*!
     90  * \brief Convert to quaternion
     91  *
     92  * \param quaternion output quaternion
     93  */
     94  void ToQuaternion(Quaternion &quaternion) const;
    9495
    95             /*!
    96             * \brief Convert to quaternion
    97             *
    98             * \return quaternion
    99             */
    100             Quaternion ToQuaternion(void) const;
    101             /*!
    102             * \brief Convert from radian to degree
    103             *
    104             * \param radianValue value in radian
    105             *
    106             * \return value in degree
    107             */
    108             static float ToDegree(float radianValue);
     96  /*!
     97  * \brief Convert to quaternion
     98  *
     99  * \return quaternion
     100  */
     101  Quaternion ToQuaternion(void) const;
     102  /*!
     103  * \brief Convert from radian to degree
     104  *
     105  * \param radianValue value in radian
     106  *
     107  * \return value in degree
     108  */
     109  static float ToDegree(float radianValue);
    109110
    110             /*!
    111             * \brief Convert from degree to radian
    112             *
    113             * \param degreeValue value in degree
    114             *
    115             * \return value in radian
    116             */
    117             static float ToRadian(float degreeValue);
     111  /*!
     112  * \brief Convert from degree to radian
     113  *
     114  * \param degreeValue value in degree
     115  *
     116  * \return value in radian
     117  */
     118  static float ToRadian(float degreeValue);
    118119
    119             /*!
    120             * \brief Compute yaw distance
    121             *
    122             * Compute yaw distance from given angle. This is the minimum distance.
    123             *
    124             * \param angle starting angle
    125             *
    126             * \return value distance in radian
    127             */
    128             float YawDistanceFrom(float angle) const;
     120  /*!
     121  * \brief Compute yaw distance
     122  *
     123  * Compute yaw distance from given angle. This is the minimum distance.
     124  *
     125  * \param angle starting angle
     126  *
     127  * \return value distance in radian
     128  */
     129  float YawDistanceFrom(float angle) const;
    129130
    130             /*!
    131             * \brief roll value
    132             */
    133             float roll;
     131  /*!
     132  * \brief roll value
     133  */
     134  float roll;
    134135
    135             /*!
    136             * \brief pitch value
    137             */
    138             float pitch;
     136  /*!
     137  * \brief pitch value
     138  */
     139  float pitch;
    139140
    140             /*!
    141             * \brief yaw value
    142             */
    143             float yaw;
     141  /*!
     142  * \brief yaw value
     143  */
     144  float yaw;
    144145
    145             Euler& operator=(const Euler &euler);
    146 
    147     };
     146  Euler &operator=(const Euler &euler);
     147};
    148148
    149149} // end namespace core
  • trunk/include/FlairCore/FrameworkManager.h

    r2 r13  
    1818class FrameworkManager_impl;
    1919
    20 namespace flair
    21 {
    22     namespace gui
    23     {
    24         class TabWidget;
    25         class SendData;
    26     }
     20namespace flair {
     21namespace gui {
     22class TabWidget;
     23class SendData;
    2724}
    28 namespace flair
    29 {
    30 namespace core
    31 {
    32     class IODevice;
    33 
    34     /*! \class FrameworkManager
    35     *
    36     * \brief Main class of the Framework library
    37     *
    38     * This is the main class of the library. Only one instance of this class is allowed
    39     * by program. Morevoer, its name must be unique if more than one program using this class
    40     * is running on the same system (a control and a simlator for example). \n
    41     * This class allows: \n
    42     * -connexion with ground station, \n
    43     * -creation of a QTabWidget on ground station, \n
    44     * -handling of xml files, used for default values of Widgets, \n
    45     * -logging of datas.
    46     */
    47     class FrameworkManager: public Object
    48     {
    49         public:
    50             /*!
    51             * \brief Constructor
    52             *
    53             * Construct a FrameworkManager. \n
    54             * Call SetupConnection method just after this constructor to setup the conection with a ground station.
    55             *
    56             * \param name name, must be unique
    57             */
    58             FrameworkManager(std::string name);
    59 
    60             /*!
    61             * \brief Destructor
    62             *
    63             * Calling it will automatically destruct all childs. \n
    64             * Destruction implies destruction of the QTabWidget on ground station.
    65             *
    66             */
    67             ~FrameworkManager();
    68 
    69             /*!
    70             * \brief Setup the connection with ground station
    71             *
    72             * Call this method just after the constructor of this class. If this method is not called, the program will run headless.
    73             *
    74             * \param address address of ground station
    75             * \param port port of ground station
    76             * \param rcv_buf_size receive buffer size
    77             */
    78             void SetupConnection(std::string address,uint16_t port,size_t rcv_buf_size=10000);
    79 
    80             /*!
    81             * \brief Setup the user interface
    82             *
    83             * If this method is called after SetupConnection, Widgets will be displayed in the ground station.
    84             * Otherwise, it will run headless, but default values of Widgets will be taken from the xml file.
    85             *
    86             * \param xml_file xml file for default values of Widgets
    87             */
    88             void SetupUserInterface(std::string xml_file);
    89 
    90             /*!
    91             * \brief Get TabWidget
    92             *
    93             * \return TabWidget
    94             */
    95             gui::TabWidget* GetTabWidget(void) const;
    96 
    97             /*!
    98             * \brief Logger setup
    99             *
    100             * Setup path of log files. \n
    101             * No logging will be performed if this method is not called. \n
    102             *
    103             * \param log_path path to store logs
    104             */
    105             void SetupLogger(std::string log_path);
    106 
    107             /*!
    108             * \brief Add log element
    109             *
    110             * The added element will be automatically logged once
    111             * logging started (see StartLog()). \n
    112             * This element must define on its side the io_data
    113             * to log, trough IODevice::SetDataToLog method.
    114             *
    115             * \param device IODevice to add
    116             */
    117             void AddDeviceToLog(IODevice *device);
    118 
    119             /*!
    120             * \brief Start logging
    121             *
    122             * All IODevice added through AddDeviceToLog() method
    123             * will automatically be logged. \n
    124             * SetupLogger() must have been called before.
    125             */
    126             void StartLog(void);
    127 
    128             /*!
    129             * \brief Stop logging
    130             *
    131             * Logs will automatically be sent to ground station.
    132             */
    133             void StopLog(void);
    134 
    135             /*!
    136             * \brief Is logging?
    137             *
    138             * \return true if is logging
    139             */
    140             bool IsLogging(void) const;
    141 
    142             /*!
    143             * \brief Notify that SendData's period has changed
    144             *
    145             * This funtion must be called when the period has changed. \n
    146             * Normally, it occurs in the Widget::XmlEvent method. \n
    147             * This method must be called with communication blocked (see BlockCom()).
    148             *
    149             * \param obj SendData which changed
    150             */
    151             void UpdateSendData(const gui::SendData *obj);
    152 
    153             /*!
    154             * \brief Block communication
    155             *
    156             * This funtion blocks the communication beetween the program and ground station. \n
    157             * It must be called before changing datas or parameters exchanged between the program
    158             * and the ground station.
    159             *
    160             */
    161             void BlockCom(void);
    162 
    163              /*!
    164             * \brief Unblock communication
    165             *
    166             * This funtion unblocks the communication beetween the program and ground station. \n
    167             * It must be called after changing datas or parameters exchanged between the program
    168             * and the ground station.
    169             *
    170             */
    171             void UnBlockCom(void);
    172 
    173             /*!
    174             * \brief Is connection lost?
    175             *
    176             * Once this method returns true, it will never return false back. \n
    177             * Note that this method return false if no connection is defined (see SetupConnection).
    178             *
    179             * \return true if connection with ground station is lost
    180             */
    181             bool ConnectionLost(void) const;
    182 
    183             /*!
    184             * \brief Disable errors display
    185             *
    186             * Disable errors display, if you do not want to saturate console for exemple.
    187             * By defaults errors disply is enabled.
    188             *
    189             * \param value true to disable errors display
    190             */
    191             void DisableErrorsDisplay(bool value);
    192 
    193             /*!
    194             * \brief Is displaying errors?
    195             *
    196             *
    197             * \return true if errors display is enabled
    198             */
    199             bool IsDisplayingErrors(void) const;
    200 
    201         private:
    202             class FrameworkManager_impl* pimpl_;
    203     };
    204 
    205     /*!
    206     * \brief get FrameworkManager
    207     *
    208     * \return the FrameworkManager
    209     */
    210     FrameworkManager* getFrameworkManager(void);
    211 
    212     /*!
    213     * \brief is big endian?
    214     *
    215     * \return true if big endian, false if little endian
    216     */
    217     bool IsBigEndian(void);
     25}
     26namespace flair {
     27namespace core {
     28class IODevice;
     29
     30/*! \class FrameworkManager
     31*
     32* \brief Main class of the Framework library
     33*
     34* This is the main class of the library. Only one instance of this class is
     35*allowed
     36* by program. Morevoer, its name must be unique if more than one program using
     37*this class
     38* is running on the same system (a control and a simlator for example). \n
     39* This class allows: \n
     40* -connexion with ground station, \n
     41* -creation of a QTabWidget on ground station, \n
     42* -handling of xml files, used for default values of Widgets, \n
     43* -logging of datas.
     44*/
     45class FrameworkManager : public Object {
     46public:
     47  /*!
     48  * \brief Constructor
     49  *
     50  * Construct a FrameworkManager. \n
     51  * Call SetupConnection method just after this constructor to setup the
     52  *conection with a ground station.
     53  *
     54  * \param name name, must be unique
     55  */
     56  FrameworkManager(std::string name);
     57
     58  /*!
     59  * \brief Destructor
     60  *
     61  * Calling it will automatically destruct all childs. \n
     62  * Destruction implies destruction of the QTabWidget on ground station.
     63  *
     64  */
     65  ~FrameworkManager();
     66
     67  /*!
     68  * \brief Setup the connection with ground station
     69  *
     70  * Call this method just after the constructor of this class. If this method is
     71  *not called, the program will run headless.
     72  *
     73  * \param address address of ground station
     74  * \param port port of ground station
     75  * \param rcv_buf_size receive buffer size
     76  */
     77  void SetupConnection(std::string address, uint16_t port,
     78                       size_t rcv_buf_size = 10000);
     79
     80  /*!
     81  * \brief Setup the user interface
     82  *
     83  * If this method is called after SetupConnection, Widgets will be displayed in
     84  *the ground station.
     85  * Otherwise, it will run headless, but default values of Widgets will be taken
     86  *from the xml file.
     87  *
     88  * \param xml_file xml file for default values of Widgets
     89  */
     90  void SetupUserInterface(std::string xml_file);
     91
     92  /*!
     93  * \brief Get TabWidget
     94  *
     95  * \return TabWidget
     96  */
     97  gui::TabWidget *GetTabWidget(void) const;
     98
     99  /*!
     100  * \brief Logger setup
     101  *
     102  * Setup path of log files. \n
     103  * No logging will be performed if this method is not called. \n
     104  *
     105  * \param log_path path to store logs
     106  */
     107  void SetupLogger(std::string log_path);
     108
     109  /*!
     110  * \brief Add log element
     111  *
     112  * The added element will be automatically logged once
     113  * logging started (see StartLog()). \n
     114  * This element must define on its side the io_data
     115  * to log, trough IODevice::SetDataToLog method.
     116  *
     117  * \param device IODevice to add
     118  */
     119  void AddDeviceToLog(IODevice *device);
     120
     121  /*!
     122  * \brief Start logging
     123  *
     124  * All IODevice added through AddDeviceToLog() method
     125  * will automatically be logged. \n
     126  * SetupLogger() must have been called before.
     127  */
     128  void StartLog(void);
     129
     130  /*!
     131  * \brief Stop logging
     132  *
     133  * Logs will automatically be sent to ground station.
     134  */
     135  void StopLog(void);
     136
     137  /*!
     138  * \brief Is logging?
     139  *
     140  * \return true if is logging
     141  */
     142  bool IsLogging(void) const;
     143
     144  /*!
     145  * \brief Notify that SendData's period has changed
     146  *
     147  * This funtion must be called when the period has changed. \n
     148  * Normally, it occurs in the Widget::XmlEvent method. \n
     149  * This method must be called with communication blocked (see BlockCom()).
     150  *
     151  * \param obj SendData which changed
     152  */
     153  void UpdateSendData(const gui::SendData *obj);
     154
     155  /*!
     156  * \brief Block communication
     157  *
     158  * This funtion blocks the communication beetween the program and ground
     159  *station. \n
     160  * It must be called before changing datas or parameters exchanged between the
     161  *program
     162  * and the ground station.
     163  *
     164  */
     165  void BlockCom(void);
     166
     167  /*!
     168 * \brief Unblock communication
     169 *
     170 * This funtion unblocks the communication beetween the program and ground
     171 *station. \n
     172 * It must be called after changing datas or parameters exchanged between the
     173 *program
     174 * and the ground station.
     175 *
     176 */
     177  void UnBlockCom(void);
     178
     179  /*!
     180  * \brief Is connection lost?
     181  *
     182  * Once this method returns true, it will never return false back. \n
     183  * Note that this method return false if no connection is defined (see
     184  *SetupConnection).
     185  *
     186  * \return true if connection with ground station is lost
     187  */
     188  bool ConnectionLost(void) const;
     189
     190  /*!
     191  * \brief Disable errors display
     192  *
     193  * Disable errors display, if you do not want to saturate console for exemple.
     194  * By defaults errors disply is enabled.
     195  *
     196  * \param value true to disable errors display
     197  */
     198  void DisableErrorsDisplay(bool value);
     199
     200  /*!
     201  * \brief Is displaying errors?
     202  *
     203  *
     204  * \return true if errors display is enabled
     205  */
     206  bool IsDisplayingErrors(void) const;
     207
     208private:
     209  class FrameworkManager_impl *pimpl_;
     210};
     211
     212/*!
     213* \brief get FrameworkManager
     214*
     215* \return the FrameworkManager
     216*/
     217FrameworkManager *getFrameworkManager(void);
     218
     219/*!
     220* \brief is big endian?
     221*
     222* \return true if big endian, false if little endian
     223*/
     224bool IsBigEndian(void);
    218225
    219226} // end namespace core
  • trunk/include/FlairCore/GeoCoordinate.h

    r2 r13  
    1515#include <io_data.h>
    1616
    17 namespace flair { namespace core {
     17namespace flair {
     18namespace core {
    1819
    19     /*! \class GeoCoordinate
    20     *
    21     * \brief Class defining a point by its lla coordinates
    22     */
    23     class GeoCoordinate: public io_data {
    24         public:
    25             class Type: public DataType {
    26             public:
    27                 size_t GetSize() const {
    28                     return sizeof(latitude)+sizeof(longitude)+sizeof(altitude);
    29                 }
    30                 std::string GetDescription() const {return "lla";}
    31             };
     20/*! \class GeoCoordinate
     21*
     22* \brief Class defining a point by its lla coordinates
     23*/
     24class GeoCoordinate : public io_data {
     25public:
     26  class Type : public DataType {
     27  public:
     28    size_t GetSize() const {
     29      return sizeof(latitude) + sizeof(longitude) + sizeof(altitude);
     30    }
     31    std::string GetDescription() const { return "lla"; }
     32  };
    3233
    33             /*!
    34             * \brief Constructor
    35             *
    36             * Construct GeoCoordinate using values from another class.
    37             *
    38             * \param parent parent
    39             * \param name name
    40             * \param point class to copy
    41             * \param n number of samples
    42             */
    43             GeoCoordinate(const Object* parent,std::string name,const GeoCoordinate *point,int n=1);
     34  /*!
     35  * \brief Constructor
     36  *
     37  * Construct GeoCoordinate using values from another class.
     38  *
     39  * \param parent parent
     40  * \param name name
     41  * \param point class to copy
     42  * \param n number of samples
     43  */
     44  GeoCoordinate(const Object *parent, std::string name,
     45                const GeoCoordinate *point, int n = 1);
    4446
    45             /*!
    46             * \brief Constructor
    47             *
    48             * Construct GeoCoordinate using specified values.
    49             *
    50             * \param parent parent
    51             * \param name name
    52             * \param latitude latitude
    53             * \param longitude longitude
    54             * \param altitude altitude
    55             * \param n number of samples
    56             */
    57             GeoCoordinate(const Object* parent,std::string name,double latitude,double longitude,double altitude,int n=1);
     47  /*!
     48  * \brief Constructor
     49  *
     50  * Construct GeoCoordinate using specified values.
     51  *
     52  * \param parent parent
     53  * \param name name
     54  * \param latitude latitude
     55  * \param longitude longitude
     56  * \param altitude altitude
     57  * \param n number of samples
     58  */
     59  GeoCoordinate(const Object *parent, std::string name, double latitude,
     60                double longitude, double altitude, int n = 1);
    5861
    59             /*!
    60             * \brief Destructor
    61             *
    62             */
    63             ~GeoCoordinate();
     62  /*!
     63  * \brief Destructor
     64  *
     65  */
     66  ~GeoCoordinate();
    6467
    65             /*!
    66             * \brief Copy
    67             *
    68             * \param point class to copy
    69             */
    70             void CopyFrom(const GeoCoordinate *point);
     68  /*!
     69  * \brief Copy
     70  *
     71  * \param point class to copy
     72  */
     73  void CopyFrom(const GeoCoordinate *point);
    7174
    72             /*!
    73             * \brief Set coordinates
    74             *
    75             * \param latitude latitude
    76             * \param longitude longitude
    77             * \param altitude altitude
    78             */
    79             void SetCoordinates(double latitude,double longitude,double altitude);
     75  /*!
     76  * \brief Set coordinates
     77  *
     78  * \param latitude latitude
     79  * \param longitude longitude
     80  * \param altitude altitude
     81  */
     82  void SetCoordinates(double latitude, double longitude, double altitude);
    8083
    81             /*!
    82             * \brief Get coordinates
    83             *
    84             * \param latitude latitude
    85             * \param longitude longitude
    86             * \param altitude altitude
    87             */
    88             void GetCoordinates(double *latitude,double *longitude,double *altitude) const;
     84  /*!
     85  * \brief Get coordinates
     86  *
     87  * \param latitude latitude
     88  * \param longitude longitude
     89  * \param altitude altitude
     90  */
     91  void GetCoordinates(double *latitude, double *longitude,
     92                      double *altitude) const;
    8993
    90             Type const &GetDataType() const {return dataType;}
    91         private:
    92             /*!
    93             * \brief Copy datas
    94             *
    95             * Reimplemented from io_data. \n
    96             * See io_data::CopyDatas.
    97             *
    98             * \param dst destination buffer
    99             */
    100             void CopyDatas(char* ptr) const;
     94  Type const &GetDataType() const { return dataType; }
    10195
    102             double latitude;
    103             double longitude;
    104             double altitude;
    105             Type dataType;
    106     };
     96private:
     97  /*!
     98  * \brief Copy datas
     99  *
     100  * Reimplemented from io_data. \n
     101  * See io_data::CopyDatas.
     102  *
     103  * \param dst destination buffer
     104  */
     105  void CopyDatas(char *ptr) const;
     106
     107  double latitude;
     108  double longitude;
     109  double altitude;
     110  Type dataType;
     111};
    107112
    108113} // end namespace core
  • trunk/include/FlairCore/GridLayout.h

    r2 r13  
    1616#include <Layout.h>
    1717
    18 namespace flair
    19 {
    20 namespace gui
    21 {
    22     class LayoutPosition;
     18namespace flair {
     19namespace gui {
     20class LayoutPosition;
    2321
    24     /*! \class GridLayout
    25     *
    26     * \brief Class displaying a QGridLayout on the ground station
    27     *
    28     */
    29     class GridLayout: public Layout
    30     {
    31         public:
    32             /*!
    33             * \brief Constructor
    34             *
    35             * Construct a QCheckBox at given position. \n
    36             * The GridLayout will automatically be child of position->getLayout() Layout. After calling this constructor,
    37             * position will be deleted as it is no longer usefull.
    38             *
    39             * \param parent parent
    40             * \param name name
     22/*! \class GridLayout
     23*
     24* \brief Class displaying a QGridLayout on the ground station
     25*
     26*/
     27class GridLayout : public Layout {
     28public:
     29  /*!
     30  * \brief Constructor
     31  *
     32  * Construct a QCheckBox at given position. \n
     33  * The GridLayout will automatically be child of position->getLayout() Layout.
     34  After calling this constructor,
     35  * position will be deleted as it is no longer usefull.
     36  *
     37  * \param parent parent
     38  * \param name name
    4139
    42             */
    43             GridLayout(const LayoutPosition* position,std::string name);
     40  */
     41  GridLayout(const LayoutPosition *position, std::string name);
    4442
    45             /*!
    46             * \brief Destructor
    47             *
    48             */
    49             ~GridLayout();
     43  /*!
     44  * \brief Destructor
     45  *
     46  */
     47  ~GridLayout();
    5048
    51         private:
    52     };
     49private:
     50};
    5351
    5452} // end namespace gui
  • trunk/include/FlairCore/GroupBox.h

    r2 r13  
    1616#include <Layout.h>
    1717
    18 namespace flair
    19 {
    20 namespace gui
    21 {
    22     class LayoutPosition;
     18namespace flair {
     19namespace gui {
     20class LayoutPosition;
    2321
    24     /*! \class GroupBox
    25     *
    26     * \brief Class displaying a QGroupBox on the ground station
    27     *
    28     */
    29     class GroupBox: public Layout
    30     {
    31         public:
    32             /*!
    33             * \brief Constructor
    34             *
    35             * Construct a QGroupBox at given position. \n
    36             * The GroupBox will automatically be child of position->getLayout() Layout. After calling this constructor,
    37             * position will be deleted as it is no longer usefull.
    38             *
    39             * \param position position
    40             * \param name name
    41             */
    42             GroupBox(const LayoutPosition* position,std::string name);
     22/*! \class GroupBox
     23*
     24* \brief Class displaying a QGroupBox on the ground station
     25*
     26*/
     27class GroupBox : public Layout {
     28public:
     29  /*!
     30  * \brief Constructor
     31  *
     32  * Construct a QGroupBox at given position. \n
     33  * The GroupBox will automatically be child of position->getLayout() Layout.
     34  *After calling this constructor,
     35  * position will be deleted as it is no longer usefull.
     36  *
     37  * \param position position
     38  * \param name name
     39  */
     40  GroupBox(const LayoutPosition *position, std::string name);
    4341
    44             /*!
    45             * \brief Destructor
    46             *
    47             */
    48             ~GroupBox();
     42  /*!
     43  * \brief Destructor
     44  *
     45  */
     46  ~GroupBox();
    4947
    50         private:
    51     };
     48private:
     49};
    5250
    5351} // end namespace gui
  • trunk/include/FlairCore/I2cPort.h

    r2 r13  
    1717#include <stdint.h>
    1818
    19 namespace flair
    20 {
    21 namespace core
    22 {
    23     /*! \class I2cPort
    24     *
    25     * \brief Base class for i2c port
    26     *
    27     * This class has a Mutex which must be used to protect access to the port in case
    28     * that more than one Thread is using it. Lock the Mutex before any communication (including SetSlave)
    29     * and release it after communication.
    30     */
    31     class I2cPort: public Mutex
    32     {
    33         public:
    34             /*!
    35             * \brief Constructor
    36             *
    37             * Construct an i2c port.
    38             *
    39             * \param parent parent
    40             * \param name name
    41             */
    42             I2cPort(const Object* parent,std::string name): Mutex(parent,name)
    43             {}
     19namespace flair {
     20namespace core {
     21/*! \class I2cPort
     22*
     23* \brief Base class for i2c port
     24*
     25* This class has a Mutex which must be used to protect access to the port in
     26*case
     27* that more than one Thread is using it. Lock the Mutex before any communication
     28*(including SetSlave)
     29* and release it after communication.
     30*/
     31class I2cPort : public Mutex {
     32public:
     33  /*!
     34  * \brief Constructor
     35  *
     36  * Construct an i2c port.
     37  *
     38  * \param parent parent
     39  * \param name name
     40  */
     41  I2cPort(const Object *parent, std::string name) : Mutex(parent, name) {}
    4442
    45             /*!
    46             * \brief Destructor
    47             *
    48             */
    49             ~I2cPort(){};
     43  /*!
     44  * \brief Destructor
     45  *
     46  */
     47  ~I2cPort(){};
    5048
    51             /*!
    52             * \brief Set slave's address
    53             *
    54             * This function need to be called before any communication.
    55             *
    56             * \param address slave's address
    57             */
    58             virtual int SetSlave(uint16_t address)=0;
     49  /*!
     50  * \brief Set slave's address
     51  *
     52  * This function need to be called before any communication.
     53  *
     54  * \param address slave's address
     55  */
     56  virtual int SetSlave(uint16_t address) = 0;
    5957
    60             /*!
    61             * \brief Write datas
    62             *
    63             * \param buf pointer to datas
    64             * \param nbyte length of datas
    65             *
    66             * \return amount of written datas
    67             */
    68             virtual ssize_t Write(const void *buf,size_t nbyte)=0;
     58  /*!
     59  * \brief Write datas
     60  *
     61  * \param buf pointer to datas
     62  * \param nbyte length of datas
     63  *
     64  * \return amount of written datas
     65  */
     66  virtual ssize_t Write(const void *buf, size_t nbyte) = 0;
    6967
    70             /*!
    71             * \brief Read datas
    72             *
    73             * \param buf pointer to datas
    74             * \param nbyte length of datas
    75             *
    76             * \return amount of read datas
    77             */
    78             virtual ssize_t Read(void *buf,size_t nbyte)=0;
     68  /*!
     69  * \brief Read datas
     70  *
     71  * \param buf pointer to datas
     72  * \param nbyte length of datas
     73  *
     74  * \return amount of read datas
     75  */
     76  virtual ssize_t Read(void *buf, size_t nbyte) = 0;
    7977
    80             /*!
    81             * \brief Set RX timeout
    82             *
    83             * Timeout for waiting an ACK from the slave.
    84             *
    85             * \param timeout_ns timeout in nano second
    86             */
    87             virtual void SetRxTimeout(Time timeout_ns)=0;
     78  /*!
     79  * \brief Set RX timeout
     80  *
     81  * Timeout for waiting an ACK from the slave.
     82  *
     83  * \param timeout_ns timeout in nano second
     84  */
     85  virtual void SetRxTimeout(Time timeout_ns) = 0;
    8886
    89             /*!
    90             * \brief Set TX timeout
    91             *
    92             * Timeout for waiting an ACK from the slave.
    93             *
    94             * \param timeout_ns timeout in nano second
    95             */
    96             virtual void SetTxTimeout(Time timeout_ns)=0;
    97 
    98     };
     87  /*!
     88  * \brief Set TX timeout
     89  *
     90  * Timeout for waiting an ACK from the slave.
     91  *
     92  * \param timeout_ns timeout in nano second
     93  */
     94  virtual void SetTxTimeout(Time timeout_ns) = 0;
     95};
    9996} // end namespace core
    10097} // end namespace framework
  • trunk/include/FlairCore/IODataElement.h

    r2 r13  
    1616#include "io_data.h"
    1717
    18 namespace flair { namespace core {
     18namespace flair {
     19namespace core {
    1920
    20     class DataType;
     21class DataType;
    2122
    22     /*! \class IODataElement
    23     *
    24     * \brief Abstract class for accessing an element of an io_data.
    25     */
    26     class IODataElement: public Object
    27     {
    28         public:
    29             /*!
    30             * \brief Constructor
    31             *
    32             * Construct an IODataElement. \n
    33             *
    34             */
    35             IODataElement(const io_data* parent,std::string name): Object(parent,name)
    36             {
    37                 this->parent=parent;
    38             }
    39             size_t Size() const
    40             {
    41                 return size;
    42             }
     23/*! \class IODataElement
     24*
     25* \brief Abstract class for accessing an element of an io_data.
     26*/
     27class IODataElement : public Object {
     28public:
     29  /*!
     30  * \brief Constructor
     31  *
     32  * Construct an IODataElement. \n
     33  *
     34  */
     35  IODataElement(const io_data *parent, std::string name)
     36      : Object(parent, name) {
     37    this->parent = parent;
     38  }
     39  size_t Size() const { return size; }
    4340
    44             virtual void CopyData(char* dst) const=0;
     41  virtual void CopyData(char *dst) const = 0;
    4542
    46             /*!
    47             * \brief DataType
    48             *
    49             * \return type of data
    50             */
    51             virtual DataType const &GetDataType(void) const=0;
     43  /*!
     44  * \brief DataType
     45  *
     46  * \return type of data
     47  */
     48  virtual DataType const &GetDataType(void) const = 0;
    5249
    53         protected:
    54             size_t size;
     50protected:
     51  size_t size;
    5552
    56         private:
    57             const io_data* parent;
    58 
    59     };
     53private:
     54  const io_data *parent;
     55};
    6056
    6157} // end namespace core
  • trunk/include/FlairCore/IODevice.h

    r2 r13  
    2020class FrameworkManager_impl;
    2121
    22 namespace flair { namespace core {
     22namespace flair {
     23namespace core {
    2324
    24     class io_data;
    25     class DataType;
     25class io_data;
     26class DataType;
    2627
    27     /*! \class IODevice
    28     *
    29     * \brief Abstract class for input/ouput system
    30     *
    31     * An input/output system is generally used to describe a sensor, an actuator or a filter. \n
    32     * These systems can be linked (for exemple a sensor with a filter), when an IODevice
    33     * is created with a parent of type IODevice.
    34     * In this case, an update of the parent's data will call an update
    35     * of the child's data (for exemple when a sensor gets new datas, a filter is automatically called). \n
    36     * Output of this object can also be sent to a shared memory using the OutputToShMem method; in order to use it with an
    37     * external program.
    38     */
    39     class IODevice: public Object {
    40         friend class ::IODevice_impl;
    41         friend class ::Thread_impl;
    42         friend class ::FrameworkManager_impl;
     28/*! \class IODevice
     29*
     30* \brief Abstract class for input/ouput system
     31*
     32* An input/output system is generally used to describe a sensor, an actuator or
     33*a filter. \n
     34* These systems can be linked (for exemple a sensor with a filter), when an
     35*IODevice
     36* is created with a parent of type IODevice.
     37* In this case, an update of the parent's data will call an update
     38* of the child's data (for exemple when a sensor gets new datas, a filter is
     39*automatically called). \n
     40* Output of this object can also be sent to a shared memory using the
     41*OutputToShMem method; in order to use it with an
     42* external program.
     43*/
     44class IODevice : public Object {
     45  friend class ::IODevice_impl;
     46  friend class ::Thread_impl;
     47  friend class ::FrameworkManager_impl;
    4348
    44         public:
    45             /*!
    46             * \brief Constructor
    47             *
    48             * Construct an IODevice of Object's type "IODevice" (see Object::ObjectType). \n
    49             * If parent's Object::ObjectType is also "IODevice", this IODevice will be linked to its parent
    50             * (see ProcessUpdate()).
    51             *
    52             * \param parent parent
    53             * \param name name
    54             */
    55             IODevice(const Object* parent,std::string name);
     49public:
     50  /*!
     51  * \brief Constructor
     52  *
     53  * Construct an IODevice of Object's type "IODevice" (see Object::ObjectType).
     54  *\n
     55  * If parent's Object::ObjectType is also "IODevice", this IODevice will be
     56  *linked to its parent
     57  * (see ProcessUpdate()).
     58  *
     59  * \param parent parent
     60  * \param name name
     61  */
     62  IODevice(const Object *parent, std::string name);
    5663
    57             /*!
    58             * \brief Destructor
    59             *
    60             */
    61             virtual ~IODevice();
     64  /*!
     65  * \brief Destructor
     66  *
     67  */
     68  virtual ~IODevice();
    6269
    63             /*!
    64             * \brief Add an IODevice to the logs
    65             *
    66             * The IODevice will be automatically logged among this IODevice logs,
    67             * if logging is enabled (see SetDataToLog(), FrameworkManager::StartLog
    68             * and FrameworkManager::AddDeviceToLog). \n
    69             * Logging happens when ProcessUpdate() is called. \n
    70             * Note that when an IODevice is just added for logs (ie. no parent/child
    71             * link between the two IODevice),
    72             * UpdateFrom() is not automatically called.
    73             *
    74             * \param device IODevice to log
    75             */
    76             void AddDeviceToLog(const IODevice* device);
     70  /*!
     71  * \brief Add an IODevice to the logs
     72  *
     73  * The IODevice will be automatically logged among this IODevice logs,
     74  * if logging is enabled (see SetDataToLog(), FrameworkManager::StartLog
     75  * and FrameworkManager::AddDeviceToLog). \n
     76  * Logging happens when ProcessUpdate() is called. \n
     77  * Note that when an IODevice is just added for logs (ie. no parent/child
     78  * link between the two IODevice),
     79  * UpdateFrom() is not automatically called.
     80  *
     81  * \param device IODevice to log
     82  */
     83  void AddDeviceToLog(const IODevice *device);
    7784
    78             /*!
    79             * \brief Add an io_data to the log
    80             *
    81             * The io_data will be automatically logged if enabled (see FrameworkManager::StartLog
    82             * and FrameworkManager::AddDeviceToLog),
    83             * during call to ProcessUpdate().
    84             *
    85             * \param data data to log
    86             */
    87             void AddDataToLog(const io_data* data);
     85  /*!
     86  * \brief Add an io_data to the log
     87  *
     88  * The io_data will be automatically logged if enabled (see
     89  *FrameworkManager::StartLog
     90  * and FrameworkManager::AddDeviceToLog),
     91  * during call to ProcessUpdate().
     92  *
     93  * \param data data to log
     94  */
     95  void AddDataToLog(const io_data *data);
    8896
    89             /*!
    90             * \brief Send the output to a shared memory
    91             *
    92             * Use this method to output log datas to a shared memory.
    93             * This can be usefull to get datas from an external progam. \n
    94             * Output happens when ProcessUpdate() is called. \n
    95             * The name and the structure of the shared memory will be displayed when
    96             * this method is called with true as argument. \n
    97             * By default it is not enabled.
    98             *
    99             *
    100             * \param enabled true to enable the output, false otherwise
    101             */
    102             void OutputToShMem(bool enabled);
     97  /*!
     98  * \brief Send the output to a shared memory
     99  *
     100  * Use this method to output log datas to a shared memory.
     101  * This can be usefull to get datas from an external progam. \n
     102  * Output happens when ProcessUpdate() is called. \n
     103  * The name and the structure of the shared memory will be displayed when
     104  * this method is called with true as argument. \n
     105  * By default it is not enabled.
     106  *
     107  *
     108  * \param enabled true to enable the output, false otherwise
     109  */
     110  void OutputToShMem(bool enabled);
    103111
    104             //TODO: these 2 method should be pure virtual
    105             virtual DataType const &GetInputDataType() const;
    106             virtual DataType const &GetOutputDataType() const;
     112  // TODO: these 2 method should be pure virtual
     113  virtual DataType const &GetInputDataType() const;
     114  virtual DataType const &GetOutputDataType() const;
    107115
    108         protected:
    109             /*!
    110             * \brief Process the childs of type IODevice, and log if needed
    111             *
    112             * This method must be called after computing datas;
    113             * generally at the end of the reimplemented UpdateFrom or after acquiring datas in case of a sensor. \n
    114             * It will call UpdateFrom methods of each child of type IODevice,
    115             * and log all datas (this IODevice and its childs)
    116             * if logging is enabled (see SetDataToLog(), AddDeviceToLog(),
    117             * FrameworkManager::StartLog and FrameworkManager::AddDeviceToLog). \n
    118             * If a thread is waiting on this IODevice (see Thread::WaitUpdate), it will be resumed.
    119             *
    120             * \param data data to process
    121             */
    122             void ProcessUpdate(io_data* data);
     116protected:
     117  /*!
     118  * \brief Process the childs of type IODevice, and log if needed
     119  *
     120  * This method must be called after computing datas;
     121  * generally at the end of the reimplemented UpdateFrom or after acquiring
     122  *datas in case of a sensor. \n
     123  * It will call UpdateFrom methods of each child of type IODevice,
     124  * and log all datas (this IODevice and its childs)
     125  * if logging is enabled (see SetDataToLog(), AddDeviceToLog(),
     126  * FrameworkManager::StartLog and FrameworkManager::AddDeviceToLog). \n
     127  * If a thread is waiting on this IODevice (see Thread::WaitUpdate), it will be
     128  *resumed.
     129  *
     130  * \param data data to process
     131  */
     132  void ProcessUpdate(io_data *data);
    123133
    124         private:
    125             /*!
    126             * \brief Update using provided datas
    127             *
    128             * This method is automatically called by ProcessUpdate()
    129             * of the Object::Parent's if its Object::ObjectType is "IODevice". \n
    130             * This method must be reimplemented, in order to process the data from the parent.
    131             *
    132             * \param data data from the parent to process
    133             */
    134             virtual void UpdateFrom(const io_data *data)=0;
     134private:
     135  /*!
     136  * \brief Update using provided datas
     137  *
     138  * This method is automatically called by ProcessUpdate()
     139  * of the Object::Parent's if its Object::ObjectType is "IODevice". \n
     140  * This method must be reimplemented, in order to process the data from the
     141  *parent.
     142  *
     143  * \param data data from the parent to process
     144  */
     145  virtual void UpdateFrom(const io_data *data) = 0;
    135146
    136             class IODevice_impl* pimpl_;
    137     };
     147  class IODevice_impl *pimpl_;
     148};
    138149
    139150} // end namespace core
  • trunk/include/FlairCore/ImuData.h

    r2 r13  
    1717#include <Vector3D.h>
    1818
    19 namespace flair { namespace core {
    20 
    21     /*! \class ImuData
    22     *
    23     * \brief Class defining IMU datas
    24     *
    25     * IMU (inertial measurement unit) datas consist of raw accelerometer values, raw gyrometer values
    26     * and raw magnetometer values.
    27     *
    28     */
    29     class ImuData: public io_data {
    30         public:
    31             class Type: public DataType {
    32             public:
    33                 Type(ScalarType const &_elementDataType):
    34                     elementDataType(_elementDataType){}
    35                 ScalarType const &GetElementDataType() const {return elementDataType;}
    36                 std::string GetDescription() const {return "imu data";}
    37                 size_t GetSize() const {
    38                     size_t size=0;
    39                     size+=3*elementDataType.GetSize();//RawAcc
    40                     size+=3*elementDataType.GetSize();//RawGyr
    41                     size+=3*elementDataType.GetSize();//RawMag
    42                     return size;
    43                 }
    44             private:
    45                 ScalarType const &elementDataType;
    46             };
    47 
    48             /*!
    49             \enum PlotableData_t
    50             \brief Datas wich can be plotted in a DataPlot1D
    51             */
    52             typedef enum {
    53                 RawAx/*! x raw accelerometer */, RawAy/*! y raw accelerometer */ ,RawAz/*! z raw accelerometer */,
    54                 RawGx/*! x raw gyrometer */,RawGy/*! y raw gyrometer */,RawGz/*! z raw gyrometer */,
    55                 RawGxDeg/*! x raw gyrometer degree */,RawGyDeg/*! y raw gyrometer degree */,RawGzDeg/*! z raw gyrometer degree */,
    56                 RawMx/*! x raw magnetometer */,RawMy/*! y raw magnetometer */,RawMz/*! z raw magnetometer */
    57                 } PlotableData_t;
    58 
    59             /*!
    60             * \brief Constructor
    61             *
    62             * Construct an io_data representing IMU datas. \n
    63             *
    64             * \param parent parent
    65             * \param name name
    66             * \param n number of samples
    67             */
    68             ImuData(const Object* parent,std::string name="",int n=1);
    69 
    70             /*!
    71             * \brief Destructor
    72             *
    73             */
    74             ~ImuData();
    75 
    76             /*!
    77             * \brief Element
    78             *
    79             * Get a pointer to a specific element. This pointer can be used for plotting.
    80             *
    81             * \param data_type data type
    82             *
    83             * \return pointer to the element
    84             */
    85             IODataElement* Element(PlotableData_t data_type) const;
    86 
    87             /*!
    88             * \brief Get raw accelerations
    89             *
    90             * This method is mutex protected.
    91             *
    92             * \return raw accelerations
    93             *
    94             */
    95             Vector3D GetRawAcc(void) const;
    96 
    97             /*!
    98             * \brief Get raw magnetometers
    99             *
    100             * This method is mutex protected.
    101             *
    102             * \return raw magnetometers
    103             *
    104             */
    105             Vector3D GetRawMag(void) const;
    106 
    107             /*!
    108             * \brief Get raw angular speed
    109             *
    110             * This method is mutex protected.
    111             *
    112             * \return raw angular speed
    113             *
    114             */
    115             Vector3D GetRawGyr(void) const;
    116 
    117             /*!
    118             * \brief Get raw accelerations, magnetometers and angular speeds
    119             *
    120             * This method is mutex protected.
    121             *
    122             * \param rawAcc raw accelerations
    123             * \param rawMag raw magnetometers
    124             * \param rawGyr raw angular speeds
    125             *
    126             */
    127             void GetRawAccMagAndGyr(Vector3D &rawAcc,Vector3D &rawMag,Vector3D &rawGyr) const;
    128 
    129             /*!
    130             * \brief Set raw accelerations
    131             *
    132             * This method is mutex protected.
    133             *
    134             * \param raw accelerations
    135             *
    136             */
    137             void SetRawAcc(const Vector3D &rawAcc);
    138 
    139             /*!
    140             * \brief Set raw magnetometers
    141             *
    142             * This method is mutex protected.
    143             *
    144             * \param raw magnetometers
    145             *
    146             */
    147             void SetRawMag(const Vector3D &rawMag);
    148 
    149             /*!
    150             * \brief Set raw angular speed
    151             *
    152             * This method is mutex protected.
    153             *
    154             * \param raw angular speed
    155             *
    156             */
    157             void SetRawGyr(const Vector3D &rawGyr);
    158 
    159             /*!
    160             * \brief Set raw accelerations, magnetometers and angular speeds
    161             *
    162             * This method is mutex protected.
    163             *
    164             * \param rawAcc raw accelerations
    165             * \param rawMag raw magnetometers
    166             * \param rawGyr raw angular speeds
    167             *
    168             */
    169             void SetRawAccMagAndGyr(const Vector3D &rawAcc,const Vector3D &rawMag,const Vector3D &rawGyr);
    170 
    171             Type const&GetDataType() const {return dataType;}
    172         private:
    173             /*!
    174             * \brief Copy datas
    175             *
    176             * Reimplemented from io_data. \n
    177             * See io_data::CopyDatas.
    178             *
    179             * \param dst destination buffer
    180             */
    181             void CopyDatas(char* dst) const;
    182 
    183             /*!
    184             * \brief Raw accelerometer
    185             *
    186             */
    187             Vector3D rawAcc;
    188 
    189             /*!
    190             * \brief Raw gyrometer
    191             *
    192             */
    193             Vector3D rawGyr;
    194 
    195             /*!
    196             * \brief Raw magnetometer
    197             *
    198             */
    199             Vector3D rawMag;
    200 
    201             void Queue(char** dst,const void *src,size_t size) const;
    202             Type dataType;
    203 
    204     };
     19namespace flair {
     20namespace core {
     21
     22/*! \class ImuData
     23*
     24* \brief Class defining IMU datas
     25*
     26* IMU (inertial measurement unit) datas consist of raw accelerometer values, raw
     27*gyrometer values
     28* and raw magnetometer values.
     29*
     30*/
     31class ImuData : public io_data {
     32public:
     33  class Type : public DataType {
     34  public:
     35    Type(ScalarType const &_elementDataType)
     36        : elementDataType(_elementDataType) {}
     37    ScalarType const &GetElementDataType() const { return elementDataType; }
     38    std::string GetDescription() const { return "imu data"; }
     39    size_t GetSize() const {
     40      size_t size = 0;
     41      size += 3 * elementDataType.GetSize(); // RawAcc
     42      size += 3 * elementDataType.GetSize(); // RawGyr
     43      size += 3 * elementDataType.GetSize(); // RawMag
     44      return size;
     45    }
     46
     47  private:
     48    ScalarType const &elementDataType;
     49  };
     50
     51  /*!
     52  \enum PlotableData_t
     53  \brief Datas wich can be plotted in a DataPlot1D
     54  */
     55  typedef enum {
     56    RawAx /*! x raw accelerometer */,
     57    RawAy /*! y raw accelerometer */,
     58    RawAz /*! z raw accelerometer */,
     59    RawGx /*! x raw gyrometer */,
     60    RawGy /*! y raw gyrometer */,
     61    RawGz /*! z raw gyrometer */,
     62    RawGxDeg /*! x raw gyrometer degree */,
     63    RawGyDeg /*! y raw gyrometer degree */,
     64    RawGzDeg /*! z raw gyrometer degree */,
     65    RawMx /*! x raw magnetometer */,
     66    RawMy /*! y raw magnetometer */,
     67    RawMz /*! z raw magnetometer */
     68  } PlotableData_t;
     69
     70  /*!
     71  * \brief Constructor
     72  *
     73  * Construct an io_data representing IMU datas. \n
     74  *
     75  * \param parent parent
     76  * \param name name
     77  * \param n number of samples
     78  */
     79  ImuData(const Object *parent, std::string name = "", int n = 1);
     80
     81  /*!
     82  * \brief Destructor
     83  *
     84  */
     85  ~ImuData();
     86
     87  /*!
     88  * \brief Element
     89  *
     90  * Get a pointer to a specific element. This pointer can be used for plotting.
     91  *
     92  * \param data_type data type
     93  *
     94  * \return pointer to the element
     95  */
     96  IODataElement *Element(PlotableData_t data_type) const;
     97
     98  /*!
     99  * \brief Get raw accelerations
     100  *
     101  * This method is mutex protected.
     102  *
     103  * \return raw accelerations
     104  *
     105  */
     106  Vector3D GetRawAcc(void) const;
     107
     108  /*!
     109  * \brief Get raw magnetometers
     110  *
     111  * This method is mutex protected.
     112  *
     113  * \return raw magnetometers
     114  *
     115  */
     116  Vector3D GetRawMag(void) const;
     117
     118  /*!
     119  * \brief Get raw angular speed
     120  *
     121  * This method is mutex protected.
     122  *
     123  * \return raw angular speed
     124  *
     125  */
     126  Vector3D GetRawGyr(void) const;
     127
     128  /*!
     129  * \brief Get raw accelerations, magnetometers and angular speeds
     130  *
     131  * This method is mutex protected.
     132  *
     133  * \param rawAcc raw accelerations
     134  * \param rawMag raw magnetometers
     135  * \param rawGyr raw angular speeds
     136  *
     137  */
     138  void GetRawAccMagAndGyr(Vector3D &rawAcc, Vector3D &rawMag,
     139                          Vector3D &rawGyr) const;
     140
     141  /*!
     142  * \brief Set raw accelerations
     143  *
     144  * This method is mutex protected.
     145  *
     146  * \param raw accelerations
     147  *
     148  */
     149  void SetRawAcc(const Vector3D &rawAcc);
     150
     151  /*!
     152  * \brief Set raw magnetometers
     153  *
     154  * This method is mutex protected.
     155  *
     156  * \param raw magnetometers
     157  *
     158  */
     159  void SetRawMag(const Vector3D &rawMag);
     160
     161  /*!
     162  * \brief Set raw angular speed
     163  *
     164  * This method is mutex protected.
     165  *
     166  * \param raw angular speed
     167  *
     168  */
     169  void SetRawGyr(const Vector3D &rawGyr);
     170
     171  /*!
     172  * \brief Set raw accelerations, magnetometers and angular speeds
     173  *
     174  * This method is mutex protected.
     175  *
     176  * \param rawAcc raw accelerations
     177  * \param rawMag raw magnetometers
     178  * \param rawGyr raw angular speeds
     179  *
     180  */
     181  void SetRawAccMagAndGyr(const Vector3D &rawAcc, const Vector3D &rawMag,
     182                          const Vector3D &rawGyr);
     183
     184  Type const &GetDataType() const { return dataType; }
     185
     186private:
     187  /*!
     188  * \brief Copy datas
     189  *
     190  * Reimplemented from io_data. \n
     191  * See io_data::CopyDatas.
     192  *
     193  * \param dst destination buffer
     194  */
     195  void CopyDatas(char *dst) const;
     196
     197  /*!
     198  * \brief Raw accelerometer
     199  *
     200  */
     201  Vector3D rawAcc;
     202
     203  /*!
     204  * \brief Raw gyrometer
     205  *
     206  */
     207  Vector3D rawGyr;
     208
     209  /*!
     210  * \brief Raw magnetometer
     211  *
     212  */
     213  Vector3D rawMag;
     214
     215  void Queue(char **dst, const void *src, size_t size) const;
     216  Type dataType;
     217};
    205218
    206219} // end namespace core
  • trunk/include/FlairCore/Label.h

    r2 r13  
    1616#include <Widget.h>
    1717
    18 namespace flair
    19 {
    20 namespace gui
    21 {
     18namespace flair {
     19namespace gui {
    2220
    23     class LayoutPosition;
     21class LayoutPosition;
    2422
    25     /*! \class Label
    26     *
    27     * \brief Class displaying a QLabel on the ground station
    28     *
    29     */
    30     class Label:public Widget
    31     {
    32         public:
    33             /*!
    34             * \brief Constructor
    35             *
    36             * Construct a QLabel at given position. \n
    37             * The Label will automatically be child of position->getLayout() Layout. After calling this constructor,
    38             * position will be deleted as it is no longer usefull.
    39             *
    40             * \param parent parent
    41             * \param name name
    42             * \param buf_size size of the text buffer
    43             */
    44             Label(const LayoutPosition* position,std::string name,size_t buf_size=255);
     23/*! \class Label
     24*
     25* \brief Class displaying a QLabel on the ground station
     26*
     27*/
     28class Label : public Widget {
     29public:
     30  /*!
     31  * \brief Constructor
     32  *
     33  * Construct a QLabel at given position. \n
     34  * The Label will automatically be child of position->getLayout() Layout. After
     35  *calling this constructor,
     36  * position will be deleted as it is no longer usefull.
     37  *
     38  * \param parent parent
     39  * \param name name
     40  * \param buf_size size of the text buffer
     41  */
     42  Label(const LayoutPosition *position, std::string name,
     43        size_t buf_size = 255);
    4544
    46             /*!
    47             * \brief Destructor
    48             *
    49             */
    50             ~Label();
     45  /*!
     46  * \brief Destructor
     47  *
     48  */
     49  ~Label();
    5150
    52             /*!
    53             * \brief Set text
    54             *
    55             * \param format text string to display, see standard printf
    56             */
    57             void SetText(const char * format, ...);
     51  /*!
     52  * \brief Set text
     53  *
     54  * \param format text string to display, see standard printf
     55  */
     56  void SetText(const char *format, ...);
    5857
    59         private:
    60             char* printf_buffer;
    61     };
     58private:
     59  char *printf_buffer;
     60};
    6261
    6362} // end namespace gui
  • trunk/include/FlairCore/Layout.h

    r2 r13  
    1717#include <Mutex.h>
    1818
    19 namespace flair
    20 {
    21 namespace gui
    22 {
    23     class LayoutPosition;
     19namespace flair {
     20namespace gui {
     21class LayoutPosition;
    2422
    25     /*! \class Layout
    26     *
    27     * \brief Abstract class to display a layout on the ground station
    28     *
    29     * This is an abstract class to display layouts (like GridLayout, GroupBox, etc). \n
    30     * A layout can contains Widgets (Box, DataPlot, Picture, etc). \n
    31     * Layout holds a Mutex, which can be used to protect access to Box's value for example.
    32     */
    33     class Layout: public Widget
    34     {
    35         friend class Box;
     23/*! \class Layout
     24*
     25* \brief Abstract class to display a layout on the ground station
     26*
     27* This is an abstract class to display layouts (like GridLayout, GroupBox, etc).
     28*\n
     29* A layout can contains Widgets (Box, DataPlot, Picture, etc). \n
     30* Layout holds a Mutex, which can be used to protect access to Box's value for
     31*example.
     32*/
     33class Layout : public Widget {
     34  friend class Box;
    3635
    37         public:
    38             /*!
    39             * \brief Constructor
    40             *
    41             * Construct a Layout. Type is a predifined one, and will be
    42             * interpreted by the ground station.
    43             *
    44             * \param parent parent
    45             * \param name name
    46             * \param type type of layout
    47             */
    48             Layout(const Widget* parent,std::string name,std::string type);
     36public:
     37  /*!
     38  * \brief Constructor
     39  *
     40  * Construct a Layout. Type is a predifined one, and will be
     41  * interpreted by the ground station.
     42  *
     43  * \param parent parent
     44  * \param name name
     45  * \param type type of layout
     46  */
     47  Layout(const Widget *parent, std::string name, std::string type);
    4948
    50             /*!
    51             * \brief Destructor
    52             *
    53             */
    54             ~Layout();
     49  /*!
     50  * \brief Destructor
     51  *
     52  */
     53  ~Layout();
    5554
    56             /*!
    57             * \brief Last Row and Col LayoutPosition
    58             *
    59             * Get a LayoutPosition at the last row and col.
    60             *
    61             * \return the LayoutPosition
    62             */
    63             LayoutPosition* LastRowLastCol(void) const;
     55  /*!
     56  * \brief Last Row and Col LayoutPosition
     57  *
     58  * Get a LayoutPosition at the last row and col.
     59  *
     60  * \return the LayoutPosition
     61  */
     62  LayoutPosition *LastRowLastCol(void) const;
    6463
    65             /*!
    66             * \brief New Row LayoutPosition
    67             *
    68             * Get a LayoutPosition at a new row and first col. This new row will be at the last position.
    69             *
    70             * \return the LayoutPosition
    71             */
    72             LayoutPosition*  NewRow(void) const;
     64  /*!
     65  * \brief New Row LayoutPosition
     66  *
     67  * Get a LayoutPosition at a new row and first col. This new row will be at the
     68  *last position.
     69  *
     70  * \return the LayoutPosition
     71  */
     72  LayoutPosition *NewRow(void) const;
    7373
    74             /*!
    75             * \brief LayoutPosition at specified position
    76             *
    77             * Get a LayoutPosition at specified row and col.
    78             *
    79             * \param row row
    80             * \param col col
    81             *
    82             * \return the LayoutPosition
    83             */
    84             LayoutPosition*  At(uint16_t row,uint16_t col) const;
     74  /*!
     75  * \brief LayoutPosition at specified position
     76  *
     77  * Get a LayoutPosition at specified row and col.
     78  *
     79  * \param row row
     80  * \param col col
     81  *
     82  * \return the LayoutPosition
     83  */
     84  LayoutPosition *At(uint16_t row, uint16_t col) const;
    8585
    86         private:
    87             /*!
    88             * \brief Mutex
    89             *
    90             * This Mutex can be used by friends class like Box to protect access
    91             * to Box's value.
    92             */
    93             core::Mutex* mutex;
    94     };
     86private:
     87  /*!
     88  * \brief Mutex
     89  *
     90  * This Mutex can be used by friends class like Box to protect access
     91  * to Box's value.
     92  */
     93  core::Mutex *mutex;
     94};
    9595
    9696} // end namespace gui
  • trunk/include/FlairCore/LayoutPosition.h

    r2 r13  
    1616#include <stdint.h>
    1717
    18 namespace flair
    19 {
    20 namespace gui
    21 {
    22     class Layout;
     18namespace flair {
     19namespace gui {
     20class Layout;
    2321
    24     /*! \class LayoutPosition
    25     *
    26     * \brief Class to define a position in a layout on the ground station.
    27     *
     22/*! \class LayoutPosition
     23*
     24* \brief Class to define a position in a layout on the ground station.
     25*
    2826
    29     */
    30     class LayoutPosition
    31     {
    32         public:
    33             /*!
    34             * \brief Constructor
    35             *
    36             * Construct a LayoutPosition, in given Layout at given place.
    37             *
    38             * \param layout layout
    39             * \param row row position
    40             * \param col col position
    41             */
    42             LayoutPosition(const Layout* layout,int16_t row,int16_t col);
     27*/
     28class LayoutPosition {
     29public:
     30  /*!
     31  * \brief Constructor
     32  *
     33  * Construct a LayoutPosition, in given Layout at given place.
     34  *
     35  * \param layout layout
     36  * \param row row position
     37  * \param col col position
     38  */
     39  LayoutPosition(const Layout *layout, int16_t row, int16_t col);
    4340
    44             /*!
    45             * \brief Destructor
    46             *
    47             */
    48             ~LayoutPosition();
     41  /*!
     42  * \brief Destructor
     43  *
     44  */
     45  ~LayoutPosition();
    4946
    50             /*!
    51             * \brief get Layout
    52             *
    53             * \return the parent Layout
    54             */
    55             const Layout* getLayout(void) const;
     47  /*!
     48  * \brief get Layout
     49  *
     50  * \return the parent Layout
     51  */
     52  const Layout *getLayout(void) const;
    5653
    57             /*!
    58             * \brief get row
    59             *
    60             * \return row position
    61             */
    62             int16_t Row(void) const;
     54  /*!
     55  * \brief get row
     56  *
     57  * \return row position
     58  */
     59  int16_t Row(void) const;
    6360
    64             /*!
    65             * \brief get col
    66             *
    67             * \return col position
    68             */
    69             int16_t Col(void) const;
     61  /*!
     62  * \brief get col
     63  *
     64  * \return col position
     65  */
     66  int16_t Col(void) const;
    7067
    71 
    72         private:
    73             const Layout *layout;
    74             int16_t row,col;
    75 
    76     };
     68private:
     69  const Layout *layout;
     70  int16_t row, col;
     71};
    7772
    7873} // end namespace gui
  • trunk/include/FlairCore/Map.h

    r2 r13  
    1717#include <stdint.h>
    1818
    19 namespace flair
    20 {
    21 namespace core
    22 {
    23     class GeoCoordinate;
     19namespace flair {
     20namespace core {
     21class GeoCoordinate;
    2422}
    2523
    26 namespace gui
    27 {
     24namespace gui {
    2825
    29     class LayoutPosition;
     26class LayoutPosition;
    3027
    31     /*! \class Map
    32     *
    33     * \brief Class displaying a GPS map on the ground station
    34     *
    35     */
    36     class Map: public SendData
    37     {
    38         public:
    39             /*!
    40             * \brief Constructor
    41             *
    42             * Construct a map at given position. \n
    43             * The Map will automatically be child of position->getLayout() Layout. After calling this constructor,
    44             * position will be deleted as it is no longer usefull.
    45             *
    46             * \param position position to draw map
    47             * \param name name
    48             */
    49             Map(const LayoutPosition* position,std::string name);
     28/*! \class Map
     29*
     30* \brief Class displaying a GPS map on the ground station
     31*
     32*/
     33class Map : public SendData {
     34public:
     35  /*!
     36  * \brief Constructor
     37  *
     38  * Construct a map at given position. \n
     39  * The Map will automatically be child of position->getLayout() Layout. After
     40  *calling this constructor,
     41  * position will be deleted as it is no longer usefull.
     42  *
     43  * \param position position to draw map
     44  * \param name name
     45  */
     46  Map(const LayoutPosition *position, std::string name);
    5047
    51             /*!
    52             * \brief Destructor
    53             *
    54             */
    55             ~Map();
     48  /*!
     49  * \brief Destructor
     50  *
     51  */
     52  ~Map();
    5653
    57             /*!
    58             * \brief Add a point to the map
    59             *
    60             * \param point point to draw
    61             * \param name name
    62             */
    63             void AddPoint(const core::GeoCoordinate* point,std::string name="");
     54  /*!
     55  * \brief Add a point to the map
     56  *
     57  * \param point point to draw
     58  * \param name name
     59  */
     60  void AddPoint(const core::GeoCoordinate *point, std::string name = "");
    6461
    65             /*!
    66             * \brief Copy datas to specified buffer
    67             *
    68             * Reimplemented from SendData.
    69             *
    70             * \param buf output buffer
    71             */
    72             void CopyDatas(char* buf) const;
     62  /*!
     63  * \brief Copy datas to specified buffer
     64  *
     65  * Reimplemented from SendData.
     66  *
     67  * \param buf output buffer
     68  */
     69  void CopyDatas(char *buf) const;
    7370
    74         private:
    75             /*!
    76             * \brief Extra Xml event
    77             *
    78             * Reimplemented from SendData.
    79             */
    80             void ExtraXmlEvent(void);
     71private:
     72  /*!
     73  * \brief Extra Xml event
     74  *
     75  * Reimplemented from SendData.
     76  */
     77  void ExtraXmlEvent(void);
    8178
    82             std::vector<core::GeoCoordinate*> checkpoints;
    83             std::vector<const core::GeoCoordinate*> to_draw;
    84             //std::vector<xmlNodePtr> checkpoints_node;
    85             //bool init;
    86     };
     79  std::vector<core::GeoCoordinate *> checkpoints;
     80  std::vector<const core::GeoCoordinate *> to_draw;
     81  // std::vector<xmlNodePtr> checkpoints_node;
     82  // bool init;
     83};
    8784
    8885} // end namespace gui
  • trunk/include/FlairCore/Mutex.h

    r2 r13  
    1919class ConditionVariable_impl;
    2020
    21 namespace flair
    22 {
    23 namespace core
    24 {
     21namespace flair {
     22namespace core {
    2523
    26     /*! \class Mutex
    27     *
    28     * \brief Class defining a mutex
    29     *
    30     */
    31     class Mutex: public Object
    32     {
    33         friend class ::ConditionVariable_impl;
     24/*! \class Mutex
     25*
     26* \brief Class defining a mutex
     27*
     28*/
     29class Mutex : public Object {
     30  friend class ::ConditionVariable_impl;
    3431
    35         public:
    36             /*!
    37             * \brief Constructor
    38             *
    39             * Construct a mutex.
    40             *
    41             * \param parent parent
    42             * \param name name
    43             */
    44             Mutex(const Object *parent,std::string name="");
     32public:
     33  /*!
     34  * \brief Constructor
     35  *
     36  * Construct a mutex.
     37  *
     38  * \param parent parent
     39  * \param name name
     40  */
     41  Mutex(const Object *parent, std::string name = "");
    4542
    46             /*!
    47             * \brief Destructor
    48             *
    49             */
    50             ~Mutex();
     43  /*!
     44  * \brief Destructor
     45  *
     46  */
     47  ~Mutex();
    5148
    52             /*!
    53             * \brief GetMutex
    54             *
    55             * Lock the mutex.
    56             *
    57             */
    58             void GetMutex(void) const;
     49  /*!
     50  * \brief GetMutex
     51  *
     52  * Lock the mutex.
     53  *
     54  */
     55  void GetMutex(void) const;
    5956
    60             /*!
    61             * \brief ReleaseMutex
    62             *
    63             * Unlock the mutex.
    64             *
    65             */
    66             void ReleaseMutex(void) const;
     57  /*!
     58  * \brief ReleaseMutex
     59  *
     60  * Unlock the mutex.
     61  *
     62  */
     63  void ReleaseMutex(void) const;
    6764
    68         private:
    69             class Mutex_impl* pimpl_;
    70     };
     65private:
     66  class Mutex_impl *pimpl_;
     67};
    7168
    7269} // end namespace core
  • trunk/include/FlairCore/Object.h

    r2 r13  
    1818#include <stdarg.h>
    1919
    20 #define Warn(...) Warning(__PRETTY_FUNCTION__,__VA_ARGS__)
    21 #define Err(...) Error(__PRETTY_FUNCTION__,__VA_ARGS__)
    22 #define Info(...) Information(__PRETTY_FUNCTION__,__LINE__,__VA_ARGS__)
     20#define Warn(...) Warning(__PRETTY_FUNCTION__, __VA_ARGS__)
     21#define Err(...) Error(__PRETTY_FUNCTION__, __VA_ARGS__)
     22#define Info(...) Information(__PRETTY_FUNCTION__, __LINE__, __VA_ARGS__)
    2323
    2424#define TIME_INFINITE 0
     
    2828class Widget_impl;
    2929
    30 namespace flair
    31 {
    32 namespace core
    33 {
     30namespace flair {
     31namespace core {
    3432
    35     class FrameworkManager;
     33class FrameworkManager;
    3634
    37     class Message {
    38     public:
    39         Message(unsigned int myBufferSize):bufferSize(myBufferSize) {
    40             buffer=new char[bufferSize];
    41         }
    42         ~Message() {
    43             delete buffer;
    44         }
    45         char *buffer;
    46         size_t bufferSize;
    47     };
     35class Message {
     36public:
     37  Message(unsigned int myBufferSize) : bufferSize(myBufferSize) {
     38    buffer = new char[bufferSize];
     39  }
     40  ~Message() { delete buffer; }
     41  char *buffer;
     42  size_t bufferSize;
     43};
    4844
    49     /*!
    50     * \brief Time definition, in ns
    51     *
    52     */
    53     typedef unsigned long long Time;
     45/*!
     46* \brief Time definition, in ns
     47*
     48*/
     49typedef unsigned long long Time;
    5450
    55     /*!
    56     * \brief Time
    57     *
    58     * \return actual time in ns (origin depends on whether the method is compiled in hard real time mode or not. As a conquence, only time differences should be used)
    59     */
    60     Time GetTime(void);
     51/*!
     52* \brief Time
     53*
     54* \return actual time in ns (origin depends on whether the method is compiled in
     55*hard real time mode or not. As a conquence, only time differences should be
     56*used)
     57*/
     58Time GetTime(void);
    6159
    62     /*!
    63     * \brief Formatted print
    64     *
    65     * See standard printf for syntax.
    66     *
    67     * \param format text string to display
    68     */
    69     void Printf(const char *format, ...);
     60/*!
     61* \brief Formatted print
     62*
     63* See standard printf for syntax.
     64*
     65* \param format text string to display
     66*/
     67void Printf(const char *format, ...);
    7068
    71     /*! \class Object
    72     *
    73     * \brief Base class for all Framework's classes
    74     *
    75     * This is the base class for all other classes. \n
    76     * It handles parent/child links and thus allow auto destruction of childs.
    77     *
    78     */
    79     class Object
    80     {
    81         friend class ::Widget_impl;
     69/*! \class Object
     70*
     71* \brief Base class for all Framework's classes
     72*
     73* This is the base class for all other classes. \n
     74* It handles parent/child links and thus allow auto destruction of childs.
     75*
     76*/
     77class Object {
     78  friend class ::Widget_impl;
    8279
    83         public:
    84             typedef enum {
    85                 Auto=0,
    86                 Red=31,
    87                 Green=32,
    88                 Orange=33
    89             } color_t;
    90             /*!
    91             * \brief Constructor
    92             *
    93             * Construct an Object, which is child of its parent.
    94             *
    95             * \param parent parent
    96             * \param name name
    97             * \param type type
    98             */
    99             Object(const Object* parent=NULL,std::string name="",std::string type="");
     80public:
     81  typedef enum { Auto = 0, Red = 31, Green = 32, Orange = 33 } color_t;
     82  /*!
     83  * \brief Constructor
     84  *
     85  * Construct an Object, which is child of its parent.
     86  *
     87  * \param parent parent
     88  * \param name name
     89  * \param type type
     90  */
     91  Object(const Object *parent = NULL, std::string name = "",
     92         std::string type = "");
    10093
    101             /*!
    102             * \brief Destructor
    103             *
    104             * Calling it will automatically destruct all childs.
    105             *
    106             */
    107             virtual ~Object();
     94  /*!
     95  * \brief Destructor
     96  *
     97  * Calling it will automatically destruct all childs.
     98  *
     99  */
     100  virtual ~Object();
    108101
    109             /*!
    110             * \brief Name
    111             *
    112             * \return Object's name
    113             */
    114             std::string ObjectName(void) const;
     102  /*!
     103  * \brief Name
     104  *
     105  * \return Object's name
     106  */
     107  std::string ObjectName(void) const;
    115108
    116             /*!
    117             * \brief Type
    118             *
    119             * \return Object's type
    120             */
    121             std::string ObjectType(void) const;
     109  /*!
     110  * \brief Type
     111  *
     112  * \return Object's type
     113  */
     114  std::string ObjectType(void) const;
    122115
    123             /*!
    124             * \brief Parent
    125             *
    126             * \return Object's parent
    127             */
    128             const Object* Parent(void) const;
     116  /*!
     117  * \brief Parent
     118  *
     119  * \return Object's parent
     120  */
     121  const Object *Parent(void) const;
    129122
    130             /*!
    131             * \brief Childs of the same type
    132             *
    133             * \return a vector of all childs of the same type
    134             */
    135             std::vector<const Object*>* TypeChilds(void) const;
     123  /*!
     124  * \brief Childs of the same type
     125  *
     126  * \return a vector of all childs of the same type
     127  */
     128  std::vector<const Object *> *TypeChilds(void) const;
    136129
    137             /*!
    138             * \brief Childs
    139             *
    140             * \return a vector of all childs
    141             */
    142             std::vector<const Object*>* Childs(void) const;
     130  /*!
     131  * \brief Childs
     132  *
     133  * \return a vector of all childs
     134  */
     135  std::vector<const Object *> *Childs(void) const;
    143136
    144             /*!
    145             * \brief Formatted information
    146             *
    147             * Green colored Printf(). \n
    148             * Note that it is better to call Info macro, which automatically fills function parameter.
    149             *
    150             * \param function name of calling function
    151             * \param line line number in calling function
    152             * \param format text string to display
    153             */
    154             void Information(const char *function, int line, const char *format, ...) const;
     137  /*!
     138  * \brief Formatted information
     139  *
     140  * Green colored Printf(). \n
     141  * Note that it is better to call Info macro, which automatically fills
     142  *function parameter.
     143  *
     144  * \param function name of calling function
     145  * \param line line number in calling function
     146  * \param format text string to display
     147  */
     148  void Information(const char *function, int line, const char *format,
     149                   ...) const;
    155150
    156             /*!
    157             * \brief Formatted warning
    158             *
    159             * Orange colored Printf(). \n
    160             * Note that it is better to call Warn macro, which automatically fills function parameter.
    161             *
    162             * \param function name of calling function
    163             * \param format text string to display
    164             */
    165             void Warning(const char *function,const char *format, ...) const;
     151  /*!
     152  * \brief Formatted warning
     153  *
     154  * Orange colored Printf(). \n
     155  * Note that it is better to call Warn macro, which automatically fills
     156  *function parameter.
     157  *
     158  * \param function name of calling function
     159  * \param format text string to display
     160  */
     161  void Warning(const char *function, const char *format, ...) const;
    166162
    167             /*!
    168             * \brief Formatted error
    169             *
    170             * Red colored Printf(). \n
    171             * Note that it is better to call Err macro, which automatically fills function parameter. \n
    172             * After calling this method, ErrorOccured() will always return true.
    173             *
    174             * \param function name of calling function
    175             * \param format text string to display
    176             */
    177             void Error(const char *function,const char *format, ...) const;
     163  /*!
     164  * \brief Formatted error
     165  *
     166  * Red colored Printf(). \n
     167  * Note that it is better to call Err macro, which automatically fills function
     168  *parameter. \n
     169  * After calling this method, ErrorOccured() will always return true.
     170  *
     171  * \param function name of calling function
     172  * \param format text string to display
     173  */
     174  void Error(const char *function, const char *format, ...) const;
    178175
    179             /*!
    180             * \brief Has an errror occured?
    181             *
    182             * Check if an error occured, in fact if Error() was called at least once. \n
    183             * Once Error() was called, this method will never return back false.
    184             *
    185             * \param recursive if true, recursively check among childs
    186             * \return true if an error occured
    187             */
    188             bool ErrorOccured(bool recursive=true) const;
     176  /*!
     177  * \brief Has an errror occured?
     178  *
     179  * Check if an error occured, in fact if Error() was called at least once. \n
     180  * Once Error() was called, this method will never return back false.
     181  *
     182  * \param recursive if true, recursively check among childs
     183  * \return true if an error occured
     184  */
     185  bool ErrorOccured(bool recursive = true) const;
    189186
    190         private:
    191             class Object_impl* pimpl_;
    192             void ColorPrintf(color_t, const char *function, int line, const char *format, va_list *args) const;
    193     };
     187private:
     188  class Object_impl *pimpl_;
     189  void ColorPrintf(color_t, const char *function, int line, const char *format,
     190                   va_list *args) const;
     191};
    194192
    195193} // end namespace core
  • trunk/include/FlairCore/OneAxisRotation.h

    r2 r13  
    1818class OneAxisRotation_impl;
    1919
    20 
    21 namespace flair
    22 {
    23 namespace gui
    24 {
    25     class LayoutPosition;
     20namespace flair {
     21namespace gui {
     22class LayoutPosition;
    2623}
    2724
    28 namespace core
    29 {
    30     class Vector3D;
    31     class Euler;
    32     class Quaternion;
    33     class RotationMatrix;
     25namespace core {
     26class Vector3D;
     27class Euler;
     28class Quaternion;
     29class RotationMatrix;
    3430
    35     /*! \class OneAxisRotation
    36     *
    37     * \brief Class defining a rotation around one axis
    38     *
    39     * Axe and value of the rotation are placed in a GroupBox on ground station.
    40     *
    41     */
    42     class OneAxisRotation: public gui::GroupBox
    43     {
    44         public:
    45             /*!
    46             * \brief Constructor
    47             *
    48             * Construct a OneAxisRotation at given position.
    49             *
    50             * \param position position to place the GroupBox
    51             * \param name name
    52             */
    53             OneAxisRotation(const gui::LayoutPosition* position,std::string namel);
     31/*! \class OneAxisRotation
     32*
     33* \brief Class defining a rotation around one axis
     34*
     35* Axe and value of the rotation are placed in a GroupBox on ground station.
     36*
     37*/
     38class OneAxisRotation : public gui::GroupBox {
     39public:
     40  /*!
     41  * \brief Constructor
     42  *
     43  * Construct a OneAxisRotation at given position.
     44  *
     45  * \param position position to place the GroupBox
     46  * \param name name
     47  */
     48  OneAxisRotation(const gui::LayoutPosition *position, std::string namel);
    5449
    55             /*!
    56             * \brief Destructor
    57             *
    58             */
    59             ~OneAxisRotation();
     50  /*!
     51  * \brief Destructor
     52  *
     53  */
     54  ~OneAxisRotation();
    6055
    61             /*!
    62             * \brief Compute rotation
    63             *
    64             * \param vector Vector3D to rotate
    65             */
    66             void ComputeRotation(core::Vector3D& vector) const;
     56  /*!
     57  * \brief Compute rotation
     58  *
     59  * \param vector Vector3D to rotate
     60  */
     61  void ComputeRotation(core::Vector3D &vector) const;
    6762
    68             /*!
    69             * \brief Compute rotation
    70             *
    71             * \param euler Euler angle to rotate
    72             */
    73             void ComputeRotation(core::Euler& euler) const;
     63  /*!
     64  * \brief Compute rotation
     65  *
     66  * \param euler Euler angle to rotate
     67  */
     68  void ComputeRotation(core::Euler &euler) const;
    7469
    75             /*!
    76             * \brief Compute rotation
    77             *
    78             * \param quaternion Quaternion to rotate
    79             */
    80             void ComputeRotation(core::Quaternion& quaternion) const;
     70  /*!
     71  * \brief Compute rotation
     72  *
     73  * \param quaternion Quaternion to rotate
     74  */
     75  void ComputeRotation(core::Quaternion &quaternion) const;
    8176
    82             /*!
    83             * \brief Compute rotation
    84             *
    85             * \param matrix RotationMatrix to rotate
    86             */
    87             void ComputeRotation(core::RotationMatrix& matrix) const;
     77  /*!
     78  * \brief Compute rotation
     79  *
     80  * \param matrix RotationMatrix to rotate
     81  */
     82  void ComputeRotation(core::RotationMatrix &matrix) const;
    8883
    89         private:
    90             const class OneAxisRotation_impl* pimpl_;
    91 
    92     };
     84private:
     85  const class OneAxisRotation_impl *pimpl_;
     86};
    9387
    9488} // end namespace core
  • trunk/include/FlairCore/Picture.h

    r2 r13  
    1717#include <cxtypes.h>
    1818
    19 namespace flair
    20 {
    21 namespace core
    22 {
    23     class cvimage;
     19namespace flair {
     20namespace core {
     21class cvimage;
    2422}
    2523
    26 namespace gui
    27 {
     24namespace gui {
    2825
    29     class LayoutPosition;
     26class LayoutPosition;
    3027
    31     /*! \class Picture
    32     *
    33     * \brief Class displaying a Picture on the ground station
    34     *
    35     */
    36     class Picture:public SendData
    37     {
    38         public:
    39             /*!
    40             * \brief Constructor
    41             *
    42             * Construct a picture at given position. \n
    43             * The Picture will automatically be child of position->getLayout() Layout. After calling this constructor,
    44             * position will be deleted as it is no longer usefull.
    45             *
    46             * \param position position to draw plot
    47             * \param name name
    48             * \param image image to draw
    49             */
    50             Picture(const LayoutPosition* position,std::string name,const core::cvimage *image);
     28/*! \class Picture
     29*
     30* \brief Class displaying a Picture on the ground station
     31*
     32*/
     33class Picture : public SendData {
     34public:
     35  /*!
     36  * \brief Constructor
     37  *
     38  * Construct a picture at given position. \n
     39  * The Picture will automatically be child of position->getLayout() Layout.
     40  *After calling this constructor,
     41  * position will be deleted as it is no longer usefull.
     42  *
     43  * \param position position to draw plot
     44  * \param name name
     45  * \param image image to draw
     46  */
     47  Picture(const LayoutPosition *position, std::string name,
     48          const core::cvimage *image);
    5149
    52             /*!
    53             * \brief Destructor
    54             *
    55             */
    56             ~Picture();
     50  /*!
     51  * \brief Destructor
     52  *
     53  */
     54  ~Picture();
    5755
    58         private:
    59             /*!
    60             * \brief Copy datas to specified buffer
    61             *
    62             * Reimplemented from SendData.
    63             *
    64             * \param buf output buffer
    65             */
    66             void CopyDatas(char* buf) const;
     56private:
     57  /*!
     58  * \brief Copy datas to specified buffer
     59  *
     60  * Reimplemented from SendData.
     61  *
     62  * \param buf output buffer
     63  */
     64  void CopyDatas(char *buf) const;
    6765
    68             /*!
    69             * \brief Extra Xml event
    70             *
    71             * Reimplemented from SendData.
    72             */
    73             void ExtraXmlEvent(void){};
     66  /*!
     67  * \brief Extra Xml event
     68  *
     69  * Reimplemented from SendData.
     70  */
     71  void ExtraXmlEvent(void){};
    7472
    75             const core::cvimage *image;
    76     };
     73  const core::cvimage *image;
     74};
    7775
    7876} // end namespace gui
  • trunk/include/FlairCore/PushButton.h

    r2 r13  
    1616#include <Widget.h>
    1717
    18 namespace flair
    19 {
    20 namespace gui
    21 {
     18namespace flair {
     19namespace gui {
    2220
    23     class LayoutPosition;
     21class LayoutPosition;
    2422
    25     /*! \class PushButton
    26     *
    27     * \brief Class displaying a QPushButton on the ground station
    28     *
    29     */
    30     class PushButton:public Widget
    31     {
    32         public:
    33             /*!
    34             * \brief Constructor
    35             *
    36             * Construct a QPushButton at given position. \n
    37             * The PushButton will automatically be child of position->getLayout() Layout. After calling this constructor,
    38             * position will be deleted as it is no longer usefull.
    39             *
    40             * \param parent parent
    41             * \param name name
    42             */
    43             PushButton(const LayoutPosition* position,std::string name);
     23/*! \class PushButton
     24*
     25* \brief Class displaying a QPushButton on the ground station
     26*
     27*/
     28class PushButton : public Widget {
     29public:
     30  /*!
     31  * \brief Constructor
     32  *
     33  * Construct a QPushButton at given position. \n
     34  * The PushButton will automatically be child of position->getLayout() Layout.
     35  *After calling this constructor,
     36  * position will be deleted as it is no longer usefull.
     37  *
     38  * \param parent parent
     39  * \param name name
     40  */
     41  PushButton(const LayoutPosition *position, std::string name);
    4442
    45             /*!
    46             * \brief Destructor
    47             *
    48             */
    49             ~PushButton();
     43  /*!
     44  * \brief Destructor
     45  *
     46  */
     47  ~PushButton();
    5048
    51             /*!
    52             * \brief Has been clicled?
    53             *
    54             * After calling this method, the internal flag
    55             * representing the state of the button is
    56             * automatically set to false.
    57             *
    58             * \return true if button was clicked
    59             */
    60             bool Clicked(void);
     49  /*!
     50  * \brief Has been clicled?
     51  *
     52  * After calling this method, the internal flag
     53  * representing the state of the button is
     54  * automatically set to false.
     55  *
     56  * \return true if button was clicked
     57  */
     58  bool Clicked(void);
    6159
    62         private:
    63             /*!
    64             * \brief XmlEvent from ground station
    65             *
    66             * Reimplemented from Widget.
    67             *
    68             */
    69             void XmlEvent(void);
     60private:
     61  /*!
     62  * \brief XmlEvent from ground station
     63  *
     64  * Reimplemented from Widget.
     65  *
     66  */
     67  void XmlEvent(void);
    7068
    71             bool clicked;
    72     };
     69  bool clicked;
     70};
    7371
    7472} // end namespace gui
  • trunk/include/FlairCore/Quaternion.h

    r2 r13  
    1313#define QUATERNION_H
    1414
    15 namespace flair { namespace core {
    16     class Euler;
    17     class Vector3D;
    18     class RotationMatrix;
    19 
    20     /*! \class Quaternion
    21     *
    22     * \brief Class defining a quaternion
    23     */
    24     class Quaternion {
    25         public:
    26             /*!
    27             * \brief Constructor
    28             *
    29             * Construct a quaternion using specified values.
    30             *
    31             * \param q0, scalar part
    32             * \param q1
    33             * \param q2
    34             * \param q3
    35             */
    36             Quaternion(float q0=1,float q1=0,float q2=0,float q3=0);
    37 
    38             /*!
    39             * \brief Destructor
    40             *
    41             */
    42             ~Quaternion();
    43 
    44             /*!
    45             * \brief Norm
    46             *
    47             * \return norm
    48             */
    49             float GetNorm(void) const;
    50 
    51             /*!
    52             * \brief Normalize
    53             */
    54             void Normalize(void);
    55 
    56             /*!
    57             * \brief Logarithm
    58             *
    59             * This method also Normalize the quaternion.
    60             *
    61             * \param logarithm output logarithm
    62             */
    63             void GetLogarithm(Vector3D &logarithm);
    64 
    65             /*!
    66             * \brief Logarithm
    67             *
    68             * This method also Normalize the quaternion.
    69             *
    70             * \return output logarithm
    71             */
    72             Vector3D GetLogarithm(void);
    73 
    74             /*!
    75             * \brief Conjugate
    76             */
    77             void Conjugate(void);
    78 
    79             /*!
    80             * \brief Conjugate
    81             *
    82             * \return Conjugate
    83             */
    84             Quaternion GetConjugate(void);
    85 
    86             /*!
    87             * \brief Derivative
    88             *
    89             * \param w angular speed
    90             *
    91             * \return derivative
    92             */
    93             Quaternion GetDerivative(const Vector3D &angularSpeed) const;
    94 
    95             /*!
    96             * \brief Derivate
    97             *
    98             * \param w rotationonal speed
    99             */
    100             void Derivate(const Vector3D &angularSpeed);
    101 
    102             /*!
    103             * \brief Convert to euler angles
    104             *
    105             * \param euler output euler angles
    106             */
    107             void ToEuler(Euler &euler) const;
    108 
    109             /*!
    110             * \brief Convert to euler angles
    111             *
    112             * \return euler angles
    113             */
    114             Euler ToEuler(void) const;
    115 
    116             /*!
    117             * \brief Convert to rotation matrix
    118             *
    119             * \param m output matrix
    120             */
    121             void ToRotationMatrix(RotationMatrix &matrix) const;
    122 
    123             /*!
    124             * \brief q0
    125             */
    126             float q0;
    127 
    128             /*!
    129             * \brief q1
    130             */
    131             float q1;
    132 
    133             /*!
    134             * \brief q2
    135             */
    136             float q2;
    137 
    138             /*!
    139             * \brief q3
    140             */
    141             float q3;
    142 
    143             Quaternion& operator+=(const Quaternion& quaternion);
    144             Quaternion& operator-=(const Quaternion& quaternion);
    145             Quaternion& operator=(const Quaternion& quaternion);
    146     };
    147 
    148     /*! Add
    149     *
    150     * \brief Add
    151     *
    152     * \param quaterniontA quaternion
    153     * \param quaterniontB quaternion
    154     *
    155     * \return quaterniontA+quaterniontB
    156     */
    157     Quaternion operator + (Quaternion const &quaterniontA,Quaternion const &quaterniontB);
    158 
    159     /*! Substract
    160     *
    161     * \brief Substract
    162     *
    163     * \param quaterniontA quaternion
    164     * \param quaterniontB quaternion
    165     *
    166     * \return quaterniontA-quaterniontB
    167     */
    168     Quaternion operator - (Quaternion const &quaternionA,Quaternion const &quaterniontB);
    169 
    170     /*! Minus
    171     *
    172     * \brief Minus
    173     *
    174     * \param quaternion quaternion
    175     *
    176     * \return -quaternion
    177     */
    178     Quaternion operator-(const Quaternion &quaternion);
    179 
    180     /*! Multiply
    181     *
    182     * \brief Multiply
    183     *
    184     * \param quaterniontA quaternion
    185     * \param quaterniontB quaternion
    186     *
    187     * \return quaterniontA*quaterniontB
    188     */
    189     Quaternion operator * (Quaternion const &quaternionA,Quaternion const &quaterniontB);
    190 
    191     /*! Multiply
    192     *
    193     * \brief Multiply
    194     *
    195     * \param coeff coefficient
    196     * \param quat quaternion
    197     *
    198     * \return coeff*quat
    199     */
    200     Quaternion operator * (float coeff,Quaternion const &quaternion);
    201 
    202     /*! Multiply
    203     *
    204     * \brief Multiply
    205     *
    206     * \param quat quaternion
    207     * \param coeff coefficient
    208     *
    209     * \return coeff*quat
    210     */
    211     Quaternion operator * (Quaternion const &quaternion,float coeff);
     15namespace flair {
     16namespace core {
     17class Euler;
     18class Vector3D;
     19class RotationMatrix;
     20
     21/*! \class Quaternion
     22*
     23* \brief Class defining a quaternion
     24*/
     25class Quaternion {
     26public:
     27  /*!
     28  * \brief Constructor
     29  *
     30  * Construct a quaternion using specified values.
     31  *
     32  * \param q0, scalar part
     33  * \param q1
     34  * \param q2
     35  * \param q3
     36  */
     37  Quaternion(float q0 = 1, float q1 = 0, float q2 = 0, float q3 = 0);
     38
     39  /*!
     40  * \brief Destructor
     41  *
     42  */
     43  ~Quaternion();
     44
     45  /*!
     46  * \brief Norm
     47  *
     48  * \return norm
     49  */
     50  float GetNorm(void) const;
     51
     52  /*!
     53  * \brief Normalize
     54  */
     55  void Normalize(void);
     56
     57  /*!
     58  * \brief Logarithm
     59  *
     60  * This method also Normalize the quaternion.
     61  *
     62  * \param logarithm output logarithm
     63  */
     64  void GetLogarithm(Vector3D &logarithm);
     65
     66  /*!
     67  * \brief Logarithm
     68  *
     69  * This method also Normalize the quaternion.
     70  *
     71  * \return output logarithm
     72  */
     73  Vector3D GetLogarithm(void);
     74
     75  /*!
     76  * \brief Conjugate
     77  */
     78  void Conjugate(void);
     79
     80  /*!
     81  * \brief Conjugate
     82  *
     83  * \return Conjugate
     84  */
     85  Quaternion GetConjugate(void);
     86
     87  /*!
     88  * \brief Derivative
     89  *
     90  * \param w angular speed
     91  *
     92  * \return derivative
     93  */
     94  Quaternion GetDerivative(const Vector3D &angularSpeed) const;
     95
     96  /*!
     97  * \brief Derivate
     98  *
     99  * \param w rotationonal speed
     100  */
     101  void Derivate(const Vector3D &angularSpeed);
     102
     103  /*!
     104  * \brief Convert to euler angles
     105  *
     106  * \param euler output euler angles
     107  */
     108  void ToEuler(Euler &euler) const;
     109
     110  /*!
     111  * \brief Convert to euler angles
     112  *
     113  * \return euler angles
     114  */
     115  Euler ToEuler(void) const;
     116
     117  /*!
     118  * \brief Convert to rotation matrix
     119  *
     120  * \param m output matrix
     121  */
     122  void ToRotationMatrix(RotationMatrix &matrix) const;
     123
     124  /*!
     125  * \brief q0
     126  */
     127  float q0;
     128
     129  /*!
     130  * \brief q1
     131  */
     132  float q1;
     133
     134  /*!
     135  * \brief q2
     136  */
     137  float q2;
     138
     139  /*!
     140  * \brief q3
     141  */
     142  float q3;
     143
     144  Quaternion &operator+=(const Quaternion &quaternion);
     145  Quaternion &operator-=(const Quaternion &quaternion);
     146  Quaternion &operator=(const Quaternion &quaternion);
     147};
     148
     149/*! Add
     150*
     151* \brief Add
     152*
     153* \param quaterniontA quaternion
     154* \param quaterniontB quaternion
     155*
     156* \return quaterniontA+quaterniontB
     157*/
     158Quaternion operator+(Quaternion const &quaterniontA,
     159                     Quaternion const &quaterniontB);
     160
     161/*! Substract
     162*
     163* \brief Substract
     164*
     165* \param quaterniontA quaternion
     166* \param quaterniontB quaternion
     167*
     168* \return quaterniontA-quaterniontB
     169*/
     170Quaternion operator-(Quaternion const &quaternionA,
     171                     Quaternion const &quaterniontB);
     172
     173/*! Minus
     174*
     175* \brief Minus
     176*
     177* \param quaternion quaternion
     178*
     179* \return -quaternion
     180*/
     181Quaternion operator-(const Quaternion &quaternion);
     182
     183/*! Multiply
     184*
     185* \brief Multiply
     186*
     187* \param quaterniontA quaternion
     188* \param quaterniontB quaternion
     189*
     190* \return quaterniontA*quaterniontB
     191*/
     192Quaternion operator*(Quaternion const &quaternionA,
     193                     Quaternion const &quaterniontB);
     194
     195/*! Multiply
     196*
     197* \brief Multiply
     198*
     199* \param coeff coefficient
     200* \param quat quaternion
     201*
     202* \return coeff*quat
     203*/
     204Quaternion operator*(float coeff, Quaternion const &quaternion);
     205
     206/*! Multiply
     207*
     208* \brief Multiply
     209*
     210* \param quat quaternion
     211* \param coeff coefficient
     212*
     213* \return coeff*quat
     214*/
     215Quaternion operator*(Quaternion const &quaternion, float coeff);
    212216
    213217} // end namespace core
  • trunk/include/FlairCore/RTDM_I2cPort.h

    r2 r13  
    1616#include <I2cPort.h>
    1717
    18 namespace flair
    19 {
    20 namespace core
    21 {
    22     /*! \class RTDM_I2cPort
    23     *
    24     * \brief Class for real time i2c port using RTDM
    25     *
    26     * This class can only be used with the real time version of Framework library.
    27     *
    28     */
    29     class RTDM_I2cPort: public I2cPort
    30     {
    31         public:
    32             /*!
    33             * \brief Constructor
    34             *
    35             * Construct an RTDM i2c port, with the following default values: \n
    36             * - 400kbits baudrate \n
    37             * - 500000ns RX timeout \n
    38             * - 1000000ns TX timeout
    39             *
    40             * \param parent parent
    41             * \param name name
    42             * \param device i2c device (ex rti2c1)
    43             */
    44             RTDM_I2cPort(const Object* parent,std::string name,std::string device);
     18namespace flair {
     19namespace core {
     20/*! \class RTDM_I2cPort
     21*
     22* \brief Class for real time i2c port using RTDM
     23*
     24* This class can only be used with the real time version of Framework library.
     25*
     26*/
     27class RTDM_I2cPort : public I2cPort {
     28public:
     29  /*!
     30  * \brief Constructor
     31  *
     32  * Construct an RTDM i2c port, with the following default values: \n
     33  * - 400kbits baudrate \n
     34  * - 500000ns RX timeout \n
     35  * - 1000000ns TX timeout
     36  *
     37  * \param parent parent
     38  * \param name name
     39  * \param device i2c device (ex rti2c1)
     40  */
     41  RTDM_I2cPort(const Object *parent, std::string name, std::string device);
    4542
    46             /*!
    47             * \brief Destructor
    48             *
    49             */
    50             ~RTDM_I2cPort();
     43  /*!
     44  * \brief Destructor
     45  *
     46  */
     47  ~RTDM_I2cPort();
    5148
    52             /*!
    53             * \brief Set slave's address
    54             *
    55             * This method need to be called before any communication.
    56             *
    57             * \param address slave's address
    58             */
    59             int SetSlave(uint16_t address);
     49  /*!
     50  * \brief Set slave's address
     51  *
     52  * This method need to be called before any communication.
     53  *
     54  * \param address slave's address
     55  */
     56  int SetSlave(uint16_t address);
    6057
    61             /*!
    62             * \brief Write datas
    63             *
    64             * \param buf pointer to datas
    65             * \param nbyte length of datas
    66             *
    67             * \return amount of written datas
    68             */
    69             ssize_t Write(const void *buf,size_t nbyte);
     58  /*!
     59  * \brief Write datas
     60  *
     61  * \param buf pointer to datas
     62  * \param nbyte length of datas
     63  *
     64  * \return amount of written datas
     65  */
     66  ssize_t Write(const void *buf, size_t nbyte);
    7067
    71             /*!
    72             * \brief Read datas
    73             *
    74             * \param buf pointer to datas
    75             * \param nbyte length of datas
    76             *
    77             * \return amount of read datas
    78             */
    79             ssize_t Read(void *buf,size_t nbyte);
     68  /*!
     69  * \brief Read datas
     70  *
     71  * \param buf pointer to datas
     72  * \param nbyte length of datas
     73  *
     74  * \return amount of read datas
     75  */
     76  ssize_t Read(void *buf, size_t nbyte);
    8077
    81             /*!
    82             * \brief Set RX timeout
    83             *
    84             * Timeout for waiting an ACK from the slave.
    85             *
    86             * \param timeout_ns timeout in nano second
    87             */
    88             void SetRxTimeout(Time timeout_ns);
     78  /*!
     79  * \brief Set RX timeout
     80  *
     81  * Timeout for waiting an ACK from the slave.
     82  *
     83  * \param timeout_ns timeout in nano second
     84  */
     85  void SetRxTimeout(Time timeout_ns);
    8986
    90             /*!
    91             * \brief Set TX timeout
    92             *
    93             * Timeout for waiting an ACK from the slave.
    94             *
    95             * \param timeout_ns timeout in nano second
    96             */
    97             void SetTxTimeout(Time timeout_ns);
     87  /*!
     88  * \brief Set TX timeout
     89  *
     90  * Timeout for waiting an ACK from the slave.
     91  *
     92  * \param timeout_ns timeout in nano second
     93  */
     94  void SetTxTimeout(Time timeout_ns);
    9895
    99         private:
    100             int fd;
    101     };
     96private:
     97  int fd;
     98};
    10299} // end namespace core
    103100} // end namespace flair
  • trunk/include/FlairCore/RTDM_SerialPort.h

    r2 r13  
    1616#include <SerialPort.h>
    1717
    18 namespace flair
    19 {
    20 namespace core
    21 {
    22     /*! \class RTDM_SerialPort
    23     *
    24     * \brief Class for real time serial port using RTDM
    25     *
    26     * This class can only be used with the real time version of Framework library.
    27     *
    28     */
    29     class RTDM_SerialPort: public SerialPort
    30     {
     18namespace flair {
     19namespace core {
     20/*! \class RTDM_SerialPort
     21*
     22* \brief Class for real time serial port using RTDM
     23*
     24* This class can only be used with the real time version of Framework library.
     25*
     26*/
     27class RTDM_SerialPort : public SerialPort {
    3128
    32         public:
    33             /*!
    34             * \brief Constructor
    35             *
    36             * Construct an RTDM serial port, with the following default values: \n
    37             * - 115200bps baudrate
    38             *
    39             * \param parent parent
    40             * \param name name
    41             * \param device serial device (ex rtser1)
    42             */
    43             RTDM_SerialPort(const Object* parent,std::string port_name,std::string device);
     29public:
     30  /*!
     31  * \brief Constructor
     32  *
     33  * Construct an RTDM serial port, with the following default values: \n
     34  * - 115200bps baudrate
     35  *
     36  * \param parent parent
     37  * \param name name
     38  * \param device serial device (ex rtser1)
     39  */
     40  RTDM_SerialPort(const Object *parent, std::string port_name,
     41                  std::string device);
    4442
    45             /*!
    46             * \brief Destructor
    47             *
    48             */
    49             ~RTDM_SerialPort();
     43  /*!
     44  * \brief Destructor
     45  *
     46  */
     47  ~RTDM_SerialPort();
    5048
    51             /*!
    52             * \brief Set baudrate
    53             *
    54             * \param baudrate baudrate
    55             *
    56             */
    57             void SetBaudrate(int baudrate);
     49  /*!
     50  * \brief Set baudrate
     51  *
     52  * \param baudrate baudrate
     53  *
     54  */
     55  void SetBaudrate(int baudrate);
    5856
    59             /*!
    60             * \brief Set RX timeout
    61             *
    62             * Timeout for waiting datas.
    63             *
    64             * \param timeout_ns timeout in nano second
    65             */
    66             void SetRxTimeout(Time timeout_ns);
     57  /*!
     58  * \brief Set RX timeout
     59  *
     60  * Timeout for waiting datas.
     61  *
     62  * \param timeout_ns timeout in nano second
     63  */
     64  void SetRxTimeout(Time timeout_ns);
    6765
    68             /*!
    69             * \brief Write datas
    70             *
    71             * \param buf pointer to datas
    72             * \param nbyte length of datas
    73             *
    74             * \return amount of written datas
    75             */
    76             ssize_t Write(const void *buf,size_t nbyte);
     66  /*!
     67  * \brief Write datas
     68  *
     69  * \param buf pointer to datas
     70  * \param nbyte length of datas
     71  *
     72  * \return amount of written datas
     73  */
     74  ssize_t Write(const void *buf, size_t nbyte);
    7775
    78             /*!
    79             * \brief Read datas
    80             *
    81             * \param buf pointer to datas
    82             * \param nbyte length of datas
    83             *
    84             * \return amount of read datas
    85             */
    86             ssize_t Read(void *buf,size_t nbyte);
     76  /*!
     77  * \brief Read datas
     78  *
     79  * \param buf pointer to datas
     80  * \param nbyte length of datas
     81  *
     82  * \return amount of read datas
     83  */
     84  ssize_t Read(void *buf, size_t nbyte);
    8785
    88             /*!
    89             * \brief Flush input datas
    90             *
    91             */
    92             void FlushInput(void);
     86  /*!
     87  * \brief Flush input datas
     88  *
     89  */
     90  void FlushInput(void);
    9391
    94         private:
    95             int fd;
    96     };
     92private:
     93  int fd;
     94};
    9795} // end namespace core
    9896} // end namespace flair
  • trunk/include/FlairCore/RangeFinderPlot.h

    r2 r13  
    55/*!
    66 * \file RangeFinderPlot.h
    7  * \brief Class displaying a 2D plot on the ground station for laser range finder like Hokuyo
     7 * \brief Class displaying a 2D plot on the ground station for laser range
     8 * finder like Hokuyo
    89 * \author Guillaume Sanahuja, Copyright Heudiasyc UMR UTC/CNRS 7253
    910 * \date 2014/07/23
     
    1718#include <stdint.h>
    1819
    19 namespace flair
    20 {
    21     namespace core
    22     {
    23         class cvmatrix;
    24     }
     20namespace flair {
     21namespace core {
     22class cvmatrix;
     23}
    2524}
    2625
    27 namespace flair
    28 {
    29 namespace gui
    30 {
     26namespace flair {
     27namespace gui {
    3128
    32     class LayoutPosition;
     29class LayoutPosition;
    3330
    34     /*! \class RangeFinderPlot
    35     *
    36     * \brief Class displaying a 2D plot on the ground station for laser range finder like Hokuyo
    37     *
    38     */
    39     class RangeFinderPlot: public SendData
    40     {
    41         public:
    42             /*!
    43             * \brief Constructor
    44             *
    45             * Construct a 2D plot at given position. \n
    46             * The RangeFinderPlot will automatically be child of position->getLayout() Layout. After calling this constructor,
    47             * position will be deleted as it is no longer usefull.
    48             *
    49             * \param position position to display the plot
    50             * \param name name
    51             * \param x_name name of x axis
    52             * \param xmin default xmin of the plot
    53             * \param xmax default xmax of the plot
    54             * \param y_name name of y axis
    55             * \param ymin default ymin of the plot
    56             * \param ymax default ymax of the plot
    57             * \param datas laser datas
    58             * \param start_angle start angle of the laser
    59             * \param end_angle end angle of the laser
    60             * \param nb_samples number of samples
    61             */
    62             RangeFinderPlot(const LayoutPosition* position,std::string name,
    63                             std::string x_name,float xmin,float xmax,
    64                             std::string y_name,float ymin,float ymax,
    65                             const core::cvmatrix* datas,float start_angle,float end_angle,uint32_t nb_samples);
     31/*! \class RangeFinderPlot
     32*
     33* \brief Class displaying a 2D plot on the ground station for laser range finder
     34*like Hokuyo
     35*
     36*/
     37class RangeFinderPlot : public SendData {
     38public:
     39  /*!
     40  * \brief Constructor
     41  *
     42  * Construct a 2D plot at given position. \n
     43  * The RangeFinderPlot will automatically be child of position->getLayout()
     44  *Layout. After calling this constructor,
     45  * position will be deleted as it is no longer usefull.
     46  *
     47  * \param position position to display the plot
     48  * \param name name
     49  * \param x_name name of x axis
     50  * \param xmin default xmin of the plot
     51  * \param xmax default xmax of the plot
     52  * \param y_name name of y axis
     53  * \param ymin default ymin of the plot
     54  * \param ymax default ymax of the plot
     55  * \param datas laser datas
     56  * \param start_angle start angle of the laser
     57  * \param end_angle end angle of the laser
     58  * \param nb_samples number of samples
     59  */
     60  RangeFinderPlot(const LayoutPosition *position, std::string name,
     61                  std::string x_name, float xmin, float xmax,
     62                  std::string y_name, float ymin, float ymax,
     63                  const core::cvmatrix *datas, float start_angle,
     64                  float end_angle, uint32_t nb_samples);
    6665
    67             /*!
    68             * \brief Destructor
    69             *
    70             */
    71             ~RangeFinderPlot();
     66  /*!
     67  * \brief Destructor
     68  *
     69  */
     70  ~RangeFinderPlot();
    7271
    73         private:
    74             /*!
    75             * \brief Copy datas to specified buffer
    76             *
    77             * Reimplemented from SendData.
    78             *
    79             * \param buf output buffer
    80             */
    81             void CopyDatas(char* buf) const;
     72private:
     73  /*!
     74  * \brief Copy datas to specified buffer
     75  *
     76  * Reimplemented from SendData.
     77  *
     78  * \param buf output buffer
     79  */
     80  void CopyDatas(char *buf) const;
    8281
    83             /*!
    84             * \brief Extra Xml event
    85             *
    86             * Reimplemented from SendData.
    87             */
    88             void ExtraXmlEvent(void){};
     82  /*!
     83  * \brief Extra Xml event
     84  *
     85  * Reimplemented from SendData.
     86  */
     87  void ExtraXmlEvent(void){};
    8988
    90             const core::cvmatrix* datas;
    91     };
     89  const core::cvmatrix *datas;
     90};
    9291
    9392} // end namespace gui
  • trunk/include/FlairCore/RotationMatrix.h

    r2 r13  
    1717namespace flair {
    1818namespace core {
    19     class Euler;
     19class Euler;
    2020
    21     /*! \class RotationMatrix
    22     *
    23     * \brief Class defining a rotation matrix
    24     */
    25     class RotationMatrix {
    26         public:
    27             /*!
    28             * \brief Constructor
    29             *
    30             * Construct an identity rotation matrix
    31             *
    32             */
    33             RotationMatrix();
     21/*! \class RotationMatrix
     22*
     23* \brief Class defining a rotation matrix
     24*/
     25class RotationMatrix {
     26public:
     27  /*!
     28  * \brief Constructor
     29  *
     30  * Construct an identity rotation matrix
     31  *
     32  */
     33  RotationMatrix();
    3434
    35             /*!
    36             * \brief Destructor
    37             *
    38             */
    39             ~RotationMatrix();
     35  /*!
     36  * \brief Destructor
     37  *
     38  */
     39  ~RotationMatrix();
    4040
    41             /*!
    42             * \brief Convert to euler angles
    43             *
    44             * \param euler output euler angles
    45             */
    46             void ToEuler(Euler &euler) const;
     41  /*!
     42  * \brief Convert to euler angles
     43  *
     44  * \param euler output euler angles
     45  */
     46  void ToEuler(Euler &euler) const;
    4747
    48             /*!
    49             * \brief Convert to euler angles
    50             *
    51             * \return euler angles
    52             */
    53             Euler ToEuler(void) const;
    54             /*!
    55             * \brief matrix
    56             *
    57             */
    58             float m[3][3];
     48  /*!
     49  * \brief Convert to euler angles
     50  *
     51  * \return euler angles
     52  */
     53  Euler ToEuler(void) const;
     54  /*!
     55  * \brief matrix
     56  *
     57  */
     58  float m[3][3];
    5959
    60             float& operator()(size_t row,size_t col);
    61             const float& operator()(size_t row,size_t col) const;
    62     };
     60  float &operator()(size_t row, size_t col);
     61  const float &operator()(size_t row, size_t col) const;
     62};
    6363
    6464} // end namespace core
  • trunk/include/FlairCore/SendData.h

    r2 r13  
    1818class SendData_impl;
    1919
    20 namespace flair
    21 {
    22 namespace gui
    23 {
    24     class LayoutPosition;
     20namespace flair {
     21namespace gui {
     22class LayoutPosition;
    2523
    26     /*! \class SendData
    27     *
    28     * \brief Abstract class for sending datas to ground station
    29     *
    30     */
    31     class SendData: public Widget
    32     {
    33         public:
    34             /*!
    35             * \brief Constructor
    36             *
    37             */
    38             SendData(const LayoutPosition* position,std::string name,std::string type,uint16_t default_periodms=100,bool default_enabled=false);
     24/*! \class SendData
     25*
     26* \brief Abstract class for sending datas to ground station
     27*
     28*/
     29class SendData : public Widget {
     30public:
     31  /*!
     32  * \brief Constructor
     33  *
     34  */
     35  SendData(const LayoutPosition *position, std::string name, std::string type,
     36           uint16_t default_periodms = 100, bool default_enabled = false);
    3937
    40             /*!
    41             * \brief Destructor
    42             *
    43             */
    44             virtual ~SendData();
     38  /*!
     39  * \brief Destructor
     40  *
     41  */
     42  virtual ~SendData();
    4543
    46             /*!
    47             * \brief Copy datas to specified buffer
    48             *
    49             * This method must be reimplemented, in order to send datas to ground station.
    50             *
    51             * \param buf output buffer
    52             */
    53             virtual void CopyDatas(char* buf) const =0;
     44  /*!
     45  * \brief Copy datas to specified buffer
     46  *
     47  * This method must be reimplemented, in order to send datas to ground station.
     48  *
     49  * \param buf output buffer
     50  */
     51  virtual void CopyDatas(char *buf) const = 0;
    5452
    55             size_t SendSize(void) const;
    56             uint16_t SendPeriod(void) const; // in ms
    57             bool IsEnabled(void) const;
     53  size_t SendSize(void) const;
     54  uint16_t SendPeriod(void) const; // in ms
     55  bool IsEnabled(void) const;
    5856
    59         protected:
     57protected:
     58  /*!
     59  * \brief Notify that SenData's datas have changed
     60  *
     61  * This method must be called when the datas have changed. \n
     62  * Normally, it occurs when a curve is added to a plot for example. \n
     63  * This method automatically blocks and unblocks the communication.
     64  *
     65  */
     66  void SetSendSize(size_t value);
    6067
    61             /*!
    62             * \brief Notify that SenData's datas have changed
    63             *
    64             * This method must be called when the datas have changed. \n
    65             * Normally, it occurs when a curve is added to a plot for example. \n
    66             * This method automatically blocks and unblocks the communication.
    67             *
    68             */
    69             void SetSendSize(size_t value);
     68  /*!
     69  * \brief Extra Xml event
     70  *
     71  * This method must be reimplemented to handle extra xml event. \n
     72  * It is automatically called when something changed from
     73  * ground station, through XmlEvent method. \n
     74  */
     75  virtual void ExtraXmlEvent(void) = 0;
    7076
    71             /*!
    72             * \brief Extra Xml event
    73             *
    74             * This method must be reimplemented to handle extra xml event. \n
    75             * It is automatically called when something changed from
    76             * ground station, through XmlEvent method. \n
    77             */
    78             virtual void ExtraXmlEvent(void)=0;
     77private:
     78  /*!
     79  * \brief XmlEvent from ground station
     80  *
     81  * Reimplemented from Widget. \n
     82  * This method handles period and enabled properties of the SendData. \n
     83  * Then it calls ExtraXmlEvent to handle specific xml events of reimplemented
     84  *class.
     85  *
     86  */
     87  void XmlEvent(void);
    7988
    80         private:
    81             /*!
    82             * \brief XmlEvent from ground station
    83             *
    84             * Reimplemented from Widget. \n
    85             * This method handles period and enabled properties of the SendData. \n
    86             * Then it calls ExtraXmlEvent to handle specific xml events of reimplemented class.
    87             *
    88             */
    89             void XmlEvent(void);
     89  void SetSendPeriod(uint16_t value);
     90  void SetEnabled(bool value);
    9091
    91             void SetSendPeriod(uint16_t value);
    92             void SetEnabled(bool value);
    93 
    94             class SendData_impl* pimpl_;
    95     };
     92  class SendData_impl *pimpl_;
     93};
    9694
    9795} // end namespace core
  • trunk/include/FlairCore/SerialPort.h

    r2 r13  
    1717#include <stdint.h>
    1818
    19 namespace flair
    20 {
    21 namespace core
    22 {
    23     /*! \class SerialPort
    24     *
    25     * \brief Base class for serial port
    26     */
    27     class SerialPort: public Object
    28     {
    29         public:
    30             /*!
    31             * \brief Constructor
    32             *
    33             * Construct a serial port.
    34             *
    35             * \param parent parent
    36             * \param name name
    37             */
    38             SerialPort(const Object* parent,std::string name): Object(parent,name)
    39             {}
     19namespace flair {
     20namespace core {
     21/*! \class SerialPort
     22*
     23* \brief Base class for serial port
     24*/
     25class SerialPort : public Object {
     26public:
     27  /*!
     28  * \brief Constructor
     29  *
     30  * Construct a serial port.
     31  *
     32  * \param parent parent
     33  * \param name name
     34  */
     35  SerialPort(const Object *parent, std::string name) : Object(parent, name) {}
    4036
    41             /*!
    42             * \brief Destructor
    43             *
    44             */
    45             ~SerialPort(){};
     37  /*!
     38  * \brief Destructor
     39  *
     40  */
     41  ~SerialPort(){};
    4642
    47             /*!
    48             * \brief Set baudrate
    49             *
    50             * \param baudrate baudrate
    51             *
    52             */
    53             virtual void SetBaudrate(int baudrate)=0;
     43  /*!
     44  * \brief Set baudrate
     45  *
     46  * \param baudrate baudrate
     47  *
     48  */
     49  virtual void SetBaudrate(int baudrate) = 0;
    5450
    55             /*!
    56             * \brief Set RX timeout
    57             *
    58             * Timeout for waiting datas.
    59             *
    60             * \param timeout_ns timeout in nano second
    61             */
    62             virtual void SetRxTimeout(Time timeout_ns)=0;
     51  /*!
     52  * \brief Set RX timeout
     53  *
     54  * Timeout for waiting datas.
     55  *
     56  * \param timeout_ns timeout in nano second
     57  */
     58  virtual void SetRxTimeout(Time timeout_ns) = 0;
    6359
    64             /*!
    65             * \brief Write datas
    66             *
    67             * \param buf pointer to datas
    68             * \param nbyte length of datas
    69             *
    70             * \return amount of written datas
    71             */
    72             virtual ssize_t Write(const void *buf,size_t nbyte)=0;
     60  /*!
     61  * \brief Write datas
     62  *
     63  * \param buf pointer to datas
     64  * \param nbyte length of datas
     65  *
     66  * \return amount of written datas
     67  */
     68  virtual ssize_t Write(const void *buf, size_t nbyte) = 0;
    7369
    74             /*!
    75             * \brief Read datas
    76             *
    77             * \param buf pointer to datas
    78             * \param nbyte length of datas
    79             *
    80             * \return amount of read datas
    81             */
    82             virtual ssize_t Read(void *buf,size_t nbyte)=0;
     70  /*!
     71  * \brief Read datas
     72  *
     73  * \param buf pointer to datas
     74  * \param nbyte length of datas
     75  *
     76  * \return amount of read datas
     77  */
     78  virtual ssize_t Read(void *buf, size_t nbyte) = 0;
    8379
    84             /*!
    85             * \brief Flush input datas
    86             *
    87             */
    88             virtual void FlushInput(void)=0;
    89 
    90     };
     80  /*!
     81  * \brief Flush input datas
     82  *
     83  */
     84  virtual void FlushInput(void) = 0;
     85};
    9186} // end namespace core
    9287} // end namespace framework
  • trunk/include/FlairCore/SharedMem.h

    r2 r13  
    1919class SharedMem_impl;
    2020
    21 namespace flair
    22 {
    23 namespace core
    24 {
     21namespace flair {
     22namespace core {
    2523
    26     /*! \class SharedMem
    27     *
    28     * \brief Class defining a shared memory
    29     *
    30     * Shared memory is identified by its name so it can be accessed
    31     * by another processus using its name.
    32     */
     24/*! \class SharedMem
     25*
     26* \brief Class defining a shared memory
     27*
     28* Shared memory is identified by its name so it can be accessed
     29* by another processus using its name.
     30*/
    3331
    34     class SharedMem: public Object
    35     {
    36         public:
    37             /*!
    38             * \brief Constructor
    39             *
    40             * Construct a shared memory object
    41             *
    42             * \param parent parent
    43             * \param name name
    44             * \param size size of the shared memory
    45             */
    46             SharedMem(const Object* parent,std::string name,size_t size);
     32class SharedMem : public Object {
     33public:
     34  /*!
     35  * \brief Constructor
     36  *
     37  * Construct a shared memory object
     38  *
     39  * \param parent parent
     40  * \param name name
     41  * \param size size of the shared memory
     42  */
     43  SharedMem(const Object *parent, std::string name, size_t size);
    4744
    48             /*!
    49             * \brief Destructor
    50             *
    51             */
    52             ~SharedMem();
     45  /*!
     46  * \brief Destructor
     47  *
     48  */
     49  ~SharedMem();
    5350
    54             /*!
    55             * \brief Write
    56             *
    57             * \param buf input buffer to write to memory
    58             * \param size buffer size
    59             */
    60             void Write(const char* buf,size_t size);
     51  /*!
     52  * \brief Write
     53  *
     54  * \param buf input buffer to write to memory
     55  * \param size buffer size
     56  */
     57  void Write(const char *buf, size_t size);
    6158
    62             /*!
    63             * \brief Read
    64             *
    65             * \param buf output buffer to write from memory
    66             * \param size buffer size
    67             */
    68             void Read(char* buf,size_t size) const;
     59  /*!
     60  * \brief Read
     61  *
     62  * \param buf output buffer to write from memory
     63  * \param size buffer size
     64  */
     65  void Read(char *buf, size_t size) const;
    6966
    70         private:
    71             SharedMem_impl* pimpl_;
    72     };
     67private:
     68  SharedMem_impl *pimpl_;
     69};
    7370
    7471} // end namespace core
  • trunk/include/FlairCore/Socket.h

    r2 r13  
    2020class Socket_impl;
    2121
    22 namespace flair
    23 {
    24 namespace core
    25 {
     22namespace flair {
     23namespace core {
    2624
    27     /*! \class Socket
    28     *
    29     * \brief Class encapsulating a UDP socket. It assumes packets are coming from only one distant host on a given port.
    30     *
    31     */
    32     class Socket: public Object {
    33     public:
    34         /*!
    35         * \brief Constructor
    36         *
    37         * Construct the client side of the socket
    38         *
    39         * \param parent parent
    40         * \param name name
    41         * \param address server address (ex 192.168.1.1:9000)
    42         * \param broadcast true if address is a broadcast address
    43         */
    44         Socket(const Object* parent, std::string name,std::string address,bool broadcast=false);
     25/*! \class Socket
     26*
     27* \brief Class encapsulating a UDP socket. It assumes packets are coming from
     28*only one distant host on a given port.
     29*
     30*/
     31class Socket : public Object {
     32public:
     33  /*!
     34  * \brief Constructor
     35  *
     36  * Construct the client side of the socket
     37  *
     38  * \param parent parent
     39  * \param name name
     40  * \param address server address (ex 192.168.1.1:9000)
     41  * \param broadcast true if address is a broadcast address
     42  */
     43  Socket(const Object *parent, std::string name, std::string address,
     44         bool broadcast = false);
    4545
    46         /*!
    47         * \brief Constructor
    48         *
    49         * Construct the server side of the socket
    50         *
    51         * \param parent parent
    52         * \param name name
    53         * \param port listening port
    54         */
    55         Socket(const Object* parent, std::string name,uint16_t port);
     46  /*!
     47  * \brief Constructor
     48  *
     49  * Construct the server side of the socket
     50  *
     51  * \param parent parent
     52  * \param name name
     53  * \param port listening port
     54  */
     55  Socket(const Object *parent, std::string name, uint16_t port);
    5656
    57         /*!
    58         * \brief Destructor
    59         *
    60         */
    61         ~Socket();
     57  /*!
     58  * \brief Destructor
     59  *
     60  */
     61  ~Socket();
    6262
    63         /*!
    64         * \brief Send a message
    65         *
    66         * In case of a broadcast Socket, Parent()->ObjectName() is used as source of the message, this name should be unique.
    67         *
    68         * \param message message
    69         */
    70         void SendMessage(std::string message);
     63  /*!
     64  * \brief Send a message
     65  *
     66  * In case of a broadcast Socket, Parent()->ObjectName() is used as source of
     67  *the message, this name should be unique.
     68  *
     69  * \param message message
     70  */
     71  void SendMessage(std::string message);
    7172
    72         /*!
    73         * \brief Send a message
    74         *
    75         * \param message message
    76         * \param message_len message length
    77         */
    78         void SendMessage(const char* message,size_t message_len);
     73  /*!
     74  * \brief Send a message
     75  *
     76  * \param message message
     77  * \param message_len message length
     78  */
     79  void SendMessage(const char *message, size_t message_len);
    7980
    80         /*!
    81         * \brief Receive a message
    82         *
    83         * Receive a message and wait up to timeout. \n
    84         * If src and src_len are specified, the source of the message will be
    85         * copied in the src buffer. \n
    86         * Note that in case of a broadcast socket, own messages are filtered and
    87         * are not received.
    88         *
    89         * \param buf buffer to put the message
    90         * \param buf_len buffer length
    91         * \param timeout timeout
    92         * \param src buffer to put source name
    93         * \param src_len buffer length
    94         *
    95         * \return size of the received message
    96         */
    97         ssize_t RecvMessage(char* buf,size_t buf_len,Time timeout,char* src=NULL,size_t* src_len=NULL);
     81  /*!
     82  * \brief Receive a message
     83  *
     84  * Receive a message and wait up to timeout. \n
     85  * If src and src_len are specified, the source of the message will be
     86  * copied in the src buffer. \n
     87  * Note that in case of a broadcast socket, own messages are filtered and
     88  * are not received.
     89  *
     90  * \param buf buffer to put the message
     91  * \param buf_len buffer length
     92  * \param timeout timeout
     93  * \param src buffer to put source name
     94  * \param src_len buffer length
     95  *
     96  * \return size of the received message
     97  */
     98  ssize_t RecvMessage(char *buf, size_t buf_len, Time timeout, char *src = NULL,
     99                      size_t *src_len = NULL);
    98100
    99         void NetworkToHost(char *data,size_t dataSize);
    100         void HostToNetwork(char *data,size_t dataSize);
     101  void NetworkToHost(char *data, size_t dataSize);
     102  void HostToNetwork(char *data, size_t dataSize);
    101103
    102     private:
    103        class Socket_impl* pimpl_;
    104     };
     104private:
     105  class Socket_impl *pimpl_;
     106};
    105107
    106108} // end namespace core
  • trunk/include/FlairCore/SpinBox.h

    r2 r13  
    1616#include <Box.h>
    1717
    18 namespace flair
    19 {
    20 namespace gui
    21 {
     18namespace flair {
     19namespace gui {
    2220
    23     class LayoutPosition;
     21class LayoutPosition;
    2422
    25     /*! \class SpinBox
    26     *
    27     * \brief Class displaying a QSpinBox on the ground station
    28     *
    29     */
    30     class SpinBox : public Box
    31     {
    32         public:
    33             /*!
    34             * \brief Constructor
    35             *
    36             * Construct a QSpinBox at given position. \n
    37             * The QSpinBox is saturated to min and max values.
    38             *
    39             * \param position position to display the QSpinBox
    40             * \param name name
    41             * \param min minimum value
    42             * \param max maximum value
    43             * \param step step
    44             * \param default_value default value if not in the xml config file
    45             */
    46             SpinBox(const LayoutPosition* position,std::string name,int min,int max,int step,int default_value=0);/*!
     23/*! \class SpinBox
     24*
     25* \brief Class displaying a QSpinBox on the ground station
     26*
     27*/
     28class SpinBox : public Box {
     29public:
     30  /*!
     31  * \brief Constructor
     32  *
     33  * Construct a QSpinBox at given position. \n
     34  * The QSpinBox is saturated to min and max values.
     35  *
     36  * \param position position to display the QSpinBox
     37  * \param name name
     38  * \param min minimum value
     39  * \param max maximum value
     40  * \param step step
     41  * \param default_value default value if not in the xml config file
     42  */
     43  SpinBox(const LayoutPosition *position, std::string name, int min, int max,
     44          int step, int default_value = 0); /*!
    4745
    48             * \brief Constructor
    49             *
    50             * Construct a QSpinBox at given position. \n
    51             * The QSpinBox is saturated to min and max values.
    52             *
    53             * \param position position to display the QSpinBox
    54             * \param name name
    55             * \param suffix suffix for the value (eg unit)
    56             * \param min minimum value
    57             * \param max maximum value
    58             * \param step step
    59             * \param default_value default value if not in the xml config file
    60             */
    61             SpinBox(const LayoutPosition* position,std::string name,std::string suffix,int min,int max,int step,int default_value=0);
     46* \brief Constructor
     47*
     48* Construct a QSpinBox at given position. \n
     49* The QSpinBox is saturated to min and max values.
     50*
     51* \param position position to display the QSpinBox
     52* \param name name
     53* \param suffix suffix for the value (eg unit)
     54* \param min minimum value
     55* \param max maximum value
     56* \param step step
     57* \param default_value default value if not in the xml config file
     58*/
     59  SpinBox(const LayoutPosition *position, std::string name, std::string suffix,
     60          int min, int max, int step, int default_value = 0);
    6261
    63             /*!
    64             * \brief Destructor
    65             *
    66             */
    67             ~SpinBox();
     62  /*!
     63  * \brief Destructor
     64  *
     65  */
     66  ~SpinBox();
    6867
    69            /*!
    70             * \brief Value
    71             *
    72             * \return value
    73             */
    74             int Value(void) const;
     68  /*!
     69   * \brief Value
     70   *
     71   * \return value
     72   */
     73  int Value(void) const;
    7574
    76         private:
    77             /*!
    78             * \brief XmlEvent from ground station
    79             *
    80             * Reimplemented from Widget.
    81             *
    82             */
    83             void XmlEvent(void);
     75private:
     76  /*!
     77  * \brief XmlEvent from ground station
     78  *
     79  * Reimplemented from Widget.
     80  *
     81  */
     82  void XmlEvent(void);
    8483
    85             int box_value;
    86     };
     84  int box_value;
     85};
    8786
    8887} // end namespace gui
  • trunk/include/FlairCore/Tab.h

    r2 r13  
    1616#include <Layout.h>
    1717
    18 namespace flair
    19 {
    20 namespace gui
    21 {
     18namespace flair {
     19namespace gui {
    2220
    23     class TabWidget;
     21class TabWidget;
    2422
    25     /*! \class Tab
    26     *
    27     * \brief Class displaying a QTab on the ground station
    28     *
    29     * Tabs are displayed in a TabWidget.
    30     */
    31     class Tab: public Layout
    32     {
    33         public:
    34             /*!
    35             * \brief Constructor
    36             *
    37             * Construct a Tab in the TabWidget.
    38             *
    39             * \param parent parent
    40             * \param name name
    41             * \param position tab position, -1 to put at the last position
    42             */
    43             Tab(const TabWidget* parent,std::string name,int position=-1);
     23/*! \class Tab
     24*
     25* \brief Class displaying a QTab on the ground station
     26*
     27* Tabs are displayed in a TabWidget.
     28*/
     29class Tab : public Layout {
     30public:
     31  /*!
     32  * \brief Constructor
     33  *
     34  * Construct a Tab in the TabWidget.
     35  *
     36  * \param parent parent
     37  * \param name name
     38  * \param position tab position, -1 to put at the last position
     39  */
     40  Tab(const TabWidget *parent, std::string name, int position = -1);
    4441
    45             /*!
    46             * \brief Destructor
    47             *
    48             */
    49             ~Tab();
     42  /*!
     43  * \brief Destructor
     44  *
     45  */
     46  ~Tab();
    5047
    51         private:
    52     };
     48private:
     49};
    5350
    5451} // end namespace gui
  • trunk/include/FlairCore/TabWidget.h

    r2 r13  
    1616#include <Widget.h>
    1717
    18 namespace flair
    19 {
    20 namespace gui
    21 {
    22     class LayoutPosition;
     18namespace flair {
     19namespace gui {
     20class LayoutPosition;
    2321
    24     /*! \class TabWidget
    25     *
    26     * \brief Class displaying a QTabWidget on the ground station
    27     *
    28     * TabWidget contains Tabs.
    29     *
    30     */
    31     class TabWidget:public Widget
    32     {
    33         public:
    34             /*!
    35             * \enum TabPosition_t
    36             * \brief Position of tabs
    37             */
    38             typedef enum { North/*! north */, South/*! south */, West/*! west */, East/*! east */} TabPosition_t;
     22/*! \class TabWidget
     23*
     24* \brief Class displaying a QTabWidget on the ground station
     25*
     26* TabWidget contains Tabs.
     27*
     28*/
     29class TabWidget : public Widget {
     30public:
     31  /*!
     32  * \enum TabPosition_t
     33  * \brief Position of tabs
     34  */
     35  typedef enum {
     36    North /*! north */,
     37    South /*! south */,
     38    West /*! west */,
     39    East /*! east */
     40  } TabPosition_t;
    3941
    40             /*!
    41             * \brief Constructor
    42             *
    43             * Construct a QTabWidget at given position. \n
    44             * The TabWidget will automatically be child of position->getLayout() Layout. After calling this constructor,
    45             * position will be deleted as it is no longer usefull.
    46             *
    47             * \param position position
    48             * \param name name
    49             * \param tabPosition position of tabs
    50             */
    51             TabWidget(const LayoutPosition* position,std::string name,TabPosition_t tabPosition=TabWidget::West);
     42  /*!
     43  * \brief Constructor
     44  *
     45  * Construct a QTabWidget at given position. \n
     46  * The TabWidget will automatically be child of position->getLayout() Layout.
     47  *After calling this constructor,
     48  * position will be deleted as it is no longer usefull.
     49  *
     50  * \param position position
     51  * \param name name
     52  * \param tabPosition position of tabs
     53  */
     54  TabWidget(const LayoutPosition *position, std::string name,
     55            TabPosition_t tabPosition = TabWidget::West);
    5256
    53             /*!
    54             * \brief Destructor
    55             *
    56             */
    57             ~TabWidget();
     57  /*!
     58  * \brief Destructor
     59  *
     60  */
     61  ~TabWidget();
    5862
    59         private:
    60     };
     63private:
     64};
    6165
    6266} // end namespace core
  • trunk/include/FlairCore/TcpSocket.h

    r2 r13  
    1616#include <ConnectedSocket.h>
    1717
    18 namespace flair
    19 {
    20 namespace core
    21 {
    22     /*! \class TcpSocket
    23     *
    24     * \brief Class encapsulating a TCP socket
    25     *
    26     */
    27     class TcpSocket:public ConnectedSocket {
    28     public:
    29         TcpSocket(const Object* parent,const std::string name,bool blockOnSend=false,bool blockOnReceive=true);
    30         ~TcpSocket();
    31         void Listen(const unsigned int port,const std::string localAddress="ANY");
    32         TcpSocket *Accept(Time timeout=0); //should throw an exception if not a listening socket
    33         bool Connect(const unsigned int distantPort,const std::string distantAddress,Time timeout=0); // timeout in milliseconds
    34         ssize_t SendMessage(const char* message,size_t message_len,Time timeout=0); // timeout in milliseconds
    35         ssize_t RecvMessage(char* buf,size_t buf_len,Time timeout=0); // timeout in milliseconds
     18namespace flair {
     19namespace core {
     20/*! \class TcpSocket
     21*
     22* \brief Class encapsulating a TCP socket
     23*
     24*/
     25class TcpSocket : public ConnectedSocket {
     26public:
     27  TcpSocket(const Object *parent, const std::string name,
     28            bool blockOnSend = false, bool blockOnReceive = true);
     29  ~TcpSocket();
     30  void Listen(const unsigned int port, const std::string localAddress = "ANY");
     31  TcpSocket *Accept(
     32      Time timeout = 0); // should throw an exception if not a listening socket
     33  bool Connect(const unsigned int distantPort, const std::string distantAddress,
     34               Time timeout = 0); // timeout in milliseconds
     35  ssize_t SendMessage(const char *message, size_t message_len,
     36                      Time timeout = 0); // timeout in milliseconds
     37  ssize_t RecvMessage(char *buf, size_t buf_len,
     38                      Time timeout = 0); // timeout in milliseconds
    3639
    37         uint16_t NetworkToHost16(uint16_t data);
    38         uint16_t HostToNetwork16(uint16_t data);
    39         uint32_t NetworkToHost32(uint32_t data);
    40         uint32_t HostToNetwork32(uint32_t data);
     40  uint16_t NetworkToHost16(uint16_t data);
     41  uint16_t HostToNetwork16(uint16_t data);
     42  uint32_t NetworkToHost32(uint32_t data);
     43  uint32_t HostToNetwork32(uint32_t data);
    4144
    42     private:
    43         int socket; // socket file descriptor
    44         bool blockOnSend;
    45         bool blockOnReceive;
    46         bool isConnected;
    47         unsigned int distantPort;
    48         std::string distantAddress;
    49     };
     45private:
     46  int socket; // socket file descriptor
     47  bool blockOnSend;
     48  bool blockOnReceive;
     49  bool isConnected;
     50  unsigned int distantPort;
     51  std::string distantAddress;
     52};
    5053
    5154} // end namespace core
  • trunk/include/FlairCore/TextEdit.h

    r2 r13  
    1616#include <Widget.h>
    1717
    18 namespace flair
    19 {
    20 namespace gui
    21 {
     18namespace flair {
     19namespace gui {
    2220
    23     class LayoutPosition;
     21class LayoutPosition;
    2422
    25     /*! \class TextEdit
    26     *
    27     * \brief Class displaying a QTextEdit on the ground station
    28     *
    29     * QTextEdit allows printing on multiple lines. \n
    30     *
    31     */
    32     class TextEdit:public Widget
    33     {
    34         public:
    35             /*!
    36             * \brief Constructor
    37             *
    38             * Construct a QTabWidget at given position. \n
    39             * The TextEdit will automatically be child of position->getLayout() Layout. After calling this constructor,
    40             * position will be deleted as it is no longer usefull.
    41             *
    42             * \param parent parent
    43             * \param name name
    44             * \param buf_size size of the text buffer
    45             */
    46             TextEdit(const LayoutPosition* position,std::string name,size_t buf_size=255);
     23/*! \class TextEdit
     24*
     25* \brief Class displaying a QTextEdit on the ground station
     26*
     27* QTextEdit allows printing on multiple lines. \n
     28*
     29*/
     30class TextEdit : public Widget {
     31public:
     32  /*!
     33  * \brief Constructor
     34  *
     35  * Construct a QTabWidget at given position. \n
     36  * The TextEdit will automatically be child of position->getLayout() Layout.
     37  *After calling this constructor,
     38  * position will be deleted as it is no longer usefull.
     39  *
     40  * \param parent parent
     41  * \param name name
     42  * \param buf_size size of the text buffer
     43  */
     44  TextEdit(const LayoutPosition *position, std::string name,
     45           size_t buf_size = 255);
    4746
    48             /*!
    49             * \brief Destructor
    50             *
    51             */
    52             ~TextEdit();
     47  /*!
     48  * \brief Destructor
     49  *
     50  */
     51  ~TextEdit();
    5352
    54             /*!
    55             * \brief Append a line
    56             *
    57             * \param format text string to display, see standard printf
    58             */
    59             void Append(const char * format, ...);
     53  /*!
     54  * \brief Append a line
     55  *
     56  * \param format text string to display, see standard printf
     57  */
     58  void Append(const char *format, ...);
    6059
    61         private:
    62             char* printf_buffer;
    63             xmlNodePtr text_node;
    64     };
     60private:
     61  char *printf_buffer;
     62  xmlNodePtr text_node;
     63};
    6564
    6665} // end namespace gui
  • trunk/include/FlairCore/Thread.h

    r2 r13  
    1919class Thread_impl;
    2020
    21 namespace flair
    22 {
    23 namespace core
    24 {
    25 
    26     class IODevice;
    27 
    28     /*! \class Thread
    29     *
    30     * \brief Abstract class for a thread
    31     *
    32     * To implement a thread, Run() method must be reimplemented. \n
    33     * When Start() is called, it will automatically call Run() reimplemented method.
    34     * A thread can be periodic, in this case WaitPeriod() will block untill period is met.
    35     * Thread can also e synnchronized with an IODevice, using WaitUpdate() method. \n
    36     * Thread period is by default 100ms.
    37     */
    38     class Thread: public Object
    39     {
    40         friend class ::Thread_impl;
    41 
    42         public:
    43             /*!
    44             * \brief Constructor
    45             *
    46             * \param parent parent
    47             * \param name name
    48             * \param priority priority, should be >20 (<20 is reserved for internal use)
    49             */
    50             Thread(const Object* parent,std::string name,uint8_t priority);//priority>20, for real time only
    51 
    52             /*!
    53             * \brief Destructor
    54             *
    55             * If thread is started, SafeStop() and Join() will
    56             * be automatically called.
    57             *
    58             */
    59             virtual ~Thread();
    60 
    61             /*!
    62             * \brief Start the thread
    63             *
    64             */
    65             void Start(void);
    66 
    67             /*!
    68             * \brief Set a stop flag
    69             *
    70             * ToBeStopped() will return true after calling this method.
    71             */
    72             void SafeStop(void);
    73 
    74             /*!
    75             * \brief Set a stop flag
    76             *
    77             * Reimplemented Run() can poll this method to
    78             * determine when to stop the thread.
    79             *
    80             * \return true if SafeStop() was called
    81             */
    82             bool ToBeStopped(void) const;
    83 
    84             /*!
    85             * \brief Join the thread
    86             *
    87             * This method will block untill Run() returns.
    88             *
    89             */
    90             void Join(void);
    91 
    92             /*!
    93             * \brief Set the period in micro second
    94             *
    95             * After calling this method, IsPeriodSet will return true.
    96             *
    97             * \param period_us period in us
    98             */
    99             void SetPeriodUS(uint32_t period_us);
    100 
    101             uint32_t GetPeriodUS() const;
    102 
    103             /*!
    104             * \brief Set the period in milli second
    105             *
    106             * After calling this method, IsPeriodSet will return true.
    107             *
    108             * \param period_ums period in ms
    109             */
    110             void SetPeriodMS(uint32_t period_ms);
    111 
    112             uint32_t GetPeriodMS() const;
    113 
    114             /*!
    115             * \brief Returns if period was set
    116             *
    117             * \return true if a period was set using SetPeriodUS or SetPeriodMS
    118             * false otherwise
    119             */
    120             bool IsPeriodSet(void);
    121 
    122             /*!
    123             * \brief Wait the period
    124             *
    125             * This method will block untill period is met. \n
    126             * If no period was set (see SetPeriodUS, SetPeriodMS and IsPeriodSet), this method
    127             * returns immediately.
    128             *
    129             */
    130             void WaitPeriod(void) const;
    131 
    132             /*!
    133             * \brief Wait update of an IODevice
    134             *
    135             * This method will block untill IODevice::ProcessUpdate
    136             * is called. \n
    137             * This method is usefull to synchronize a thread with an IODevice.
    138             *
    139             * \param device IODevice to wait update from
    140             */
    141             int WaitUpdate(const IODevice* device);
    142 
    143             /*!
    144             * \brief Suspend the thread
    145             *
    146             * This method will block untill Resume() is called.
    147             *
    148             */
    149             void Suspend(void);
    150 
    151             /*!
    152             * \brief Suspend the thread with timeout
    153             *
    154             * This method will block until Resume() is called or the absolute date specified occurs
    155             *
    156             * \param date absolute date in ns
    157             * \return true if thread is woken up by a call to Resume, false otherwise
    158             */
    159             bool SuspendUntil(Time date);
    160 
    161             /*!
    162             * \brief Resume the thread
    163             *
    164             * This method will unblock the call to Suspend().
    165             *
    166             */
    167             void Resume(void);
    168 
    169             /*!
    170             * \brief Is the thread suspended?
    171             *
    172             * \return true if thread is suspended
    173             *
    174             */
    175             bool IsSuspended(void) const;
    176 
    177             /*!
    178             * \brief Sleep until absolute time
    179             *
    180             * This method will block untill time is reached.
    181             *
    182             * \param time absolute time
    183             */
    184             void SleepUntil(Time time) const;
    185 
    186             /*!
    187             * \brief Sleep for a certain time in micro second
    188             *
    189             * This method will block untill time is elapsed.
    190             *
    191             * \param time_us time to wait in micro second
    192             */
    193             void SleepUS(uint32_t time_us) const;
    194 
    195             /*!
    196             * \brief Sleep for a cartain time in milli second
    197             *
    198             * This method will block untill time is elapsed.
    199             *
    200             * \param time_ms time to wait in milli second
    201             */
    202             void SleepMS(uint32_t time_ms) const;
    203 
    204             /*!
    205             * \brief Warn if real time / non real time switches occur
    206             *
    207             * If enabled, a message with the call stack will be displayed
    208             * in case of real time / non real time switches. \n
    209             * This method can help to debug application and see if switches occur. \n
    210             * Note that it as no effect if this method is called from the non real time
    211             * Framework library.
    212             *
    213             * \param enable enable or disable warns
    214             */
    215             static void WarnUponSwitches(bool enable);
    216 
    217         private:
    218             /*!
    219             * \brief Run method
    220             *
    221             * This method is automatically called by Start(). \n
    222             * This method must be reimplemented, in order to implement the thread.
    223             *
    224             */
    225             virtual void Run(void)=0;
    226 
    227             class Thread_impl* pimpl_;
    228     };
     21namespace flair {
     22namespace core {
     23
     24class IODevice;
     25
     26/*! \class Thread
     27*
     28* \brief Abstract class for a thread
     29*
     30* To implement a thread, Run() method must be reimplemented. \n
     31* When Start() is called, it will automatically call Run() reimplemented method.
     32* A thread can be periodic, in this case WaitPeriod() will block untill period
     33*is met.
     34* Thread can also e synnchronized with an IODevice, using WaitUpdate() method.
     35*\n
     36* Thread period is by default 100ms.
     37*/
     38class Thread : public Object {
     39  friend class ::Thread_impl;
     40
     41public:
     42  /*!
     43  * \brief Constructor
     44  *
     45  * \param parent parent
     46  * \param name name
     47  * \param priority priority, should be >20 (<20 is reserved for internal use)
     48  */
     49  Thread(const Object *parent, std::string name,
     50         uint8_t priority); // priority>20, for real time only
     51
     52  /*!
     53  * \brief Destructor
     54  *
     55  * If thread is started, SafeStop() and Join() will
     56  * be automatically called.
     57  *
     58  */
     59  virtual ~Thread();
     60
     61  /*!
     62  * \brief Start the thread
     63  *
     64  */
     65  void Start(void);
     66
     67  /*!
     68  * \brief Set a stop flag
     69  *
     70  * ToBeStopped() will return true after calling this method.
     71  */
     72  void SafeStop(void);
     73
     74  /*!
     75  * \brief Set a stop flag
     76  *
     77  * Reimplemented Run() can poll this method to
     78  * determine when to stop the thread.
     79  *
     80  * \return true if SafeStop() was called
     81  */
     82  bool ToBeStopped(void) const;
     83
     84  /*!
     85  * \brief Join the thread
     86  *
     87  * This method will block untill Run() returns.
     88  *
     89  */
     90  void Join(void);
     91
     92  /*!
     93  * \brief Set the period in micro second
     94  *
     95  * After calling this method, IsPeriodSet will return true.
     96  *
     97  * \param period_us period in us
     98  */
     99  void SetPeriodUS(uint32_t period_us);
     100
     101  uint32_t GetPeriodUS() const;
     102
     103  /*!
     104  * \brief Set the period in milli second
     105  *
     106  * After calling this method, IsPeriodSet will return true.
     107  *
     108  * \param period_ums period in ms
     109  */
     110  void SetPeriodMS(uint32_t period_ms);
     111
     112  uint32_t GetPeriodMS() const;
     113
     114  /*!
     115  * \brief Returns if period was set
     116  *
     117  * \return true if a period was set using SetPeriodUS or SetPeriodMS
     118  * false otherwise
     119  */
     120  bool IsPeriodSet(void);
     121
     122  /*!
     123  * \brief Wait the period
     124  *
     125  * This method will block untill period is met. \n
     126  * If no period was set (see SetPeriodUS, SetPeriodMS and IsPeriodSet), this
     127  *method
     128  * returns immediately.
     129  *
     130  */
     131  void WaitPeriod(void) const;
     132
     133  /*!
     134  * \brief Wait update of an IODevice
     135  *
     136  * This method will block untill IODevice::ProcessUpdate
     137  * is called. \n
     138  * This method is usefull to synchronize a thread with an IODevice.
     139  *
     140  * \param device IODevice to wait update from
     141  */
     142  int WaitUpdate(const IODevice *device);
     143
     144  /*!
     145  * \brief Suspend the thread
     146  *
     147  * This method will block untill Resume() is called.
     148  *
     149  */
     150  void Suspend(void);
     151
     152  /*!
     153  * \brief Suspend the thread with timeout
     154  *
     155  * This method will block until Resume() is called or the absolute date
     156  *specified occurs
     157  *
     158  * \param date absolute date in ns
     159  * \return true if thread is woken up by a call to Resume, false otherwise
     160  */
     161  bool SuspendUntil(Time date);
     162
     163  /*!
     164  * \brief Resume the thread
     165  *
     166  * This method will unblock the call to Suspend().
     167  *
     168  */
     169  void Resume(void);
     170
     171  /*!
     172  * \brief Is the thread suspended?
     173  *
     174  * \return true if thread is suspended
     175  *
     176  */
     177  bool IsSuspended(void) const;
     178
     179  /*!
     180  * \brief Sleep until absolute time
     181  *
     182  * This method will block untill time is reached.
     183  *
     184  * \param time absolute time
     185  */
     186  void SleepUntil(Time time) const;
     187
     188  /*!
     189  * \brief Sleep for a certain time in micro second
     190  *
     191  * This method will block untill time is elapsed.
     192  *
     193  * \param time_us time to wait in micro second
     194  */
     195  void SleepUS(uint32_t time_us) const;
     196
     197  /*!
     198  * \brief Sleep for a cartain time in milli second
     199  *
     200  * This method will block untill time is elapsed.
     201  *
     202  * \param time_ms time to wait in milli second
     203  */
     204  void SleepMS(uint32_t time_ms) const;
     205
     206  /*!
     207  * \brief Warn if real time / non real time switches occur
     208  *
     209  * If enabled, a message with the call stack will be displayed
     210  * in case of real time / non real time switches. \n
     211  * This method can help to debug application and see if switches occur. \n
     212  * Note that it as no effect if this method is called from the non real time
     213  * Framework library.
     214  *
     215  * \param enable enable or disable warns
     216  */
     217  static void WarnUponSwitches(bool enable);
     218
     219private:
     220  /*!
     221  * \brief Run method
     222  *
     223  * This method is automatically called by Start(). \n
     224  * This method must be reimplemented, in order to implement the thread.
     225  *
     226  */
     227  virtual void Run(void) = 0;
     228
     229  class Thread_impl *pimpl_;
     230};
    229231
    230232} // end namespace core
  • trunk/include/FlairCore/UdtSocket.h

    r2 r13  
    1818#include <ConnectedSocket.h>
    1919
    20 namespace flair
    21 {
    22 namespace core
    23 {
    24     /*! \class UdtSocket
    25     *
    26     * \brief Class encapsulating a UDT socket
    27     *
    28     */
    29     class UdtSocket:public ConnectedSocket {
    30     public:
    31         UdtSocket(const Object* parent,const std::string name,bool blockOnSend=false,bool blockOnReceive=true);
    32         ~UdtSocket();
    33         void Listen(const unsigned int port,const std::string localAddress="ANY");
    34         UdtSocket *Accept(Time timeout); //should throw an exception if not a listening socket
    35         bool Connect(const unsigned int port,const std::string distantAddress,Time timeout); // /!\ timeout is ignored
    36         ssize_t SendMessage(const char* message,size_t message_len,Time timeout);
    37         ssize_t RecvMessage(char* buf,size_t buf_len,Time timeout);
     20namespace flair {
     21namespace core {
     22/*! \class UdtSocket
     23*
     24* \brief Class encapsulating a UDT socket
     25*
     26*/
     27class UdtSocket : public ConnectedSocket {
     28public:
     29  UdtSocket(const Object *parent, const std::string name,
     30            bool blockOnSend = false, bool blockOnReceive = true);
     31  ~UdtSocket();
     32  void Listen(const unsigned int port, const std::string localAddress = "ANY");
     33  UdtSocket *
     34  Accept(Time timeout); // should throw an exception if not a listening socket
     35  bool Connect(const unsigned int port, const std::string distantAddress,
     36               Time timeout); // /!\ timeout is ignored
     37  ssize_t SendMessage(const char *message, size_t message_len, Time timeout);
     38  ssize_t RecvMessage(char *buf, size_t buf_len, Time timeout);
    3839
    39         uint16_t NetworkToHost16(uint16_t data);
    40         uint16_t HostToNetwork16(uint16_t data);
    41         uint32_t NetworkToHost32(uint32_t data);
    42         uint32_t HostToNetwork32(uint32_t data);
     40  uint16_t NetworkToHost16(uint16_t data);
     41  uint16_t HostToNetwork16(uint16_t data);
     42  uint32_t NetworkToHost32(uint32_t data);
     43  uint32_t HostToNetwork32(uint32_t data);
    4344
    44     private:
    45         UDTSOCKET socket;
    46         bool blockOnSend;
    47         bool blockOnReceive;
    48     };
     45private:
     46  UDTSOCKET socket;
     47  bool blockOnSend;
     48  bool blockOnReceive;
     49};
    4950
    5051} // end namespace core
  • trunk/include/FlairCore/Unix_I2cPort.h

    r2 r13  
    1616#include <I2cPort.h>
    1717
    18 namespace flair
    19 {
    20 namespace core
    21 {
    22     /*! \class Unix_I2cPort
    23     *
    24     * \brief Class for unix serial port
    25     *
    26     */
    27     class Unix_I2cPort: public I2cPort
    28     {
     18namespace flair {
     19namespace core {
     20/*! \class Unix_I2cPort
     21*
     22* \brief Class for unix serial port
     23*
     24*/
     25class Unix_I2cPort : public I2cPort {
    2926
    30         public:
    31             /*!
    32             * \brief Constructor
    33             *
    34             * Construct an unix i2c port
    35             *
    36             * \param parent parent
    37             * \param name name
    38             * \param device serial device (ex /dev/i2c-1)
    39             */
    40             Unix_I2cPort(const Object* parent,std::string port_name,std::string device);
     27public:
     28  /*!
     29  * \brief Constructor
     30  *
     31  * Construct an unix i2c port
     32  *
     33  * \param parent parent
     34  * \param name name
     35  * \param device serial device (ex /dev/i2c-1)
     36  */
     37  Unix_I2cPort(const Object *parent, std::string port_name, std::string device);
    4138
    42             /*!
    43             * \brief Destructor
    44             *
    45             */
    46             ~Unix_I2cPort();
     39  /*!
     40  * \brief Destructor
     41  *
     42  */
     43  ~Unix_I2cPort();
    4744
    48             /*!
    49             * \brief Set slave's address
    50             *
    51             * This method need to be called before any communication.
    52             *
    53             * \param address slave's address
    54             */
    55             int SetSlave(uint16_t address);
     45  /*!
     46  * \brief Set slave's address
     47  *
     48  * This method need to be called before any communication.
     49  *
     50  * \param address slave's address
     51  */
     52  int SetSlave(uint16_t address);
    5653
    57             /*!
    58             * \brief Set RX timeout
    59             *
    60             * Timeout for waiting datas.
    61             *
    62             * \param timeout_ns timeout in nano second
    63             */
    64             void SetRxTimeout(Time timeout_ns);
     54  /*!
     55  * \brief Set RX timeout
     56  *
     57  * Timeout for waiting datas.
     58  *
     59  * \param timeout_ns timeout in nano second
     60  */
     61  void SetRxTimeout(Time timeout_ns);
    6562
    66             /*!
    67             * \brief Set TX timeout
    68             *
    69             * Timeout for waiting an ACK from the slave.
    70             *
    71             * \param timeout_ns timeout in nano second
    72             */
    73             void SetTxTimeout(Time timeout_ns);
     63  /*!
     64  * \brief Set TX timeout
     65  *
     66  * Timeout for waiting an ACK from the slave.
     67  *
     68  * \param timeout_ns timeout in nano second
     69  */
     70  void SetTxTimeout(Time timeout_ns);
    7471
    75             /*!
    76             * \brief Write datas
    77             *
    78             * \param buf pointer to datas
    79             * \param nbyte length of datas
    80             *
    81             * \return amount of written datas
    82             */
    83             ssize_t Write(const void *buf,size_t nbyte);
     72  /*!
     73  * \brief Write datas
     74  *
     75  * \param buf pointer to datas
     76  * \param nbyte length of datas
     77  *
     78  * \return amount of written datas
     79  */
     80  ssize_t Write(const void *buf, size_t nbyte);
    8481
    85             /*!
    86             * \brief Read datas
    87             *
    88             * \param buf pointer to datas
    89             * \param nbyte length of datas
    90             *
    91             * \return amount of read datas
    92             */
    93             ssize_t Read(void *buf,size_t nbyte);
     82  /*!
     83  * \brief Read datas
     84  *
     85  * \param buf pointer to datas
     86  * \param nbyte length of datas
     87  *
     88  * \return amount of read datas
     89  */
     90  ssize_t Read(void *buf, size_t nbyte);
    9491
    95         private:
    96             int fd;
    97     };
     92private:
     93  int fd;
     94};
    9895} // end namespace core
    9996} // end namespace flair
  • trunk/include/FlairCore/Unix_SerialPort.h

    r2 r13  
    1717#include <termios.h> /* POSIX terminal control definitions */
    1818
    19 namespace flair
    20 {
    21 namespace core
    22 {
    23     /*! \class RTDM_I2cPort
    24     *
    25     * \brief Class for unix serial port
    26     *
    27     */
    28     class Unix_SerialPort: public SerialPort
    29     {
     19namespace flair {
     20namespace core {
     21/*! \class RTDM_I2cPort
     22*
     23* \brief Class for unix serial port
     24*
     25*/
     26class Unix_SerialPort : public SerialPort {
    3027
    31         public:
    32             /*!
    33             * \brief Constructor
    34             *
    35             * Construct an unix serial port, with the following default values: \n
    36             * - 115200bps baudrate
    37             *
    38             * \param parent parent
    39             * \param name name
    40             * \param device serial device (ex rtser1)
    41             */
    42             Unix_SerialPort(const Object* parent,std::string port_name,std::string device);
     28public:
     29  /*!
     30  * \brief Constructor
     31  *
     32  * Construct an unix serial port, with the following default values: \n
     33  * - 115200bps baudrate
     34  *
     35  * \param parent parent
     36  * \param name name
     37  * \param device serial device (ex rtser1)
     38  */
     39  Unix_SerialPort(const Object *parent, std::string port_name,
     40                  std::string device);
    4341
    44             /*!
    45             * \brief Destructor
    46             *
    47             */
    48             ~Unix_SerialPort();
     42  /*!
     43  * \brief Destructor
     44  *
     45  */
     46  ~Unix_SerialPort();
    4947
    50             /*!
    51             * \brief Set baudrate
    52             *
    53             * \param baudrate baudrate
    54             *
    55             */
    56             void SetBaudrate(int baudrate);
     48  /*!
     49  * \brief Set baudrate
     50  *
     51  * \param baudrate baudrate
     52  *
     53  */
     54  void SetBaudrate(int baudrate);
    5755
    58             /*!
    59             * \brief Set RX timeout
    60             *
    61             * Timeout for waiting datas.
    62             *
    63             * \param timeout_ns timeout in nano second
    64             */
    65             void SetRxTimeout(Time timeout_ns);
     56  /*!
     57  * \brief Set RX timeout
     58  *
     59  * Timeout for waiting datas.
     60  *
     61  * \param timeout_ns timeout in nano second
     62  */
     63  void SetRxTimeout(Time timeout_ns);
    6664
    67             /*!
    68             * \brief Write datas
    69             *
    70             * \param buf pointer to datas
    71             * \param nbyte length of datas
    72             *
    73             * \return amount of written datas
    74             */
    75             ssize_t Write(const void *buf,size_t nbyte);
     65  /*!
     66  * \brief Write datas
     67  *
     68  * \param buf pointer to datas
     69  * \param nbyte length of datas
     70  *
     71  * \return amount of written datas
     72  */
     73  ssize_t Write(const void *buf, size_t nbyte);
    7674
    77             /*!
    78             * \brief Read datas
    79             *
    80             * \param buf pointer to datas
    81             * \param nbyte length of datas
    82             *
    83             * \return amount of read datas
    84             */
    85             ssize_t Read(void *buf,size_t nbyte);
     75  /*!
     76  * \brief Read datas
     77  *
     78  * \param buf pointer to datas
     79  * \param nbyte length of datas
     80  *
     81  * \return amount of read datas
     82  */
     83  ssize_t Read(void *buf, size_t nbyte);
    8684
    87             /*!
    88             * \brief Flush input datas
    89             *
    90             */
    91             void FlushInput(void);
     85  /*!
     86  * \brief Flush input datas
     87  *
     88  */
     89  void FlushInput(void);
    9290
    93         private:
    94             int fd;
    95             struct termios options;
    96     };
     91private:
     92  int fd;
     93  struct termios options;
     94};
    9795} // end namespace core
    9896} // end namespace flair
  • trunk/include/FlairCore/Vector2D.h

    r2 r13  
    1414#define VECTOR2D_H
    1515
    16 namespace flair { namespace core {
     16namespace flair {
     17namespace core {
    1718
    18     /*! \class Vector2D
    19     *
    20     * \brief Class defining a 2D vector
    21     */
    22     class Vector2D {
    23         public:
    24             /*!
    25             * \brief Constructor
    26             *
    27             * Construct a Vector2D using specified values.
    28             *
    29             * \param x
    30             * \param y
    31             */
    32             Vector2D(float x=0,float y=0);
     19/*! \class Vector2D
     20*
     21* \brief Class defining a 2D vector
     22*/
     23class Vector2D {
     24public:
     25  /*!
     26  * \brief Constructor
     27  *
     28  * Construct a Vector2D using specified values.
     29  *
     30  * \param x
     31  * \param y
     32  */
     33  Vector2D(float x = 0, float y = 0);
    3334
    34             /*!
    35             * \brief Destructor
    36             *
    37             */
    38             ~Vector2D();
     35  /*!
     36  * \brief Destructor
     37  *
     38  */
     39  ~Vector2D();
    3940
    40             /*!
    41             * \brief Rotation
    42             *
    43             * \param value rotation value in radians
    44             */
    45             void Rotate(float value);
     41  /*!
     42  * \brief Rotation
     43  *
     44  * \param value rotation value in radians
     45  */
     46  void Rotate(float value);
    4647
    47             /*!
    48             * \brief Rotation
    49             *
    50             * \param value rotation value in degrees
    51             */
    52             void RotateDeg(float value);
     48  /*!
     49  * \brief Rotation
     50  *
     51  * \param value rotation value in degrees
     52  */
     53  void RotateDeg(float value);
    5354
    54             /*!
    55             * \brief Norm
    56             *
    57             * \return value
    58             */
    59             float GetNorm(void) const;
     55  /*!
     56  * \brief Norm
     57  *
     58  * \return value
     59  */
     60  float GetNorm(void) const;
    6061
    61             /*!
    62             * \brief Normalize
    63             */
    64             void Normalize(void);
     62  /*!
     63  * \brief Normalize
     64  */
     65  void Normalize(void);
    6566
    66             /*!
    67             * \brief Saturate
    68             *
    69             * Saturate between min and max
    70             *
    71             * \param min minimum Vector2D value
    72             * \param max maximum Vector2D value
    73             */
    74             void Saturate(Vector2D min,Vector2D max);
     67  /*!
     68  * \brief Saturate
     69  *
     70  * Saturate between min and max
     71  *
     72  * \param min minimum Vector2D value
     73  * \param max maximum Vector2D value
     74  */
     75  void Saturate(Vector2D min, Vector2D max);
    7576
    76             /*!
    77             * \brief Saturate
    78             *
    79             * Saturate between min and max
    80             *
    81             * \param min minimum Vector2D(min,min) value
    82             * \param max maximum Vector2D(max,max) value
    83             */
    84             void Saturate(float min,float max);
     77  /*!
     78  * \brief Saturate
     79  *
     80  * Saturate between min and max
     81  *
     82  * \param min minimum Vector2D(min,min) value
     83  * \param max maximum Vector2D(max,max) value
     84  */
     85  void Saturate(float min, float max);
    8586
    86             /*!
    87             * \brief Saturate
    88             *
    89             * Saturate between -abs(value) and abs(value)
    90             *
    91             * \param value saturation Vector2D value
    92             */
    93             void Saturate(const Vector2D &value);
     87  /*!
     88  * \brief Saturate
     89  *
     90  * Saturate between -abs(value) and abs(value)
     91  *
     92  * \param value saturation Vector2D value
     93  */
     94  void Saturate(const Vector2D &value);
    9495
    95             /*!
    96             * \brief Saturate
    97             *
    98             * Saturate between -abs(Vector2D(value,value)) and abs(Vector2D(value,value))
    99             *
    100             * \param value saturation Vector2D(value,value)
    101             */
    102             void Saturate(float value);
     96  /*!
     97  * \brief Saturate
     98  *
     99  * Saturate between -abs(Vector2D(value,value)) and abs(Vector2D(value,value))
     100  *
     101  * \param value saturation Vector2D(value,value)
     102  */
     103  void Saturate(float value);
    103104
     105  /*!
     106  * \brief x
     107  */
     108  float x;
    104109
    105             /*!
    106             * \brief x
    107             */
    108             float x;
     110  /*!
     111  * \brief y
     112  */
     113  float y;
    109114
    110             /*!
    111             * \brief y
    112             */
    113             float y;
     115  Vector2D &operator=(const Vector2D &vector);
     116};
    114117
    115             Vector2D &operator=(const Vector2D &vector);
    116     };
     118/*! Add
     119*
     120* \brief Add
     121*
     122* \param vectorA vector
     123* \param vectorB vector
     124*/
     125Vector2D operator+(const Vector2D &vectorA, const Vector2D &vectorB);
    117126
    118     /*! Add
    119     *
    120     * \brief Add
    121     *
    122     * \param vectorA vector
    123     * \param vectorB vector
    124     */
    125     Vector2D operator + (const Vector2D &vectorA,const Vector2D &vectorB);
     127/*! Substract
     128*
     129* \brief Substract
     130*
     131* \param vectorA vector
     132* \param vectorB vector
     133*/
     134Vector2D operator-(const Vector2D &vectorA, const Vector2D &vectorB);
    126135
    127     /*! Substract
    128     *
    129     * \brief Substract
    130     *
    131     * \param vectorA vector
    132     * \param vectorB vector
    133     */
    134     Vector2D operator - (const Vector2D &vectorA,const Vector2D &vectorB);
     136/*! Divid
     137*
     138* \brief Divid
     139*
     140* \param vector vector
     141* \param coeff coefficent
     142* \return vector/coefficient
     143*/
     144Vector2D operator/(const Vector2D &vector, float coeff);
    135145
    136     /*! Divid
    137     *
    138     * \brief Divid
    139     *
    140     * \param vector vector
    141     * \param coeff coefficent
    142     * \return vector/coefficient
    143     */
    144     Vector2D operator / (const Vector2D &vector, float coeff);
     146/*! Multiply
     147*
     148* \brief Multiplyf
     149*
     150* \param vector vector
     151* \param coeff coefficent
     152* \return coefficient*vector
     153*/
     154Vector2D operator*(const Vector2D &vector, float coeff);
    145155
    146     /*! Multiply
    147     *
    148     * \brief Multiplyf
    149     *
    150     * \param vector vector
    151     * \param coeff coefficent
    152     * \return coefficient*vector
    153     */
    154     Vector2D operator * (const Vector2D &vector, float coeff);
    155 
    156     /*! Multiply
    157     *
    158     * \brief Multiply
    159     *
    160     * \param coeff coefficent
    161     * \param vector vector
    162     * \return coefficient*vector
    163     */
    164     Vector2D operator * (float coeff,const Vector2D &vector);
     156/*! Multiply
     157*
     158* \brief Multiply
     159*
     160* \param coeff coefficent
     161* \param vector vector
     162* \return coefficient*vector
     163*/
     164Vector2D operator*(float coeff, const Vector2D &vector);
    165165
    166166} // end namespace core
  • trunk/include/FlairCore/Vector3D.h

    r2 r13  
    1616#include <stddef.h>
    1717
    18 namespace flair { namespace core {
    19     class Vector2D;
    20     class RotationMatrix;
    21     class Quaternion;
    22 
    23     /*! \class Vector3D
    24     *
    25     * \brief Class defining a 3D vector
    26     */
    27     class Vector3D {
    28         public:
    29             /*!
    30             * \brief Constructor
    31             *
    32             * Construct a Vector3D using specified values.
    33             *
    34             * \param x
    35             * \param y
    36             * \param z
    37             */
    38             Vector3D(float x=0,float y=0,float z=0);
    39 
    40             /*!
    41             * \brief Destructor
    42             *
    43             */
    44             ~Vector3D();
    45 
    46             /*!
    47             * \brief x
    48             */
    49             float x;
    50 
    51             /*!
    52             * \brief y
    53             */
    54             float y;
    55 
    56             /*!
    57             * \brief z
    58             */
    59             float z;
    60 
    61             /*!
    62             * \brief x axis rotation
    63             *
    64             * \param value rotation value in radians
    65             */
    66             void RotateX(float value);
    67 
    68             /*!
    69             * \brief x axis rotation
    70             *
    71             * \param value rotation value in degrees
    72             */
    73             void RotateXDeg(float value);
    74 
    75             /*!
    76             * \brief y axis rotation
    77             *
    78             * \param value rotation value in radians
    79             */
    80             void RotateY(float value);
    81 
    82             /*!
    83             * \brief y axis rotation
    84             *
    85             * \param value rotation value in degrees
    86             */
    87             void RotateYDeg(float value);
    88 
    89             /*!
    90             * \brief z axis rotation
    91             *
    92             * \param value rotation value in radians
    93             */
    94             void RotateZ(float value);
    95 
    96             /*!
    97             * \brief z axis rotation
    98             *
    99             * \param value rotation value in degrees
    100             */
    101             void RotateZDeg(float value);
    102 
    103             /*!
    104             * \brief rotation
    105             *
    106             * \param matrix rotation matrix
    107             */
    108             void Rotate(const RotationMatrix &matrix);
    109 
    110             /*!
    111             * \brief rotation
    112             *
    113             * Compute a rotation from a quaternion. This method uses a rotation matrix
    114             * internaly.
    115             *
    116             * \param quaternion quaternion
    117             */
    118             void Rotate(const Quaternion &quaternion);
    119 
    120             /*!
    121             * \brief Convert to a Vector2D
    122             *
    123             * Uses x and y coordinates.
    124             *
    125             * \param vector destination
    126             */
    127             void To2Dxy(Vector2D &vector) const;
    128 
    129             /*!
    130             * \brief Convert to a Vector2D
    131             *
    132             * Uses x and y coordinates.
    133             *
    134             * \return destination
    135             */
    136             Vector2D To2Dxy(void) const;
    137 
    138             /*!
    139             * \brief Norm
    140             *
    141             * \return value
    142             */
    143             float GetNorm(void) const;
    144 
    145             /*!
    146             * \brief Normalize
    147             */
    148             void Normalize(void);
    149 
    150             /*!
    151             * \brief Saturate
    152             *
    153             * Saturate between min and max
    154             *
    155             * \param min minimum value
    156             * \param max maximum value
    157             */
    158             void Saturate(const Vector3D &min,const Vector3D &max);
    159 
    160             /*!
    161             * \brief Saturate
    162             *
    163             * Saturate between min and max
    164             *
    165             * \param min minimum Vector3D(min,min,min) value
    166             * \param max maximum Vector3D(max,max,max) value
    167             */
    168             void Saturate(float min,float max);
    169 
    170             /*!
    171             * \brief Saturate
    172             *
    173             * Saturate between -abs(value) and abs(value)
    174             *
    175             * \param value saturation Vector3D value
    176             */
    177             void Saturate(const Vector3D &value);
    178 
    179             /*!
    180             * \brief Saturate
    181             *
    182             * Saturate between -abs(Vector3D(value,value,value)) and abs(Vector3D(value,value,value))
    183             *
    184             * \param value saturation Vector3D(value,value,value)
    185             */
    186             void Saturate(float value);
    187 
    188             float &operator[](size_t idx);
    189             const float &operator[](size_t idx) const;
    190             Vector3D &operator=(const Vector3D& vector);
    191             Vector3D &operator+=(const Vector3D& vector);
    192             Vector3D &operator-=(const Vector3D& vector);
    193 
    194         private:
    195 
    196     };
    197 
    198     /*! Add
    199     *
    200     * \brief Add
    201     *
    202     * \param vectorA vector
    203     * \param vectorB vector
    204     *
    205     * \return vectorA+vectorB
    206     */
    207     Vector3D operator + (const Vector3D &vectorA,const Vector3D &vectorB);
    208 
    209     /*! Substract
    210     *
    211     * \brief Substract
    212     *
    213     * \param vectorA vector
    214     * \param vectorB vector
    215     *
    216     * \return vectorA-vectorB
    217     */
    218     Vector3D operator - (const Vector3D &vectorA,const Vector3D &vectorB);
    219 
    220     /*! Minus
    221     *
    222     * \brief Minus
    223     *
    224     * \param vector vector
    225     *
    226     * \return -vector
    227     */
    228     Vector3D operator-(const Vector3D &vector);
    229 
    230     /*! Divid
    231     *
    232     * \brief Divid
    233     *
    234     * \param vector vector
    235     * \param coeff coefficent
    236     *
    237     * \return vector/coefficient
    238     */
    239     Vector3D operator / (const Vector3D &vector, float coeff);
    240 
    241     /*! Hadamard product
    242     *
    243     * \brief Hadamard product
    244     *
    245     * \param vectorA vector
    246     * \param vectorBA vector
    247     *
    248     * \return Hadamard product
    249     */
    250     Vector3D operator * (const Vector3D &vectorA, const Vector3D &vectorB);
    251 
    252     /*! Multiply
    253     *
    254     * \brief Multiply
    255     *
    256     * \param vector vector
    257     * \param coeff coefficent
    258     *
    259     * \return coefficient*vector
    260     */
    261     Vector3D operator * (const Vector3D &vector, float coeff);
    262 
    263     /*! Multiply
    264     *
    265     * \brief Multiply
    266     *
    267     * \param coeff coefficent
    268     * \param vector vector
    269     *
    270     * \return coefficient*vector
    271     */
    272     Vector3D operator * (float coeff, const Vector3D &vector);
    273 
    274     /*! Cross product
    275     *
    276     * \brief Cross product
    277     *
    278     * \param vectorA first vector
    279     * \param vectorB second vector
    280     *
    281     * \return cross product
    282     */
    283     Vector3D CrossProduct(const Vector3D &vectorA, const Vector3D &vectorB);
    284 
    285     /*! Dot product
    286     *
    287     * \brief Dot product
    288     *
    289     * \param vectorA first vector
    290     * \param vectorB second vector
    291     *
    292     * \return dot product
    293     */
    294     float DotProduct(const Vector3D &vectorA, const Vector3D &vectorB);
     18namespace flair {
     19namespace core {
     20class Vector2D;
     21class RotationMatrix;
     22class Quaternion;
     23
     24/*! \class Vector3D
     25*
     26* \brief Class defining a 3D vector
     27*/
     28class Vector3D {
     29public:
     30  /*!
     31  * \brief Constructor
     32  *
     33  * Construct a Vector3D using specified values.
     34  *
     35  * \param x
     36  * \param y
     37  * \param z
     38  */
     39  Vector3D(float x = 0, float y = 0, float z = 0);
     40
     41  /*!
     42  * \brief Destructor
     43  *
     44  */
     45  ~Vector3D();
     46
     47  /*!
     48  * \brief x
     49  */
     50  float x;
     51
     52  /*!
     53  * \brief y
     54  */
     55  float y;
     56
     57  /*!
     58  * \brief z
     59  */
     60  float z;
     61
     62  /*!
     63  * \brief x axis rotation
     64  *
     65  * \param value rotation value in radians
     66  */
     67  void RotateX(float value);
     68
     69  /*!
     70  * \brief x axis rotation
     71  *
     72  * \param value rotation value in degrees
     73  */
     74  void RotateXDeg(float value);
     75
     76  /*!
     77  * \brief y axis rotation
     78  *
     79  * \param value rotation value in radians
     80  */
     81  void RotateY(float value);
     82
     83  /*!
     84  * \brief y axis rotation
     85  *
     86  * \param value rotation value in degrees
     87  */
     88  void RotateYDeg(float value);
     89
     90  /*!
     91  * \brief z axis rotation
     92  *
     93  * \param value rotation value in radians
     94  */
     95  void RotateZ(float value);
     96
     97  /*!
     98  * \brief z axis rotation
     99  *
     100  * \param value rotation value in degrees
     101  */
     102  void RotateZDeg(float value);
     103
     104  /*!
     105  * \brief rotation
     106  *
     107  * \param matrix rotation matrix
     108  */
     109  void Rotate(const RotationMatrix &matrix);
     110
     111  /*!
     112  * \brief rotation
     113  *
     114  * Compute a rotation from a quaternion. This method uses a rotation matrix
     115  * internaly.
     116  *
     117  * \param quaternion quaternion
     118  */
     119  void Rotate(const Quaternion &quaternion);
     120
     121  /*!
     122  * \brief Convert to a Vector2D
     123  *
     124  * Uses x and y coordinates.
     125  *
     126  * \param vector destination
     127  */
     128  void To2Dxy(Vector2D &vector) const;
     129
     130  /*!
     131  * \brief Convert to a Vector2D
     132  *
     133  * Uses x and y coordinates.
     134  *
     135  * \return destination
     136  */
     137  Vector2D To2Dxy(void) const;
     138
     139  /*!
     140  * \brief Norm
     141  *
     142  * \return value
     143  */
     144  float GetNorm(void) const;
     145
     146  /*!
     147  * \brief Normalize
     148  */
     149  void Normalize(void);
     150
     151  /*!
     152  * \brief Saturate
     153  *
     154  * Saturate between min and max
     155  *
     156  * \param min minimum value
     157  * \param max maximum value
     158  */
     159  void Saturate(const Vector3D &min, const Vector3D &max);
     160
     161  /*!
     162  * \brief Saturate
     163  *
     164  * Saturate between min and max
     165  *
     166  * \param min minimum Vector3D(min,min,min) value
     167  * \param max maximum Vector3D(max,max,max) value
     168  */
     169  void Saturate(float min, float max);
     170
     171  /*!
     172  * \brief Saturate
     173  *
     174  * Saturate between -abs(value) and abs(value)
     175  *
     176  * \param value saturation Vector3D value
     177  */
     178  void Saturate(const Vector3D &value);
     179
     180  /*!
     181  * \brief Saturate
     182  *
     183  * Saturate between -abs(Vector3D(value,value,value)) and
     184  *abs(Vector3D(value,value,value))
     185  *
     186  * \param value saturation Vector3D(value,value,value)
     187  */
     188  void Saturate(float value);
     189
     190  float &operator[](size_t idx);
     191  const float &operator[](size_t idx) const;
     192  Vector3D &operator=(const Vector3D &vector);
     193  Vector3D &operator+=(const Vector3D &vector);
     194  Vector3D &operator-=(const Vector3D &vector);
     195
     196private:
     197};
     198
     199/*! Add
     200*
     201* \brief Add
     202*
     203* \param vectorA vector
     204* \param vectorB vector
     205*
     206* \return vectorA+vectorB
     207*/
     208Vector3D operator+(const Vector3D &vectorA, const Vector3D &vectorB);
     209
     210/*! Substract
     211*
     212* \brief Substract
     213*
     214* \param vectorA vector
     215* \param vectorB vector
     216*
     217* \return vectorA-vectorB
     218*/
     219Vector3D operator-(const Vector3D &vectorA, const Vector3D &vectorB);
     220
     221/*! Minus
     222*
     223* \brief Minus
     224*
     225* \param vector vector
     226*
     227* \return -vector
     228*/
     229Vector3D operator-(const Vector3D &vector);
     230
     231/*! Divid
     232*
     233* \brief Divid
     234*
     235* \param vector vector
     236* \param coeff coefficent
     237*
     238* \return vector/coefficient
     239*/
     240Vector3D operator/(const Vector3D &vector, float coeff);
     241
     242/*! Hadamard product
     243*
     244* \brief Hadamard product
     245*
     246* \param vectorA vector
     247* \param vectorBA vector
     248*
     249* \return Hadamard product
     250*/
     251Vector3D operator*(const Vector3D &vectorA, const Vector3D &vectorB);
     252
     253/*! Multiply
     254*
     255* \brief Multiply
     256*
     257* \param vector vector
     258* \param coeff coefficent
     259*
     260* \return coefficient*vector
     261*/
     262Vector3D operator*(const Vector3D &vector, float coeff);
     263
     264/*! Multiply
     265*
     266* \brief Multiply
     267*
     268* \param coeff coefficent
     269* \param vector vector
     270*
     271* \return coefficient*vector
     272*/
     273Vector3D operator*(float coeff, const Vector3D &vector);
     274
     275/*! Cross product
     276*
     277* \brief Cross product
     278*
     279* \param vectorA first vector
     280* \param vectorB second vector
     281*
     282* \return cross product
     283*/
     284Vector3D CrossProduct(const Vector3D &vectorA, const Vector3D &vectorB);
     285
     286/*! Dot product
     287*
     288* \brief Dot product
     289*
     290* \param vectorA first vector
     291* \param vectorB second vector
     292*
     293* \return dot product
     294*/
     295float DotProduct(const Vector3D &vectorA, const Vector3D &vectorB);
    295296
    296297} // end namespace core
  • trunk/include/FlairCore/Vector3DSpinBox.h

    r2 r13  
    1717#include <Vector3D.h>
    1818
    19 namespace flair { namespace gui {
    20     class Layout;
     19namespace flair {
     20namespace gui {
     21class Layout;
    2122
    22     /*! \class Vector3DSpinBox
    23     *
    24     * \brief Class displaying 3 QDoubleSpinBox for x,y,z on the ground station
    25     *
    26     */
    27     class Vector3DSpinBox: public Box {
    28         public:
    29             /*!
    30             * \brief Constructor
    31             *
    32             * Construct a Vector3DSpinBox at given position. \n
    33             * Each DoubleSpinBox is saturated to min and max values.
    34             *
    35             * \param position position to display the Vector3DSpinBox
    36             * \param name name
    37             * \param min minimum value
    38             * \param max maximum value
    39             * \param step step
    40             * \param decimals number of decimals
    41             * \param default_value default value if not in the xml config file
    42             */
    43             Vector3DSpinBox(const LayoutPosition* position,std::string name,double min,double max,double step,int decimals=2,core::Vector3D default_value=core::Vector3D(0,0,0));
     23/*! \class Vector3DSpinBox
     24*
     25* \brief Class displaying 3 QDoubleSpinBox for x,y,z on the ground station
     26*
     27*/
     28class Vector3DSpinBox : public Box {
     29public:
     30  /*!
     31  * \brief Constructor
     32  *
     33  * Construct a Vector3DSpinBox at given position. \n
     34  * Each DoubleSpinBox is saturated to min and max values.
     35  *
     36  * \param position position to display the Vector3DSpinBox
     37  * \param name name
     38  * \param min minimum value
     39  * \param max maximum value
     40  * \param step step
     41  * \param decimals number of decimals
     42  * \param default_value default value if not in the xml config file
     43  */
     44  Vector3DSpinBox(const LayoutPosition *position, std::string name, double min,
     45                  double max, double step, int decimals = 2,
     46                  core::Vector3D default_value = core::Vector3D(0, 0, 0));
    4447
    45             /*!
    46             * \brief Destructor
    47             *
    48             */
    49             ~Vector3DSpinBox();
     48  /*!
     49  * \brief Destructor
     50  *
     51  */
     52  ~Vector3DSpinBox();
    5053
    51             /*!
    52             * \brief Value
    53             *
    54             * \return value
    55             */
    56             core::Vector3D Value(void) const;
    57             //operator core::Vector3D() const;
    58         private:
    59             /*!
    60             * \brief XmlEvent from ground station
    61             *
    62             * Reimplemented from Widget.
    63             *
    64             */
    65             void XmlEvent(void);
     54  /*!
     55  * \brief Value
     56  *
     57  * \return value
     58  */
     59  core::Vector3D Value(void) const;
     60  // operator core::Vector3D() const;
     61private:
     62  /*!
     63  * \brief XmlEvent from ground station
     64  *
     65  * Reimplemented from Widget.
     66  *
     67  */
     68  void XmlEvent(void);
    6669
    67             core::Vector3D box_value;
    68     };
     70  core::Vector3D box_value;
     71};
    6972
    7073} // end namespace gui
  • trunk/include/FlairCore/Vector3Ddata.h

    r2 r13  
    1818#include <Vector3D.h>
    1919
    20 namespace flair
    21 {
    22 namespace core
    23 {
     20namespace flair {
     21namespace core {
    2422
    25     /*! \class Vector3Ddata
    26     *
    27     * \brief Class defining a 3D vector and a io_data
    28     * User must manually use the io_data's Mutex to access to Vector3D values.
    29     */
    30     class Vector3Ddata: public io_data, public Vector3D
    31     {
    32         public:
    33             /*!
    34             * \brief Constructor
    35             *
    36             * Construct a Vector3D using specified values.
    37             *
    38             * \param x
    39             * \param y
    40             * \param z
    41             */
    42             Vector3Ddata(const Object* parent, std::string name,float x=0,float y=0,float z=0,uint32_t n=1);
     23/*! \class Vector3Ddata
     24*
     25* \brief Class defining a 3D vector and a io_data
     26* User must manually use the io_data's Mutex to access to Vector3D values.
     27*/
     28class Vector3Ddata : public io_data, public Vector3D {
     29public:
     30  /*!
     31  * \brief Constructor
     32  *
     33  * Construct a Vector3D using specified values.
     34  *
     35  * \param x
     36  * \param y
     37  * \param z
     38  */
     39  Vector3Ddata(const Object *parent, std::string name, float x = 0, float y = 0,
     40               float z = 0, uint32_t n = 1);
    4341
    44             /*!
    45             * \brief Destructor
    46             *
    47             */
    48             ~Vector3Ddata();
     42  /*!
     43  * \brief Destructor
     44  *
     45  */
     46  ~Vector3Ddata();
    4947
    50             /*!
    51             * \brief X Element
    52             *
    53             * Get a vectorer to x element. This pointer can be used for plotting.
    54             *
    55             * \return pointer to the element
    56             */
    57             IODataElement* XElement(void) const;
     48  /*!
     49  * \brief X Element
     50  *
     51  * Get a vectorer to x element. This pointer can be used for plotting.
     52  *
     53  * \return pointer to the element
     54  */
     55  IODataElement *XElement(void) const;
    5856
    59             /*!
    60             * \brief Y Element
    61             *
    62             * Get a pointer to y element. This pointer can be used for plotting.
    63             *
    64             * \return pointer to the element
    65             */
    66             IODataElement* YElement(void) const;
     57  /*!
     58  * \brief Y Element
     59  *
     60  * Get a pointer to y element. This pointer can be used for plotting.
     61  *
     62  * \return pointer to the element
     63  */
     64  IODataElement *YElement(void) const;
    6765
    68             /*!
    69             * \brief Z Element
    70             *
    71             * Get a pointer to z element. This pointer can be used for plotting.
    72             *
    73             * \return pointer to the element
    74             */
    75             IODataElement* ZElement(void) const;
     66  /*!
     67  * \brief Z Element
     68  *
     69  * Get a pointer to z element. This pointer can be used for plotting.
     70  *
     71  * \return pointer to the element
     72  */
     73  IODataElement *ZElement(void) const;
    7674
    77         private:
    78             /*!
    79             * \brief Copy datas
    80             *
    81             * Reimplemented from io_data. \n
    82             * See io_data::CopyDatas.
    83             *
    84             * \param dst destination buffer
    85             */
    86             void CopyDatas(char* dst) const;
    87     };
     75private:
     76  /*!
     77  * \brief Copy datas
     78  *
     79  * Reimplemented from io_data. \n
     80  * See io_data::CopyDatas.
     81  *
     82  * \param dst destination buffer
     83  */
     84  void CopyDatas(char *dst) const;
     85};
    8886
    8987} // end namespace core
  • trunk/include/FlairCore/Watchdog.h

    r2 r13  
    2020namespace core {
    2121
    22     /*! \class Watchdog
    23     *
    24     * \brief Watchdog class
    25     *
    26     * Calls a given function if not touched within a specified period of time
    27     *
    28     */
    29     class Watchdog:public Thread {
    30     public:
    31         Watchdog(const Object* parent,std::function<void()> _expired,Time _timer);
    32         ~Watchdog();
     22/*! \class Watchdog
     23*
     24* \brief Watchdog class
     25*
     26* Calls a given function if not touched within a specified period of time
     27*
     28*/
     29class Watchdog : public Thread {
     30public:
     31  Watchdog(const Object *parent, std::function<void()> _expired, Time _timer);
     32  ~Watchdog();
    3333
    34         //reset the timer
    35         void Touch();
    36         void SetTimer(Time _Timer);
    37     private:
    38         void Run();
    39         std::function<void()> expired;
    40         Time timer;
    41     };
     34  // reset the timer
     35  void Touch();
     36  void SetTimer(Time _Timer);
     37
     38private:
     39  void Run();
     40  std::function<void()> expired;
     41  Time timer;
     42};
    4243
    4344} // end namespace core
  • trunk/include/FlairCore/Widget.h

    r2 r13  
    2121class FrameworkManager_impl;
    2222
    23 namespace flair
    24 {
    25 namespace gui
    26 {
     23namespace flair {
     24namespace gui {
    2725
    28     /*! \class Widget
    29     *
    30     * \brief Abstract class for all Framework's widget classes
    31     *
    32     * A widget is an object to display on the ground station. \n
    33     * Communication with ground station is done through xml files; properties of theses files
    34     * are modified through appropriate method. \n
    35     * A xml file is used for default values of the Widget, if it has been specified in the
    36     *  constructor of the FrameworkManager.
    37     */
    38     class Widget: public core::Object
    39     {
    40         friend class core::FrameworkManager;
    41         friend class ::Widget_impl;
    42         friend class ::FrameworkManager_impl;
     26/*! \class Widget
     27*
     28* \brief Abstract class for all Framework's widget classes
     29*
     30* A widget is an object to display on the ground station. \n
     31* Communication with ground station is done through xml files; properties of
     32*theses files
     33* are modified through appropriate method. \n
     34* A xml file is used for default values of the Widget, if it has been specified
     35*in the
     36*  constructor of the FrameworkManager.
     37*/
     38class Widget : public core::Object {
     39  friend class core::FrameworkManager;
     40  friend class ::Widget_impl;
     41  friend class ::FrameworkManager_impl;
    4342
    44         public:
    45             /*!
    46             * \brief Constructor
    47             *
    48             * Construct a Widget, the xml file specified to the FrameworkManager's
    49             * constructor is sued for default values. \n
    50             * Two Widget with same parent must have different names. If a brother Widget already
    51             * has the same name, the name of the new one will be automatically changed. \n
    52             * Type must agree with predifined (hard coded) types
    53             * in ground station code.
    54             *
    55             * \param parent parent
    56             * \param name name
    57             * \param type type
    58             */
    59             Widget(const Widget* parent,std::string name,std::string type);
     43public:
     44  /*!
     45  * \brief Constructor
     46  *
     47  * Construct a Widget, the xml file specified to the FrameworkManager's
     48  * constructor is sued for default values. \n
     49  * Two Widget with same parent must have different names. If a brother Widget
     50  *already
     51  * has the same name, the name of the new one will be automatically changed. \n
     52  * Type must agree with predifined (hard coded) types
     53  * in ground station code.
     54  *
     55  * \param parent parent
     56  * \param name name
     57  * \param type type
     58  */
     59  Widget(const Widget *parent, std::string name, std::string type);
    6060
    61             /*!
    62             * \brief Destructor
    63             *
    64             */
    65             virtual ~Widget();
     61  /*!
     62  * \brief Destructor
     63  *
     64  */
     65  virtual ~Widget();
    6666
    67             /*!
    68             * \brief Set enabled
    69             *
    70             * Enable or disable the Widget on the ground station. \n
    71             * A disabled widget is greyed out on the ground station
    72             * and in unmodifiable.
    73             *
    74             * \param status
    75             */
    76             void setEnabled(bool status);
     67  /*!
     68  * \brief Set enabled
     69  *
     70  * Enable or disable the Widget on the ground station. \n
     71  * A disabled widget is greyed out on the ground station
     72  * and in unmodifiable.
     73  *
     74  * \param status
     75  */
     76  void setEnabled(bool status);
    7777
    78             /*!
    79             * \brief Is enabled?
    80             *
    81             * \return true if widget is enabled
    82             */
    83             bool isEnabled(void) const;
     78  /*!
     79  * \brief Is enabled?
     80  *
     81  * \return true if widget is enabled
     82  */
     83  bool isEnabled(void) const;
    8484
    85         protected:
    86             /*!
    87             * \brief Set a persistent xml property
    88             *
    89             * The property will be saved in the configuration xml and also used to configure the ground station.
    90             *
    91             * \param prop property to set and save
    92             * \param value value to set and save
    93             */
    94             template <typename T>
    95             void SetPersistentXmlProp(std::string prop,T value);
     85protected:
     86  /*!
     87  * \brief Set a persistent xml property
     88  *
     89  * The property will be saved in the configuration xml and also used to
     90  *configure the ground station.
     91  *
     92  * \param prop property to set and save
     93  * \param value value to set and save
     94  */
     95  template <typename T> void SetPersistentXmlProp(std::string prop, T value);
    9696
    97             /*!
    98             * \brief Get a persistent xml property
    99             *
    100             * Get the property from the xml file. If no corresponding property is found in the xml, value remains unchanged. \n
    101             * Thus value can be initialized with a default value before calling this method.
    102             *
    103             * \param prop property to get
    104             * \param value value to store the result
    105             * \return true if value was changed
    106             */
    107             template <typename T>
    108             bool GetPersistentXmlProp(std::string prop,T &value);
     97  /*!
     98  * \brief Get a persistent xml property
     99  *
     100  * Get the property from the xml file. If no corresponding property is found in
     101  *the xml, value remains unchanged. \n
     102  * Thus value can be initialized with a default value before calling this
     103  *method.
     104  *
     105  * \param prop property to get
     106  * \param value value to store the result
     107  * \return true if value was changed
     108  */
     109  template <typename T> bool GetPersistentXmlProp(std::string prop, T &value);
    109110
    110             /*!
    111             * \brief Set a volatile xml property
    112             *
    113             * This property should be used to configure the ground station (one time init). \n
    114             * The property will be destroyed after calling SendXml() as it should no be used anymore.
    115             *
    116             * \param prop property to set
    117             * \param value value to set
    118             * \param node if sepcified, node to set; otherwise use the node of the Widget
    119             */
    120             template <typename T>
    121             void SetVolatileXmlProp(std::string prop,T value,xmlNodePtr node=NULL);
     111  /*!
     112  * \brief Set a volatile xml property
     113  *
     114  * This property should be used to configure the ground station (one time
     115  *init). \n
     116  * The property will be destroyed after calling SendXml() as it should no be
     117  *used anymore.
     118  *
     119  * \param prop property to set
     120  * \param value value to set
     121  * \param node if sepcified, node to set; otherwise use the node of the Widget
     122  */
     123  template <typename T>
     124  void SetVolatileXmlProp(std::string prop, T value, xmlNodePtr node = NULL);
    122125
    123             /*!
    124             * \brief Send xml
    125             *
    126             * Send Widget's xml to ground station. \n
    127             * New changes will be taken into account by ground station. \n
    128             * All volatile properties will be erased after calling ths method, as they should not be used anymore.
    129             */
    130             void SendXml(void);
     126  /*!
     127  * \brief Send xml
     128  *
     129  * Send Widget's xml to ground station. \n
     130  * New changes will be taken into account by ground station. \n
     131  * All volatile properties will be erased after calling ths method, as they
     132  *should not be used anymore.
     133  */
     134  void SendXml(void);
    131135
    132             /*!
    133             * \brief Xml event
    134             *
    135             * This method must be reimplemented to handle a xml event. \n
    136             * It is automatically called when something changed from
    137             * ground station. \n
    138             */
    139             virtual void XmlEvent(void){};
     136  /*!
     137  * \brief Xml event
     138  *
     139  * This method must be reimplemented to handle a xml event. \n
     140  * It is automatically called when something changed from
     141  * ground station. \n
     142  */
     143  virtual void XmlEvent(void){};
    140144
    141          private:
    142             class Widget_impl* pimpl_;
    143     };
     145private:
     146  class Widget_impl *pimpl_;
     147};
    144148
    145149} // end namespace gui
  • trunk/include/FlairCore/cvimage.h

    r2 r13  
    1818#include <stdint.h>
    1919
    20 namespace flair
    21 {
    22 namespace core
    23 {
    24     /*! \class cvimage
    25     *
    26     * \brief Class defining an image of kind IplImage
    27     *
    28     * IplImage is an image struct defined in OpenCV.
    29     *
     20namespace flair {
     21namespace core {
     22/*! \class cvimage
     23*
     24* \brief Class defining an image of kind IplImage
     25*
     26* IplImage is an image struct defined in OpenCV.
     27*
     28*/
     29class cvimage : public io_data {
     30public:
     31  class Type : public DataType {
     32  public:
     33    /*!
     34    \enum Format_t
     35    \brief Picture formats
    3036    */
    31     class cvimage: public io_data {
    32     public:
    33         class Type: public DataType {
    34         public:
    35             /*!
    36             \enum Format_t
    37             \brief Picture formats
    38             */
    39             enum class Format {
    40                 YUYV,/*!< YUYV 16 bits */
    41                 UYVY,/*!< UYVY 16 bits */
    42                 BGR,/*!< BGR 24 bits */
    43                 GRAY,/*!< gray 8 bits */
    44             } ;
    45             Type(uint16_t _width, uint16_t _height, Format _format):width(_width),height(_height),format(_format) {}
     37    enum class Format {
     38      YUYV, /*!< YUYV 16 bits */
     39      UYVY, /*!< UYVY 16 bits */
     40      BGR,  /*!< BGR 24 bits */
     41      GRAY, /*!< gray 8 bits */
     42    };
     43    Type(uint16_t _width, uint16_t _height, Format _format)
     44        : width(_width), height(_height), format(_format) {}
    4645
    47             size_t GetSize() const {
    48                 size_t pixelSize;
    49                 switch(format) {
    50                 case Format::GRAY:
    51                     pixelSize=1;
    52                     break;
    53                 case Format::YUYV:
    54                 case Format::UYVY:
    55                     pixelSize=2;
    56                     break;
    57                 case Format::BGR:
    58                     pixelSize=3;
    59                     break;
    60                 default:
    61                     pixelSize=0; //TODO should throw an exception instead
    62                 }
    63                 return pixelSize*width*height;
    64             }
    65             std::string GetDescription() const {return "cv image";};
     46    size_t GetSize() const {
     47      size_t pixelSize;
     48      switch (format) {
     49      case Format::GRAY:
     50        pixelSize = 1;
     51        break;
     52      case Format::YUYV:
     53      case Format::UYVY:
     54        pixelSize = 2;
     55        break;
     56      case Format::BGR:
     57        pixelSize = 3;
     58        break;
     59      default:
     60        pixelSize = 0; // TODO should throw an exception instead
     61      }
     62      return pixelSize * width * height;
     63    }
     64    std::string GetDescription() const { return "cv image"; };
    6665
    67             Format GetFormat() const {return format;};
    68             uint16_t GetWidth() const {return width;};
    69             uint16_t GetHeight() const {return height;};
     66    Format GetFormat() const { return format; };
     67    uint16_t GetWidth() const { return width; };
     68    uint16_t GetHeight() const { return height; };
    7069
    71         private:
    72             uint16_t width;
    73             uint16_t height;
    74             Format format;
     70  private:
     71    uint16_t width;
     72    uint16_t height;
     73    Format format;
     74  };
    7575
    76         };
     76  /*!
     77  * \brief Constructor
     78  *
     79  * Construct an io_data representing an IplImage.
     80  *
     81  * \param parent parent
     82  * \param width image width
     83  * \param height image height
     84  * \param name name
     85  * \param allocate_data if true, IplImage image data is allocated; otherwise
     86  *img->imagedata must be changed
     87  * \param n number of samples
     88  */
     89  cvimage(const Object *parent, uint16_t width, uint16_t height,
     90          Type::Format format, std::string name = "", bool allocate_data = true,
     91          int n = 1);
    7792
    78         /*!
    79         * \brief Constructor
    80         *
    81         * Construct an io_data representing an IplImage.
    82         *
    83         * \param parent parent
    84         * \param width image width
    85         * \param height image height
    86         * \param name name
    87         * \param allocate_data if true, IplImage image data is allocated; otherwise img->imagedata must be changed
    88         * \param n number of samples
    89         */
    90         cvimage(const Object* parent,uint16_t width,uint16_t height,Type::Format format,std::string name="",bool allocate_data=true,int n=1);
     93  /*!
     94  * \brief Destructor
     95  *
     96  */
     97  ~cvimage();
    9198
    92         /*!
    93         * \brief Destructor
    94         *
    95         */
    96         ~cvimage();
     99  /*!
     100  * \brief IplImage
     101  *
     102  * \return IplImage
     103  */
     104  IplImage *img;
    97105
    98         /*!
    99         * \brief IplImage
    100         *
    101         * \return IplImage
    102         */
    103         IplImage* img;
     106  Type const &GetDataType() const { return dataType; };
    104107
    105         Type const&GetDataType() const {return dataType;};
     108private:
     109  /*!
     110  * \brief Copy datas
     111  *
     112  * Reimplemented from io_data. \n
     113  * See io_data::CopyDatas.
     114  *
     115  * \param dst destination buffer
     116  */
     117  void CopyDatas(char *dst) const;
    106118
    107     private:
    108         /*!
    109         * \brief Copy datas
    110         *
    111         * Reimplemented from io_data. \n
    112         * See io_data::CopyDatas.
    113         *
    114         * \param dst destination buffer
    115         */
    116         void CopyDatas(char* dst) const;
    117 
    118         bool allocate_data;
    119         Type dataType;
    120     };
     119  bool allocate_data;
     120  Type dataType;
     121};
    121122
    122123} // end namespace core
  • trunk/include/FlairCore/cvmatrix.h

    r2 r13  
    2121struct CvMat;
    2222
    23 namespace flair { namespace core {
    24 
    25     /*! \class cvmatrix
    26     *
    27     * \brief Class defining a matrix of kind CvMat
    28     *
    29     * CvMat is a matrix struct defined in OpenCV.
    30     *
    31     */
    32     class cvmatrix: public io_data {
    33     public:
    34         class Type: public DataType {
    35         public:
    36             Type(size_t _nbRows,size_t _nbCols,ScalarType const &_elementDataType):nbRows(_nbRows),nbCols(_nbCols),elementDataType(_elementDataType) {}
    37             size_t GetSize() const {
    38                 return nbRows*nbCols*elementDataType.GetSize();
    39             }
    40             std::string GetDescription() const {return "matrix";}
    41             size_t GetNbRows() const {return nbRows;}
    42             size_t GetNbCols() const {return nbCols;}
    43             ScalarType const &GetElementDataType() const {return elementDataType;}
    44 
    45         private:
    46             size_t nbRows,nbCols;
    47             ScalarType const &elementDataType;
    48         };
    49 
    50         /*!
    51         * \brief Constructor
    52         *
    53         * Construct an io_data representing a CvMat. \n
    54         * It uses a cvmatrix_descriptor to get size and elements' names. \n
    55         * Names are used for graphs and logs.
    56         *
    57         * \param parent parent
    58         * \param descriptor matrix description
    59         * \param type type of matrix elements
    60         * \param name name
    61         * \param n number of samples
    62         */
    63         cvmatrix(const Object* parent,const cvmatrix_descriptor *descriptor, ScalarType const &elementDataType,std::string name="",uint32_t n=1);
    64 
    65         /*!
    66         * \brief Constructor
    67         *
    68         * Construct an io_data representing a CvMat. \n
    69         * Elements are unamed.
    70         *
    71         * \param parent parent
    72         * \param rows matrix rows
    73         * \param cols matrix cols
    74         * \param type type of matrix elements
    75         * \param name name
    76         * \param n number of samples
    77         */
    78         cvmatrix(const Object* parent,uint32_t rows, uint32_t cols, ScalarType const &elementDataType,std::string name="",uint32_t n=1);
    79 
    80         /*!
    81         * \brief Destructor
    82         *
    83         */
    84         ~cvmatrix();
    85 
    86         /*!
    87         * \brief Element value
    88         *
    89         * Element is accessed by locking and unlocking the io_data Mutex.
    90         *
    91         * \param row element row
    92         * \param col element col
    93         *
    94         * \return element value
    95         */
    96         float Value(uint32_t row, uint32_t col) const;
    97 
    98         /*!
    99         * \brief Element value
    100         *
    101         * Element is not accessed by locking and unlocking the io_data Mutex. \n
    102         * Thus, this function should be called with Mutex locked. \n
    103         * This function is usefull when multiple successive access are done to the
    104         * elments of the matrix. It avoids unnecessary locking and unlocking.
    105         *
    106         * \param row element row
    107         * \param col element col
    108         *
    109         * \return element value
    110         */
    111         float ValueNoMutex(uint32_t row, uint32_t col) const;
    112 
    113         /*!
    114         * \brief Set element value
    115         *
    116         * Element is accessed by locking and unlocking the io_data Mutex.
    117         *
    118         * \param row element row
    119         * \param col element col
    120         * \param value element value
    121         */
    122         void SetValue(uint32_t row, uint32_t col,float value);
    123 
    124         /*!
    125         * \brief Set element value
    126         *
    127         * Element is not accessed by locking and unlocking the io_data Mutex. \n
    128         * Thus, this function should be called with Mutex locked. \n
    129         * This function is usefull when multiple successive access are done to the
    130         * elments of the matrix. It avoids unnecessary locking and unlocking.
    131         *
    132         * \param row element row
    133         * \param col element col
    134         * \param value element value
    135         */
    136         void SetValueNoMutex(uint32_t row, uint32_t col,float value);
    137 
    138         /*!
    139         * \brief get CvMat
    140         *
    141         * The io_data Mutex must be used by the user.
    142         */
    143         CvMat* getCvMat(void) const;
    144 
    145         /*!
    146         * \brief Element name
    147         *
    148         * If cvmatrix was created without cvmatrix_descriptor, element name is empty.
    149         *
    150         * \param row element row
    151         * \param col element col
    152         *
    153         * \return element name
    154         */
    155         std::string Name(uint32_t row, uint32_t col) const;
    156 
    157         /*!
    158         * \brief Element
    159         *
    160         * Get a pointer to a specific element. This pointer can be used for plotting.
    161         *
    162         * \param row element row
    163         * \param col element col
    164         *
    165         * \return pointer to the element
    166         */
    167         IODataElement* Element(uint32_t row, uint32_t col) const;
    168 
    169         /*!
    170         * \brief Element
    171         *
    172         * Get a pointer to a specific element. This pointer can be used for plotting. \n
    173         * This function can be used for a 1D matrix.
    174         *
    175         * \param index element index
    176         *
    177         * \return pointer to the element
    178         */
    179         IODataElement* Element(uint32_t index) const;
    180 
    181         /*!
    182         * \brief Number of rows
    183         *
    184         * \return rows
    185         */
    186         uint32_t Rows(void) const;
    187 
    188         /*!
    189         * \brief Number of colomns
    190         *
    191         * \return colomns
    192         */
    193         uint32_t Cols(void) const;
    194 
    195         Type const &GetDataType() const {return dataType;};
    196 
    197     private:
    198         /*!
    199         * \brief Copy datas
    200         *
    201         * Reimplemented from io_data. \n
    202         * See io_data::CopyDatas.
    203         *
    204         * \param dst destination buffer
    205         */
    206         void CopyDatas(char* dst) const;
    207 
    208         class cvmatrix_impl* pimpl_;
    209         Type dataType;
    210     };
     23namespace flair {
     24namespace core {
     25
     26/*! \class cvmatrix
     27*
     28* \brief Class defining a matrix of kind CvMat
     29*
     30* CvMat is a matrix struct defined in OpenCV.
     31*
     32*/
     33class cvmatrix : public io_data {
     34public:
     35  class Type : public DataType {
     36  public:
     37    Type(size_t _nbRows, size_t _nbCols, ScalarType const &_elementDataType)
     38        : nbRows(_nbRows), nbCols(_nbCols), elementDataType(_elementDataType) {}
     39    size_t GetSize() const {
     40      return nbRows * nbCols * elementDataType.GetSize();
     41    }
     42    std::string GetDescription() const { return "matrix"; }
     43    size_t GetNbRows() const { return nbRows; }
     44    size_t GetNbCols() const { return nbCols; }
     45    ScalarType const &GetElementDataType() const { return elementDataType; }
     46
     47  private:
     48    size_t nbRows, nbCols;
     49    ScalarType const &elementDataType;
     50  };
     51
     52  /*!
     53  * \brief Constructor
     54  *
     55  * Construct an io_data representing a CvMat. \n
     56  * It uses a cvmatrix_descriptor to get size and elements' names. \n
     57  * Names are used for graphs and logs.
     58  *
     59  * \param parent parent
     60  * \param descriptor matrix description
     61  * \param type type of matrix elements
     62  * \param name name
     63  * \param n number of samples
     64  */
     65  cvmatrix(const Object *parent, const cvmatrix_descriptor *descriptor,
     66           ScalarType const &elementDataType, std::string name = "",
     67           uint32_t n = 1);
     68
     69  /*!
     70  * \brief Constructor
     71  *
     72  * Construct an io_data representing a CvMat. \n
     73  * Elements are unamed.
     74  *
     75  * \param parent parent
     76  * \param rows matrix rows
     77  * \param cols matrix cols
     78  * \param type type of matrix elements
     79  * \param name name
     80  * \param n number of samples
     81  */
     82  cvmatrix(const Object *parent, uint32_t rows, uint32_t cols,
     83           ScalarType const &elementDataType, std::string name = "",
     84           uint32_t n = 1);
     85
     86  /*!
     87  * \brief Destructor
     88  *
     89  */
     90  ~cvmatrix();
     91
     92  /*!
     93  * \brief Element value
     94  *
     95  * Element is accessed by locking and unlocking the io_data Mutex.
     96  *
     97  * \param row element row
     98  * \param col element col
     99  *
     100  * \return element value
     101  */
     102  float Value(uint32_t row, uint32_t col) const;
     103
     104  /*!
     105  * \brief Element value
     106  *
     107  * Element is not accessed by locking and unlocking the io_data Mutex. \n
     108  * Thus, this function should be called with Mutex locked. \n
     109  * This function is usefull when multiple successive access are done to the
     110  * elments of the matrix. It avoids unnecessary locking and unlocking.
     111  *
     112  * \param row element row
     113  * \param col element col
     114  *
     115  * \return element value
     116  */
     117  float ValueNoMutex(uint32_t row, uint32_t col) const;
     118
     119  /*!
     120  * \brief Set element value
     121  *
     122  * Element is accessed by locking and unlocking the io_data Mutex.
     123  *
     124  * \param row element row
     125  * \param col element col
     126  * \param value element value
     127  */
     128  void SetValue(uint32_t row, uint32_t col, float value);
     129
     130  /*!
     131  * \brief Set element value
     132  *
     133  * Element is not accessed by locking and unlocking the io_data Mutex. \n
     134  * Thus, this function should be called with Mutex locked. \n
     135  * This function is usefull when multiple successive access are done to the
     136  * elments of the matrix. It avoids unnecessary locking and unlocking.
     137  *
     138  * \param row element row
     139  * \param col element col
     140  * \param value element value
     141  */
     142  void SetValueNoMutex(uint32_t row, uint32_t col, float value);
     143
     144  /*!
     145  * \brief get CvMat
     146  *
     147  * The io_data Mutex must be used by the user.
     148  */
     149  CvMat *getCvMat(void) const;
     150
     151  /*!
     152  * \brief Element name
     153  *
     154  * If cvmatrix was created without cvmatrix_descriptor, element name is empty.
     155  *
     156  * \param row element row
     157  * \param col element col
     158  *
     159  * \return element name
     160  */
     161  std::string Name(uint32_t row, uint32_t col) const;
     162
     163  /*!
     164  * \brief Element
     165  *
     166  * Get a pointer to a specific element. This pointer can be used for plotting.
     167  *
     168  * \param row element row
     169  * \param col element col
     170  *
     171  * \return pointer to the element
     172  */
     173  IODataElement *Element(uint32_t row, uint32_t col) const;
     174
     175  /*!
     176  * \brief Element
     177  *
     178  * Get a pointer to a specific element. This pointer can be used for plotting.
     179  *\n
     180  * This function can be used for a 1D matrix.
     181  *
     182  * \param index element index
     183  *
     184  * \return pointer to the element
     185  */
     186  IODataElement *Element(uint32_t index) const;
     187
     188  /*!
     189  * \brief Number of rows
     190  *
     191  * \return rows
     192  */
     193  uint32_t Rows(void) const;
     194
     195  /*!
     196  * \brief Number of colomns
     197  *
     198  * \return colomns
     199  */
     200  uint32_t Cols(void) const;
     201
     202  Type const &GetDataType() const { return dataType; };
     203
     204private:
     205  /*!
     206  * \brief Copy datas
     207  *
     208  * Reimplemented from io_data. \n
     209  * See io_data::CopyDatas.
     210  *
     211  * \param dst destination buffer
     212  */
     213  void CopyDatas(char *dst) const;
     214
     215  class cvmatrix_impl *pimpl_;
     216  Type dataType;
     217};
    211218
    212219} // end namespace core
  • trunk/include/FlairCore/cvmatrix_descriptor.h

    r2 r13  
    1616#include <string>
    1717
    18 namespace flair { namespace core
    19 {
     18namespace flair {
     19namespace core {
    2020
    21     /*! \class cvmatrix_descriptor
    22     *
    23     * \brief Class describing cvmatrix elements, for log and graphs purpose
    24     *
    25     * This class allows to give a name to matrix elements. These names
    26     * will be used in graphs and logs.
    27     */
    28     class cvmatrix_descriptor {
    29         public:
    30             /*!
    31             * \brief Constructor
    32             *
    33             * Construct a matrix descriptor.
    34             *
    35             * \param rows matrix rows
    36             * \param cols matrix cols
    37             */
    38             cvmatrix_descriptor(uint32_t rows, uint32_t cols);
     21/*! \class cvmatrix_descriptor
     22*
     23* \brief Class describing cvmatrix elements, for log and graphs purpose
     24*
     25* This class allows to give a name to matrix elements. These names
     26* will be used in graphs and logs.
     27*/
     28class cvmatrix_descriptor {
     29public:
     30  /*!
     31  * \brief Constructor
     32  *
     33  * Construct a matrix descriptor.
     34  *
     35  * \param rows matrix rows
     36  * \param cols matrix cols
     37  */
     38  cvmatrix_descriptor(uint32_t rows, uint32_t cols);
    3939
    40             /*!
    41             * \brief Destructor
    42             *
    43             */
    44             ~cvmatrix_descriptor();
     40  /*!
     41  * \brief Destructor
     42  *
     43  */
     44  ~cvmatrix_descriptor();
    4545
    46             /*!
    47             * \brief Set element name
    48             *
    49             * \param row element row
    50             * \param col element col
    51             * \param name element name
    52             */
    53             void SetElementName(uint32_t row, uint32_t col,std::string name);
     46  /*!
     47  * \brief Set element name
     48  *
     49  * \param row element row
     50  * \param col element col
     51  * \param name element name
     52  */
     53  void SetElementName(uint32_t row, uint32_t col, std::string name);
    5454
    55             /*!
    56             * \brief Element name
    57             *
    58             * \param row element row
    59             * \param col element col
    60             *
    61             * \return element name
    62             */
    63             std::string ElementName(uint32_t row, uint32_t col) const;
     55  /*!
     56  * \brief Element name
     57  *
     58  * \param row element row
     59  * \param col element col
     60  *
     61  * \return element name
     62  */
     63  std::string ElementName(uint32_t row, uint32_t col) const;
    6464
    65             /*!
    66             * \brief Number of rows
    67             *
    68             * \return rows
    69             */
    70             uint32_t Rows(void) const;
     65  /*!
     66  * \brief Number of rows
     67  *
     68  * \return rows
     69  */
     70  uint32_t Rows(void) const;
    7171
    72             /*!
    73             * \brief Number of colomns
    74             *
    75             * \return colomns
    76             */
    77             uint32_t Cols(void) const;
     72  /*!
     73  * \brief Number of colomns
     74  *
     75  * \return colomns
     76  */
     77  uint32_t Cols(void) const;
    7878
    79         private:
    80             uint32_t rows,cols;
    81             std::string **element_names;
    82 
    83     };
     79private:
     80  uint32_t rows, cols;
     81  std::string **element_names;
     82};
    8483
    8584} // end namespace core
  • trunk/include/FlairCore/io_data.h

    r2 r13  
    1919class io_data_impl;
    2020
    21 namespace flair { namespace core {
     21namespace flair {
     22namespace core {
    2223
    23     class Object;
     24class Object;
    2425
    25     class DataType {
    26     public:
    27         virtual std::string GetDescription() const =0;
    28         //size in bytes
    29         virtual size_t GetSize() const =0;
    30     };
     26class DataType {
     27public:
     28  virtual std::string GetDescription() const = 0;
     29  // size in bytes
     30  virtual size_t GetSize() const = 0;
     31};
    3132
    32     class DummyType: public DataType {
    33     public:
    34         size_t GetSize() const {return 0;}
    35         std::string GetDescription() const {return "dummy";};
    36     };
    37     extern DummyType dummyType;
     33class DummyType : public DataType {
     34public:
     35  size_t GetSize() const { return 0; }
     36  std::string GetDescription() const { return "dummy"; };
     37};
     38extern DummyType dummyType;
    3839
    39     class ScalarType: public DataType {
    40     public:
    41         ScalarType(size_t _size):size(_size) {}
    42         size_t GetSize() const {return size;}
    43         virtual std::string GetDescription() const {return "scalar";};
    44     private:
    45         size_t size;
    46     };
     40class ScalarType : public DataType {
     41public:
     42  ScalarType(size_t _size) : size(_size) {}
     43  size_t GetSize() const { return size; }
     44  virtual std::string GetDescription() const { return "scalar"; };
    4745
    48     class SignedIntegerType: public ScalarType {
    49     public:
    50         SignedIntegerType(size_t sizeInBits):ScalarType(sizeInBits/8){}
    51         std::string GetDescription() const {return "int"+std::to_string(GetSize()*8)+"_t";};
    52     };
    53     extern SignedIntegerType Int8Type;
    54     extern SignedIntegerType Int16Type;
     46private:
     47  size_t size;
     48};
    5549
    56     class FloatType: public ScalarType {
    57     public:
    58         FloatType():ScalarType(4){}
    59         std::string GetDescription() const {return "float";};
    60     };
    61     extern FloatType floatType;
     50class SignedIntegerType : public ScalarType {
     51public:
     52  SignedIntegerType(size_t sizeInBits) : ScalarType(sizeInBits / 8) {}
     53  std::string GetDescription() const {
     54    return "int" + std::to_string(GetSize() * 8) + "_t";
     55  };
     56};
     57extern SignedIntegerType Int8Type;
     58extern SignedIntegerType Int16Type;
    6259
     60class FloatType : public ScalarType {
     61public:
     62  FloatType() : ScalarType(4) {}
     63  std::string GetDescription() const { return "float"; };
     64};
     65extern FloatType floatType;
    6366
    64     /*! \class io_data
    65     *
    66     * \brief Abstract class for data types.
    67     *
    68     * Use this class to define a custom data type. Data types ares used for logging and graphs. \n
    69     * The reimplemented class must call SetSize() in its constructor. \n
    70     * io_data can be constructed with n samples (see io_data::io_data).
    71     * In this case, old samples can be accessed throug io_data::Prev.
    72     */
    73     class io_data: public Mutex {
    74         friend class IODevice;
    75         friend class ::IODevice_impl;
    76         friend class ::io_data_impl;
     67/*! \class io_data
     68*
     69* \brief Abstract class for data types.
     70*
     71* Use this class to define a custom data type. Data types ares used for logging
     72*and graphs. \n
     73* The reimplemented class must call SetSize() in its constructor. \n
     74* io_data can be constructed with n samples (see io_data::io_data).
     75* In this case, old samples can be accessed throug io_data::Prev.
     76*/
     77class io_data : public Mutex {
     78  friend class IODevice;
     79  friend class ::IODevice_impl;
     80  friend class ::io_data_impl;
    7781
    78         public:
    79             /*!
    80             * \brief Constructor
    81             *
    82             * Construct an io_data. \n
    83             *
    84             * \param parent parent
    85             * \param name name
    86             * \param n number of samples
    87             */
    88             io_data(const Object* parent,std::string name,int n);
     82public:
     83  /*!
     84  * \brief Constructor
     85  *
     86  * Construct an io_data. \n
     87  *
     88  * \param parent parent
     89  * \param name name
     90  * \param n number of samples
     91  */
     92  io_data(const Object *parent, std::string name, int n);
    8993
    90             /*!
    91             * \brief Destructor
    92             *
    93             */
    94             virtual ~io_data();
     94  /*!
     95  * \brief Destructor
     96  *
     97  */
     98  virtual ~io_data();
    9599
    96             /*!
    97             * \brief Set data time
    98             *
    99             * \param time time
    100             */
    101             void SetDataTime(Time time);
     100  /*!
     101  * \brief Set data time
     102  *
     103  * \param time time
     104  */
     105  void SetDataTime(Time time);
    102106
    103             /*!
    104             * \brief Data time
    105             *
    106             * \return data time
    107             */
    108             Time DataTime(void) const;
     107  /*!
     108  * \brief Data time
     109  *
     110  * \return data time
     111  */
     112  Time DataTime(void) const;
    109113
    110             /*!
    111             * \brief Previous data
    112             *
    113             * Access previous data. io_data must have been constructed with
    114             * n>1, io_data::SetPtrToCircle must have been set and
    115             * io_data::prev must have been allocated.
    116             *
    117             * \param n previous data number
    118             *
    119             * \return previous data
    120             */
    121             const io_data* Prev(int n) const;
     114  /*!
     115  * \brief Previous data
     116  *
     117  * Access previous data. io_data must have been constructed with
     118  * n>1, io_data::SetPtrToCircle must have been set and
     119  * io_data::prev must have been allocated.
     120  *
     121  * \param n previous data number
     122  *
     123  * \return previous data
     124  */
     125  const io_data *Prev(int n) const;
    122126
    123             virtual DataType const&GetDataType() const =0;
     127  virtual DataType const &GetDataType() const = 0;
    124128
    125         protected:
    126             /*!
    127             * \brief Specify the description of the reimplemented class data's
    128             *
    129             *  This method must be called in the constructor of the reimplemented class, once by element. \n
    130             *  Each element description must be called in the same order as CopyDatas put the datas in the buffer. \n
    131             *  The description will be used for the log descriptor file.
    132             *
    133             * \param description description of the element
    134             * \param datatype type of the element
    135             */
    136             void AppendLogDescription(std::string description, DataType const &datatype);
     129protected:
     130  /*!
     131  * \brief Specify the description of the reimplemented class data's
     132  *
     133  *  This method must be called in the constructor of the reimplemented class,
     134  *once by element. \n
     135  *  Each element description must be called in the same order as CopyDatas put
     136  *the datas in the buffer. \n
     137  *  The description will be used for the log descriptor file.
     138  *
     139  * \param description description of the element
     140  * \param datatype type of the element
     141  */
     142  void AppendLogDescription(std::string description, DataType const &datatype);
    137143
    138             /*!
    139             * \brief Set the datas to circle
    140             *
    141             * \param ptr pointer to the data to circle
    142             */
    143             void SetPtrToCircle(void **ptr);
     144  /*!
     145  * \brief Set the datas to circle
     146  *
     147  * \param ptr pointer to the data to circle
     148  */
     149  void SetPtrToCircle(void **ptr);
    144150
    145             /*!
    146             * \brief Pointer to previous data
    147             *
    148             * Reimplemented class must allocate this pointer if n>1. \n
    149             * Pointer must be allocated with the same kind of reimplemented class.
    150             */
    151             io_data* prev;
     151  /*!
     152  * \brief Pointer to previous data
     153  *
     154  * Reimplemented class must allocate this pointer if n>1. \n
     155  * Pointer must be allocated with the same kind of reimplemented class.
     156  */
     157  io_data *prev;
    152158
    153         private:
    154             /*!
    155             * \brief Copy datas
    156             *
    157             * This method is automatically called by IODevice::ProcessUpdate to log io_data datas. \n
    158             * This method must be reimplemented, in order to copy the datas to the logs.
    159             * Copied datas must be of size io_data::Size.
    160             *
    161             * \param dst destination buffer
    162             */
    163             virtual void CopyDatas(char* dst) const =0;
     159private:
     160  /*!
     161  * \brief Copy datas
     162  *
     163  * This method is automatically called by IODevice::ProcessUpdate to log
     164  *io_data datas. \n
     165  * This method must be reimplemented, in order to copy the datas to the logs.
     166  * Copied datas must be of size io_data::Size.
     167  *
     168  * \param dst destination buffer
     169  */
     170  virtual void CopyDatas(char *dst) const = 0;
    164171
    165             io_data_impl *pimpl_;
    166     };
     172  io_data_impl *pimpl_;
     173};
    167174
    168175} // end namespace core
  • 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
  • trunk/include/FlairMeta/HdsX8.h

    r9 r13  
    1616#include "Uav.h"
    1717
    18 namespace flair
    19 {
    20 namespace meta
    21 {
    22     /*! \class HdsX8
    23     *
    24     * \brief Class defining an ardrone2 uav
    25     */
    26     class HdsX8 : public Uav {
    27         public:
    28             HdsX8(core::FrameworkManager* parent,std::string uav_name,filter::UavMultiplex *multiplex=NULL);
    29             ~HdsX8();
    30             void StartSensors(void);
     18namespace flair {
     19namespace meta {
     20/*! \class HdsX8
     21*
     22* \brief Class defining an ardrone2 uav
     23*/
     24class HdsX8 : public Uav {
     25public:
     26  HdsX8(core::FrameworkManager *parent, std::string uav_name,
     27        filter::UavMultiplex *multiplex = NULL);
     28  ~HdsX8();
     29  void StartSensors(void);
    3130
    32         private:
    33 
    34     };
     31private:
     32};
    3533} // end namespace meta
    3634} // end namespace flair
  • trunk/include/FlairMeta/MetaDualShock3.h

    r9 r13  
    1717
    1818namespace flair {
    19     namespace core {
    20         class AhrsData;
    21         class Quaternion;
    22     }
    23     namespace filter {
    24         class Ahrs;
    25     }
     19namespace core {
     20class AhrsData;
     21class Quaternion;
     22}
     23namespace filter {
     24class Ahrs;
     25}
    2626}
    2727
     
    3131namespace meta {
    3232
    33     /*! \class MetaDualShock3
    34     *
    35     * \brief Classe intégrant la manette MetaDualShock3
    36     */
    37     class MetaDualShock3 : public sensor::TargetEthController {
    38         friend class ::MetaDualShock3_impl;
     33/*! \class MetaDualShock3
     34*
     35* \brief Classe intégrant la manette MetaDualShock3
     36*/
     37class MetaDualShock3 : public sensor::TargetEthController {
     38  friend class ::MetaDualShock3_impl;
    3939
    40         public:
    41             MetaDualShock3(core::FrameworkManager* parent,std::string name,uint16_t port,uint8_t priority);
    42             ~MetaDualShock3();
    43             core::AhrsData* GetReferenceOrientation(void) const;
    44             float ZRef(void) const;
    45             float DzRef(void) const;
    46             void SetYawRef(float value);
    47             /*!
    48             * \brief Set yaw reference
    49             *
    50             * Yaw part of the output quaternion is obtained by integrating the wz desired angular speed.\n
    51             * This method reset the yaw.
    52             *
    53             * \param value value, only the yaw part of the quaternion is used
    54             */
    55             void SetYawRef(core::Quaternion const &value);
    56             void SetZRef(float value);
    57             float RollTrim(void) const;
    58             float PitchTrim(void) const;
    59             void ErrorNotify(void);
    60             void Rumble(uint8_t left_force,uint8_t left_timeout=20,uint8_t right_force=0,uint8_t right_timeout=0);
    61             void SetLedON(unsigned int ledId);
    62             void SetLedOFF(unsigned int ledId);
    63             void FlashLed(unsigned int ledId,uint8_t on_timeout,uint8_t off_timeout);
     40public:
     41  MetaDualShock3(core::FrameworkManager *parent, std::string name,
     42                 uint16_t port, uint8_t priority);
     43  ~MetaDualShock3();
     44  core::AhrsData *GetReferenceOrientation(void) const;
     45  float ZRef(void) const;
     46  float DzRef(void) const;
     47  void SetYawRef(float value);
     48  /*!
     49  * \brief Set yaw reference
     50  *
     51  * Yaw part of the output quaternion is obtained by integrating the wz desired
     52  *angular speed.\n
     53  * This method reset the yaw.
     54  *
     55  * \param value value, only the yaw part of the quaternion is used
     56  */
     57  void SetYawRef(core::Quaternion const &value);
     58  void SetZRef(float value);
     59  float RollTrim(void) const;
     60  float PitchTrim(void) const;
     61  void ErrorNotify(void);
     62  void Rumble(uint8_t left_force, uint8_t left_timeout = 20,
     63              uint8_t right_force = 0, uint8_t right_timeout = 0);
     64  void SetLedON(unsigned int ledId);
     65  void SetLedOFF(unsigned int ledId);
     66  void FlashLed(unsigned int ledId, uint8_t on_timeout, uint8_t off_timeout);
    6467
    65         private:
    66             class MetaDualShock3_impl* pimpl_;
    67 
    68     };
     68private:
     69  class MetaDualShock3_impl *pimpl_;
     70};
    6971} // end namespace meta
    7072} // end namespace flair
  • trunk/include/FlairMeta/MetaUsRangeFinder.h

    r9 r13  
    1717
    1818namespace flair {
    19     namespace filter {
    20         class ButterworthLowPass;
    21         class EulerDerivative;
    22     }
    23     namespace sensor {
    24         class UsRangeFinder;
    25     }
    26     namespace gui {
    27         class DataPlot1D;
    28     }
     19namespace filter {
     20class ButterworthLowPass;
     21class EulerDerivative;
     22}
     23namespace sensor {
     24class UsRangeFinder;
     25}
     26namespace gui {
     27class DataPlot1D;
     28}
    2929}
    3030
    31 namespace flair
    32 {
    33 namespace meta
    34 {
    35     /*! \class MetaUsRangeFinder
    36     *
    37     * \brief Classe haut niveau pour capteur à ultra son
    38     *
    39     * Contient une dérivée d'euler et un passe bas.
    40     * Cette classe est adaptée pour un capteur d'altitude.
    41     */
    42     class MetaUsRangeFinder: public core::Object {
    43         public:
    44             MetaUsRangeFinder(sensor::UsRangeFinder* us);
    45             ~MetaUsRangeFinder();
    46             void UseDefaultPlot(void);
    47             float z(void) const;
    48             float Vz(void) const;
    49             gui::DataPlot1D *GetZPlot();
    50             gui::DataPlot1D *GetVzPlot();
     31namespace flair {
     32namespace meta {
     33/*! \class MetaUsRangeFinder
     34*
     35* \brief Classe haut niveau pour capteur à ultra son
     36*
     37* Contient une dérivée d'euler et un passe bas.
     38* Cette classe est adaptée pour un capteur d'altitude.
     39*/
     40class MetaUsRangeFinder : public core::Object {
     41public:
     42  MetaUsRangeFinder(sensor::UsRangeFinder *us);
     43  ~MetaUsRangeFinder();
     44  void UseDefaultPlot(void);
     45  float z(void) const;
     46  float Vz(void) const;
     47  gui::DataPlot1D *GetZPlot();
     48  gui::DataPlot1D *GetVzPlot();
    5149
    52         private:
    53             sensor::UsRangeFinder* us;
    54             filter::ButterworthLowPass *pbas_z,*pbas_vz;
    55             filter::EulerDerivative *vz_euler;
    56             gui::DataPlot1D* vz_plot;
    57     };
     50private:
     51  sensor::UsRangeFinder *us;
     52  filter::ButterworthLowPass *pbas_z, *pbas_vz;
     53  filter::EulerDerivative *vz_euler;
     54  gui::DataPlot1D *vz_plot;
     55};
    5856} // end namespace meta
    5957} // end namespace flair
  • trunk/include/FlairMeta/MetaVrpnObject.h

    r9 r13  
    1717#include "io_data.h"
    1818
    19 namespace flair
    20 {
    21     namespace core
    22     {
    23         class Vector3D;
    24         class FloatType;
    25     }
    26     namespace gui
    27     {
    28         class DataPlot1D;
    29         class DataPlot2D;
    30         class Tab;
    31     }
    32     namespace filter
    33     {
    34         class EulerDerivative;
    35         class LowPassFilter;
    36     }
    37     namespace sensor
    38     {
    39         class VrpnClient;
    40     }
     19namespace flair {
     20namespace core {
     21class Vector3D;
     22class FloatType;
     23}
     24namespace gui {
     25class DataPlot1D;
     26class DataPlot2D;
     27class Tab;
     28}
     29namespace filter {
     30class EulerDerivative;
     31class LowPassFilter;
     32}
     33namespace sensor {
     34class VrpnClient;
     35}
    4136}
    4237
    43 namespace flair
    44 {
    45 namespace meta
    46 {
     38namespace flair {
     39namespace meta {
    4740
    48     /*! \class MetaVrpnObject
    49     *
    50     * \brief Classe haut niveau intégrant un objet VRPN
    51     *
    52     * Contient un objet VRPN et une dérivée, d'euler.
    53     */
    54     class MetaVrpnObject: public sensor::VrpnObject {
    55         public:
    56             MetaVrpnObject(const sensor::VrpnClient *parent,std::string name);
    57             MetaVrpnObject(const sensor::VrpnClient *parent,std::string name,uint8_t id);
    58             ~MetaVrpnObject();
    59             gui::DataPlot1D* VxPlot(void) const;//1,0
    60             gui::DataPlot1D* VyPlot(void) const;//1,1
    61             gui::DataPlot1D* VzPlot(void) const;//1,2
    62             gui::DataPlot2D* XyPlot(void) const;
    63             void GetSpeed(core::Vector3D &speed) const;
     41/*! \class MetaVrpnObject
     42*
     43* \brief Classe haut niveau intégrant un objet VRPN
     44*
     45* Contient un objet VRPN et une dérivée, d'euler.
     46*/
     47class MetaVrpnObject : public sensor::VrpnObject {
     48public:
     49  MetaVrpnObject(const sensor::VrpnClient *parent, std::string name);
     50  MetaVrpnObject(const sensor::VrpnClient *parent, std::string name,
     51                 uint8_t id);
     52  ~MetaVrpnObject();
     53  gui::DataPlot1D *VxPlot(void) const; // 1,0
     54  gui::DataPlot1D *VyPlot(void) const; // 1,1
     55  gui::DataPlot1D *VzPlot(void) const; // 1,2
     56  gui::DataPlot2D *XyPlot(void) const;
     57  void GetSpeed(core::Vector3D &speed) const;
    6458
    65         private:
    66             void ConstructorCommon(const sensor::VrpnClient *parent,std::string name);
    67             filter::LowPassFilter *pbas;
    68             filter::EulerDerivative *euler;
    69             gui::DataPlot2D *xy_plot;
    70             gui::DataPlot1D *vx_opti_plot,*vy_opti_plot,*vz_opti_plot;
    71             gui::Tab* plot_tab;
    72             core::FloatType elementDataType;
    73 
    74     };
     59private:
     60  void ConstructorCommon(const sensor::VrpnClient *parent, std::string name);
     61  filter::LowPassFilter *pbas;
     62  filter::EulerDerivative *euler;
     63  gui::DataPlot2D *xy_plot;
     64  gui::DataPlot1D *vx_opti_plot, *vy_opti_plot, *vz_opti_plot;
     65  gui::Tab *plot_tab;
     66  core::FloatType elementDataType;
     67};
    7568} // end namespace meta
    7669} // end namespace flair
  • trunk/include/FlairMeta/SimuX4.h

    r9 r13  
    1616#include "Uav.h"
    1717
    18 namespace flair
    19 {
    20 namespace meta
    21 {
    22     /*! \class SimuX4
    23     *
    24     * \brief Class defining a simultation x4 uav
    25     */
    26     class SimuX4 : public Uav {
    27         public:
    28             //simu_id: 0 if simulating only one UAV
    29             //>0 otherwise
    30             SimuX4(core::FrameworkManager* parent,std::string uav_name,int simu_id=0,filter::UavMultiplex *multiplex=NULL);
    31             ~SimuX4();
    32             void StartSensors(void);
    33             void SetupVRPNAutoIP(std::string name);
    34     };
     18namespace flair {
     19namespace meta {
     20/*! \class SimuX4
     21*
     22* \brief Class defining a simultation x4 uav
     23*/
     24class SimuX4 : public Uav {
     25public:
     26  // simu_id: 0 if simulating only one UAV
     27  //>0 otherwise
     28  SimuX4(core::FrameworkManager *parent, std::string uav_name, int simu_id = 0,
     29         filter::UavMultiplex *multiplex = NULL);
     30  ~SimuX4();
     31  void StartSensors(void);
     32  void SetupVRPNAutoIP(std::string name);
     33};
    3534} // end namespace meta
    3635} // end namespace flair
  • trunk/include/FlairMeta/SimuX8.h

    r9 r13  
    1616#include "Uav.h"
    1717
    18 namespace flair
    19 {
    20 namespace meta
    21 {
    22     /*! \class SimuX8
    23     *
    24     * \brief Class defining a simultation x8 uav
    25     */
    26     class SimuX8 : public Uav {
    27         public:
    28             //simu_id: 0 if simulating only one UAV
    29             //>0 otherwise
    30             SimuX8(core::FrameworkManager* parent,std::string uav_name,int simu_id=0,filter::UavMultiplex *multiplex=NULL);
    31             ~SimuX8();
    32             void StartSensors(void);
    33             void SetupVRPNAutoIP(std::string name);
    34     };
     18namespace flair {
     19namespace meta {
     20/*! \class SimuX8
     21*
     22* \brief Class defining a simultation x8 uav
     23*/
     24class SimuX8 : public Uav {
     25public:
     26  // simu_id: 0 if simulating only one UAV
     27  //>0 otherwise
     28  SimuX8(core::FrameworkManager *parent, std::string uav_name, int simu_id = 0,
     29         filter::UavMultiplex *multiplex = NULL);
     30  ~SimuX8();
     31  void StartSensors(void);
     32  void SetupVRPNAutoIP(std::string name);
     33};
    3534} // end namespace meta
    3635} // end namespace flair
  • trunk/include/FlairMeta/Uav.h

    r9 r13  
    1717
    1818namespace flair {
    19     namespace core {
    20         class FrameworkManager;
    21     }
    22     namespace filter {
    23         class Ahrs;
    24         class UavMultiplex;
    25     }
    26     namespace actuator {
    27         class Bldc;
    28     }
    29     namespace sensor {
    30         class UsRangeFinder;
    31         class BatteryMonitor;
    32         class VrpnClient;
    33         class Imu;
    34         class Camera;
    35     }
     19namespace core {
     20class FrameworkManager;
     21}
     22namespace filter {
     23class Ahrs;
     24class UavMultiplex;
     25}
     26namespace actuator {
     27class Bldc;
     28}
     29namespace sensor {
     30class UsRangeFinder;
     31class BatteryMonitor;
     32class VrpnClient;
     33class Imu;
     34class Camera;
     35}
    3636}
    3737
    3838namespace flair {
    3939namespace meta {
    40     class MetaUsRangeFinder;
    41     class MetaVrpnObject;
     40class MetaUsRangeFinder;
     41class MetaVrpnObject;
    4242
    43     /*! \class Uav
    44     *
    45     * \brief Base class to construct sensors/actuators depending on uav type
    46     */
    47     class Uav: public core::Object {
    48         public:
    49         /*
    50             typedef enum {
    51                 None,
    52                 Auto,//rt serial if hds x4 ou x8, auto ip sinon
    53                 AutoIP,
    54                 UserDefinedIP,
    55                 AutoSerialPort,
    56                 } VRPNType_t;
     43/*! \class Uav
     44*
     45* \brief Base class to construct sensors/actuators depending on uav type
    5746*/
    58             //uav_name: for optitrack
    59             Uav(core::FrameworkManager* parent,std::string name,filter::UavMultiplex *multiplex=NULL);
    60             ~Uav();
    61             void SetupVRPN(std::string optitrack_address,std::string name);
    62             //vrpn serial: broken, need to add serial port in uav specific code
    63             //void SetupVRPNSerial(core::SerialPort *vrpn_port,std::string name,int VRPNSerialObjectId);
    64             virtual void SetupVRPNAutoIP(std::string name);
     47class Uav : public core::Object {
     48public:
     49  /*
     50      typedef enum {
     51          None,
     52          Auto,//rt serial if hds x4 ou x8, auto ip sinon
     53          AutoIP,
     54          UserDefinedIP,
     55          AutoSerialPort,
     56          } VRPNType_t;
     57*/
     58  // uav_name: for optitrack
     59  Uav(core::FrameworkManager *parent, std::string name,
     60      filter::UavMultiplex *multiplex = NULL);
     61  ~Uav();
     62  void SetupVRPN(std::string optitrack_address, std::string name);
     63  // vrpn serial: broken, need to add serial port in uav specific code
     64  // void SetupVRPNSerial(core::SerialPort *vrpn_port,std::string name,int
     65  // VRPNSerialObjectId);
     66  virtual void SetupVRPNAutoIP(std::string name);
    6567
    66             virtual void StartSensors(void);
    67             void UseDefaultPlot(void);
    68             actuator::Bldc* GetBldc(void) const;
    69             filter::UavMultiplex* GetUavMultiplex(void) const;
    70             sensor::Imu* GetImu(void) const;
    71             filter::Ahrs* GetAhrs(void) const;
    72             MetaUsRangeFinder* GetMetaUsRangeFinder(void) const;
    73             sensor::UsRangeFinder* GetUsRangeFinder(void) const;
    74             sensor::BatteryMonitor* GetBatteryMonitor(void) const;
    75             sensor::VrpnClient* GetVrpnClient(void) const;
    76             meta::MetaVrpnObject* GetVrpnObject(void) const;
    77             sensor::Camera* GetVerticalCamera(void) const;
     68  virtual void StartSensors(void);
     69  void UseDefaultPlot(void);
     70  actuator::Bldc *GetBldc(void) const;
     71  filter::UavMultiplex *GetUavMultiplex(void) const;
     72  sensor::Imu *GetImu(void) const;
     73  filter::Ahrs *GetAhrs(void) const;
     74  MetaUsRangeFinder *GetMetaUsRangeFinder(void) const;
     75  sensor::UsRangeFinder *GetUsRangeFinder(void) const;
     76  sensor::BatteryMonitor *GetBatteryMonitor(void) const;
     77  sensor::VrpnClient *GetVrpnClient(void) const;
     78  meta::MetaVrpnObject *GetVrpnObject(void) const;
     79  sensor::Camera *GetVerticalCamera(void) const;
    7880
    79         protected:
    80             void SetBldc(const actuator::Bldc *bldc);
    81             void SetMultiplex(const filter::UavMultiplex *multiplex);
    82             void SetAhrs(const filter::Ahrs *ahrs);
    83             void SetUsRangeFinder(const sensor::UsRangeFinder *us);
    84             void SetBatteryMonitor(const sensor::BatteryMonitor *battery);
    85             void SetVerticalCamera(const sensor::Camera *verticalCamera);
     81protected:
     82  void SetBldc(const actuator::Bldc *bldc);
     83  void SetMultiplex(const filter::UavMultiplex *multiplex);
     84  void SetAhrs(const filter::Ahrs *ahrs);
     85  void SetUsRangeFinder(const sensor::UsRangeFinder *us);
     86  void SetBatteryMonitor(const sensor::BatteryMonitor *battery);
     87  void SetVerticalCamera(const sensor::Camera *verticalCamera);
    8688
    87         private:
    88             sensor::Imu* imu;
    89             filter::Ahrs* ahrs;
    90             actuator::Bldc* bldc;
    91             filter::UavMultiplex *multiplex;
    92             sensor::UsRangeFinder* us;
    93             MetaUsRangeFinder* meta_us;
    94             sensor::VrpnClient *vrpnclient;
    95             MetaVrpnObject* uav_vrpn;
    96             sensor::BatteryMonitor* battery;
    97             sensor::Camera* verticalCamera;
    98     };
     89private:
     90  sensor::Imu *imu;
     91  filter::Ahrs *ahrs;
     92  actuator::Bldc *bldc;
     93  filter::UavMultiplex *multiplex;
     94  sensor::UsRangeFinder *us;
     95  MetaUsRangeFinder *meta_us;
     96  sensor::VrpnClient *vrpnclient;
     97  MetaVrpnObject *uav_vrpn;
     98  sensor::BatteryMonitor *battery;
     99  sensor::Camera *verticalCamera;
     100};
    99101} // end namespace meta
    100102} // end namespace flair
  • trunk/include/FlairMeta/UavFactory.h

    r9 r13  
    2121#include <Uav.h>
    2222
    23 flair::meta::Uav* CreateUav(flair::core::FrameworkManager* parent,std::string uav_name,std::string uav_type,flair::filter::UavMultiplex *multiplex=NULL);
     23flair::meta::Uav *CreateUav(flair::core::FrameworkManager *parent,
     24                            std::string uav_name, std::string uav_type,
     25                            flair::filter::UavMultiplex *multiplex = NULL);
    2426
    2527#endif // UAVFACTORY
  • trunk/include/FlairMeta/UavStateMachine.h

    r9 r13  
    2626
    2727namespace flair {
    28     namespace core {
    29         class FrameworkManager;
    30         class AhrsData;
    31         class io_data;
    32     }
    33     namespace gui {
    34         class PushButton;
    35         class GridLayout;
    36         class Tab;
    37         class DoubleSpinBox;
    38     }
    39     namespace filter {
    40         class ControlLaw;
    41         class NestedSat;
    42         class Pid;
    43         class PidThrust;
    44         class TrajectoryGenerator1D;
    45     }
    46     namespace sensor {
    47         class TargetController;
    48     }
    49     namespace meta {
    50         class MetaDualShock3;
    51         class Uav;
    52     }
    53 }
    54 
    55 namespace flair { namespace meta {
    56 
    57  /*! \class UavStateMachine
     28namespace core {
     29class FrameworkManager;
     30class AhrsData;
     31class io_data;
     32}
     33namespace gui {
     34class PushButton;
     35class GridLayout;
     36class Tab;
     37class DoubleSpinBox;
     38}
     39namespace filter {
     40class ControlLaw;
     41class NestedSat;
     42class Pid;
     43class PidThrust;
     44class TrajectoryGenerator1D;
     45}
     46namespace sensor {
     47class TargetController;
     48}
     49namespace meta {
     50class MetaDualShock3;
     51class Uav;
     52}
     53}
     54
     55namespace flair {
     56namespace meta {
     57
     58/*! \class UavStateMachine
    5859*
    5960* \brief State machine for UAV
    6061*
    61 * thread synchronized with ahrs, unless a period is set with SetPeriodUS or SetPeriodMS
     62* thread synchronized with ahrs, unless a period is set with SetPeriodUS or
     63*SetPeriodMS
    6264*/
    6365
    64 class UavStateMachine : public core::Thread
    65 {
    66     protected:
    67         enum class AltitudeMode_t {
    68             Manual,
    69             Custom
    70         };
    71         const AltitudeMode_t &GetAltitudeMode(void) const {
    72             return altitudeMode;
    73         }
    74         bool SetAltitudeMode(const AltitudeMode_t &altitudeMode);
    75 
    76         //uses TrajectoryGenerator1D *altitudeTrajectory to go to desiredAltitude
    77         //available in mode AltitudeMode_t::Manual
    78         //return true if goto is possible
    79         bool GotoAltitude(float desiredAltitude);
    80 
    81         enum class OrientationMode_t {
    82             Manual,
    83             Custom
    84         };
    85         const OrientationMode_t &GetOrientationMode(void) const {
    86             return orientationMode;
    87         }
    88         bool SetOrientationMode(const OrientationMode_t &orientationMode);
    89 
    90         enum class ThrustMode_t {
    91             Default,
    92             Custom
    93         };
    94         const ThrustMode_t &GetThrustMode() const {
    95             return thrustMode;
    96         }
    97         bool SetThrustMode(const ThrustMode_t &thrustMode);
    98 
    99         enum class TorqueMode_t {
    100             Default,
    101             Custom
    102         };
    103         const TorqueMode_t &GetTorqueMode(void) const {
    104             return torqueMode;
    105         }
    106         bool SetTorqueMode(const TorqueMode_t &torqueMode);
    107 
    108         enum class Event_t {
    109             EnteringFailSafeMode,
    110             EnteringControlLoop,
    111             StartLanding,
    112             FinishLanding,
    113             Stopped,
    114             TakingOff,
    115             EmergencyStop,
    116             Stabilized, //as soon as uav is 3cm far from the ground
    117             ZTrajectoryFinished,
    118         };
    119 
    120         UavStateMachine(meta::Uav* uav,uint16_t ds3Port=20000);
    121         ~UavStateMachine();
    122 
    123         const core::Quaternion &GetCurrentQuaternion(void) const;
    124 
    125         const core::Vector3D &GetCurrentAngularSpeed(void) const;
    126 
    127         const meta::Uav *GetUav(void) const;
    128 
    129         void Land(void);
    130         void TakeOff(void);
    131         void EmergencyStop(void);
    132         //! Used to signal an event
    133         /*!
    134             \param event the event which occured
    135         */
    136         virtual void SignalEvent(Event_t event);
    137 
    138         virtual const core::AhrsData *GetOrientation(void) const;
    139         const core::AhrsData *GetDefaultOrientation(void) const;
    140 
    141         virtual void AltitudeValues(float &z,float &dz) const;//in uav coordinate!
    142         void EnterFailSafeMode(void);
    143         bool ExitFailSafeMode(void);
    144         void FailSafeAltitudeValues(float &z,float &dz) const;//in uav coordinate!
    145 
    146         gui::GridLayout *GetButtonsLayout(void) const;
    147         virtual void ExtraSecurityCheck(void){};
    148         virtual void ExtraCheckJoystick(void){};
    149         virtual void ExtraCheckPushButton(void){};
    150 
    151         void GetDefaultReferenceAltitude(float &refAltitude, float &refVerticalVelocity);
    152         virtual void GetReferenceAltitude(float &refAltitude, float &refVerticalVelocity);
    153         //float GetDefaultThrustOffset(void);
    154         const core::AhrsData *GetDefaultReferenceOrientation(void) const;
    155         virtual const core::AhrsData *GetReferenceOrientation(void);
    156 
    157         /*!
    158         * \brief Compute Custom Torques
    159         *
    160         * Reimplement this method to use TorqueMode_t::Custom. \n
    161         * This method is called internally by UavStateMachine, do not call it by yourself. \n
    162         * See GetTorques if you need torques values.
    163         *
    164         * \param torques custom torques
    165         */
    166         virtual void ComputeCustomTorques(core::Euler &torques);
    167 
    168         /*!
    169         * \brief Compute Default Torques
    170         *
    171         * This method is called internally by UavStateMachine when using TorqueMode_t::Default. \n
    172         * Torques are only computed once by loop, other calls to this method will use previously computed torques.
    173         *
    174         * \param torques default torques
    175         */
    176         void ComputeDefaultTorques(core::Euler &torques);
    177 
    178         /*!
    179         * \brief Get Torques
    180         *
    181         * \return torques current torques
    182         */
    183         //const core::Euler &GetTorques() const;
    184 
    185         /*!
    186         * \brief Compute Custom Thrust
    187         *
    188         * Reimplement this method to use ThrustMode_t::Custom. \n
    189         * This method is called internally by UavStateMachine, do not call it by yourself. \n
    190         * See GetThrust if you need thrust value.
    191         *
    192         * \return custom Thrust
    193         */
    194         virtual float ComputeCustomThrust(void);
    195 
    196         /*!
    197         * \brief Compute Default Thrust
    198         *
    199         * This method is called internally by UavStateMachine when using ThrustMode_t::Default. \n
    200         * Thrust is only computed once by loop, other calls to this method will use previously computed thrust.
    201         *
    202         * \return default thrust
    203         */
    204         float ComputeDefaultThrust(void);
    205 
    206         /*!
    207         * \brief Get Thrust
    208         *
    209         * \return current thrust
    210         */
    211         //float GetThrust() const;
    212 
    213         /*!
    214         * \brief Add an IODevice to the control law logs
    215         *
    216         * The IODevice will be automatically logged among the Uz logs,
    217         * if logging is enabled (see IODevice::SetDataToLog, FrameworkManager::StartLog
    218         * and FrameworkManager::AddDeviceToLog). \n
    219         *
    220         * \param device IODevice to log
    221         */
    222         void AddDeviceToControlLawLog(const core::IODevice* device);
    223 
    224         /*!
    225         * \brief Add an io_data to the control law logs
    226         *
    227         * The io_data will be automatically logged among the Uz logs,
    228         * if logging is enabled (see IODevice::SetDataToLog, FrameworkManager::StartLog
    229         * and FrameworkManager::AddDeviceToLog). \n
    230         *
    231         * \param data io_data to log
    232         */
    233         void AddDataToControlLawLog(const core::io_data* data);
    234 
    235         const sensor::TargetController *GetJoystick(void) const;
    236 
    237         gui::Tab *setupLawTab,*graphLawTab;
    238 
    239     private:
    240         /*!
    241         \enum AltitudeState_t
    242         \brief States of the altitude state machine
    243         */
    244         enum class AltitudeState_t {
    245             Stopped,        /*!< the uav motors are stopped */
    246             TakingOff,      /*!< take off initiated. Motors accelerate progressively until the UAV lift up */
    247             Stabilized,     /*!< the uav is actively maintaining its altitude */
    248             StartLanding,   /*!< landing initiated. Altitude is required to reach the landing altitude (0 by default) */
    249             FinishLanding   /*!< motors are gradually stopped */
    250         };
    251         AltitudeState_t altitudeState;
    252         void ProcessAltitudeFiniteStateMachine();
    253         void ComputeReferenceAltitude(float &refAltitude, float &refVerticalVelocity);
    254 
    255 
    256         float groundAltitude; // effective altitude when the uav leaves the ground
    257         float currentAltitude,currentVerticalSpeed;
    258 
    259         bool failSafeMode;
    260         void SecurityCheck(void);
    261         void MandatorySecurityCheck(void);
    262         void CheckJoystick();
    263         void GenericCheckJoystick();
    264         void CheckPushButton(void);
    265         void GenericCheckPushButton(void);
    266         void Run(void);
    267         void StopMotors(void);
    268 
    269         meta::Uav *uav;
    270 
    271         core::Quaternion currentQuaternion;
    272         core::Vector3D currentAngularSpeed;
    273 
    274         const core::AhrsData *ComputeReferenceOrientation(void);
    275 
    276         void ComputeOrientation(void);
    277         void ComputeAltitude(void);
    278 
    279         void ComputeTorques(void);
    280         core::Euler currentTorques,savedDefaultTorques;
    281         bool needToComputeDefaultTorques;
    282 
    283         void ComputeThrust(void);
    284         float currentThrust,savedDefaultThrust;
    285         bool needToComputeDefaultThrust;
    286 
    287         gui::PushButton *button_kill,*button_take_off,*button_land,*button_start_log,*button_stop_log;
    288         gui::GridLayout *buttonslayout;
    289         gui::DoubleSpinBox *desiredTakeoffAltitude,*desiredLandingAltitude;
    290         AltitudeMode_t altitudeMode;
    291         OrientationMode_t orientationMode;
    292         ThrustMode_t thrustMode;
    293         TorqueMode_t torqueMode;
    294         bool flagBatteryLow;
    295         bool flagConnectionLost;
    296         bool flagZTrajectoryFinished;
    297         filter::NestedSat *uRoll,*uPitch;
    298         filter::Pid *uYaw;
    299         filter::PidThrust *uZ;
    300 
    301         MetaDualShock3 *joy;
    302         filter::TrajectoryGenerator1D *altitudeTrajectory;
     66class UavStateMachine : public core::Thread {
     67protected:
     68  enum class AltitudeMode_t { Manual, Custom };
     69  const AltitudeMode_t &GetAltitudeMode(void) const { return altitudeMode; }
     70  bool SetAltitudeMode(const AltitudeMode_t &altitudeMode);
     71
     72  // uses TrajectoryGenerator1D *altitudeTrajectory to go to desiredAltitude
     73  // available in mode AltitudeMode_t::Manual
     74  // return true if goto is possible
     75  bool GotoAltitude(float desiredAltitude);
     76
     77  enum class OrientationMode_t { Manual, Custom };
     78  const OrientationMode_t &GetOrientationMode(void) const {
     79    return orientationMode;
     80  }
     81  bool SetOrientationMode(const OrientationMode_t &orientationMode);
     82
     83  enum class ThrustMode_t { Default, Custom };
     84  const ThrustMode_t &GetThrustMode() const { return thrustMode; }
     85  bool SetThrustMode(const ThrustMode_t &thrustMode);
     86
     87  enum class TorqueMode_t { Default, Custom };
     88  const TorqueMode_t &GetTorqueMode(void) const { return torqueMode; }
     89  bool SetTorqueMode(const TorqueMode_t &torqueMode);
     90
     91  enum class Event_t {
     92    EnteringFailSafeMode,
     93    EnteringControlLoop,
     94    StartLanding,
     95    FinishLanding,
     96    Stopped,
     97    TakingOff,
     98    EmergencyStop,
     99    Stabilized, // as soon as uav is 3cm far from the ground
     100    ZTrajectoryFinished,
     101  };
     102
     103  UavStateMachine(meta::Uav *uav, uint16_t ds3Port = 20000);
     104  ~UavStateMachine();
     105
     106  const core::Quaternion &GetCurrentQuaternion(void) const;
     107
     108  const core::Vector3D &GetCurrentAngularSpeed(void) const;
     109
     110  const meta::Uav *GetUav(void) const;
     111
     112  void Land(void);
     113  void TakeOff(void);
     114  void EmergencyStop(void);
     115  //! Used to signal an event
     116  /*!
     117      \param event the event which occured
     118  */
     119  virtual void SignalEvent(Event_t event);
     120
     121  virtual const core::AhrsData *GetOrientation(void) const;
     122  const core::AhrsData *GetDefaultOrientation(void) const;
     123
     124  virtual void AltitudeValues(float &z, float &dz) const; // in uav coordinate!
     125  void EnterFailSafeMode(void);
     126  bool ExitFailSafeMode(void);
     127  void FailSafeAltitudeValues(float &z, float &dz) const; // in uav coordinate!
     128
     129  gui::GridLayout *GetButtonsLayout(void) const;
     130  virtual void ExtraSecurityCheck(void){};
     131  virtual void ExtraCheckJoystick(void){};
     132  virtual void ExtraCheckPushButton(void){};
     133
     134  void GetDefaultReferenceAltitude(float &refAltitude,
     135                                   float &refVerticalVelocity);
     136  virtual void GetReferenceAltitude(float &refAltitude,
     137                                    float &refVerticalVelocity);
     138  // float GetDefaultThrustOffset(void);
     139  const core::AhrsData *GetDefaultReferenceOrientation(void) const;
     140  virtual const core::AhrsData *GetReferenceOrientation(void);
     141
     142  /*!
     143  * \brief Compute Custom Torques
     144  *
     145  * Reimplement this method to use TorqueMode_t::Custom. \n
     146  * This method is called internally by UavStateMachine, do not call it by
     147  *yourself. \n
     148  * See GetTorques if you need torques values.
     149  *
     150  * \param torques custom torques
     151  */
     152  virtual void ComputeCustomTorques(core::Euler &torques);
     153
     154  /*!
     155  * \brief Compute Default Torques
     156  *
     157  * This method is called internally by UavStateMachine when using
     158  *TorqueMode_t::Default. \n
     159  * Torques are only computed once by loop, other calls to this method will use
     160  *previously computed torques.
     161  *
     162  * \param torques default torques
     163  */
     164  void ComputeDefaultTorques(core::Euler &torques);
     165
     166  /*!
     167  * \brief Get Torques
     168  *
     169  * \return torques current torques
     170  */
     171  // const core::Euler &GetTorques() const;
     172
     173  /*!
     174  * \brief Compute Custom Thrust
     175  *
     176  * Reimplement this method to use ThrustMode_t::Custom. \n
     177  * This method is called internally by UavStateMachine, do not call it by
     178  *yourself. \n
     179  * See GetThrust if you need thrust value.
     180  *
     181  * \return custom Thrust
     182  */
     183  virtual float ComputeCustomThrust(void);
     184
     185  /*!
     186  * \brief Compute Default Thrust
     187  *
     188  * This method is called internally by UavStateMachine when using
     189  *ThrustMode_t::Default. \n
     190  * Thrust is only computed once by loop, other calls to this method will use
     191  *previously computed thrust.
     192  *
     193  * \return default thrust
     194  */
     195  float ComputeDefaultThrust(void);
     196
     197  /*!
     198  * \brief Get Thrust
     199  *
     200  * \return current thrust
     201  */
     202  // float GetThrust() const;
     203
     204  /*!
     205  * \brief Add an IODevice to the control law logs
     206  *
     207  * The IODevice will be automatically logged among the Uz logs,
     208  * if logging is enabled (see IODevice::SetDataToLog,
     209  *FrameworkManager::StartLog
     210  * and FrameworkManager::AddDeviceToLog). \n
     211  *
     212  * \param device IODevice to log
     213  */
     214  void AddDeviceToControlLawLog(const core::IODevice *device);
     215
     216  /*!
     217  * \brief Add an io_data to the control law logs
     218  *
     219  * The io_data will be automatically logged among the Uz logs,
     220  * if logging is enabled (see IODevice::SetDataToLog,
     221  *FrameworkManager::StartLog
     222  * and FrameworkManager::AddDeviceToLog). \n
     223  *
     224  * \param data io_data to log
     225  */
     226  void AddDataToControlLawLog(const core::io_data *data);
     227
     228  const sensor::TargetController *GetJoystick(void) const;
     229
     230  gui::Tab *setupLawTab, *graphLawTab;
     231
     232private:
     233  /*!
     234  \enum AltitudeState_t
     235  \brief States of the altitude state machine
     236  */
     237  enum class AltitudeState_t {
     238    Stopped,      /*!< the uav motors are stopped */
     239    TakingOff,    /*!< take off initiated. Motors accelerate progressively until
     240                     the UAV lift up */
     241    Stabilized,   /*!< the uav is actively maintaining its altitude */
     242    StartLanding, /*!< landing initiated. Altitude is required to reach the
     243                     landing altitude (0 by default) */
     244    FinishLanding /*!< motors are gradually stopped */
     245  };
     246  AltitudeState_t altitudeState;
     247  void ProcessAltitudeFiniteStateMachine();
     248  void ComputeReferenceAltitude(float &refAltitude, float &refVerticalVelocity);
     249
     250  float groundAltitude; // effective altitude when the uav leaves the ground
     251  float currentAltitude, currentVerticalSpeed;
     252
     253  bool failSafeMode;
     254  void SecurityCheck(void);
     255  void MandatorySecurityCheck(void);
     256  void CheckJoystick();
     257  void GenericCheckJoystick();
     258  void CheckPushButton(void);
     259  void GenericCheckPushButton(void);
     260  void Run(void);
     261  void StopMotors(void);
     262
     263  meta::Uav *uav;
     264
     265  core::Quaternion currentQuaternion;
     266  core::Vector3D currentAngularSpeed;
     267
     268  const core::AhrsData *ComputeReferenceOrientation(void);
     269
     270  void ComputeOrientation(void);
     271  void ComputeAltitude(void);
     272
     273  void ComputeTorques(void);
     274  core::Euler currentTorques, savedDefaultTorques;
     275  bool needToComputeDefaultTorques;
     276
     277  void ComputeThrust(void);
     278  float currentThrust, savedDefaultThrust;
     279  bool needToComputeDefaultThrust;
     280
     281  gui::PushButton *button_kill, *button_take_off, *button_land,
     282      *button_start_log, *button_stop_log;
     283  gui::GridLayout *buttonslayout;
     284  gui::DoubleSpinBox *desiredTakeoffAltitude, *desiredLandingAltitude;
     285  AltitudeMode_t altitudeMode;
     286  OrientationMode_t orientationMode;
     287  ThrustMode_t thrustMode;
     288  TorqueMode_t torqueMode;
     289  bool flagBatteryLow;
     290  bool flagConnectionLost;
     291  bool flagZTrajectoryFinished;
     292  filter::NestedSat *uRoll, *uPitch;
     293  filter::Pid *uYaw;
     294  filter::PidThrust *uZ;
     295
     296  MetaDualShock3 *joy;
     297  filter::TrajectoryGenerator1D *altitudeTrajectory;
    303298};
    304 
    305299};
    306300};
  • trunk/include/FlairMeta/XAir.h

    r9 r13  
    1616#include "Uav.h"
    1717
    18 namespace flair
    19 {
    20 namespace meta
    21 {
    22     /*! \class XAir
    23     *
    24     * \brief Class defining an ardrone2 uav
    25     */
    26     class XAir : public Uav {
    27         public:
    28             XAir(core::FrameworkManager* parent,std::string uav_name,filter::UavMultiplex *multiplex=NULL);
    29             ~XAir();
    30             void StartSensors(void);
     18namespace flair {
     19namespace meta {
     20/*! \class XAir
     21*
     22* \brief Class defining an ardrone2 uav
     23*/
     24class XAir : public Uav {
     25public:
     26  XAir(core::FrameworkManager *parent, std::string uav_name,
     27       filter::UavMultiplex *multiplex = NULL);
     28  ~XAir();
     29  void StartSensors(void);
    3130
    32         private:
    33 
    34     };
     31private:
     32};
    3533} // end namespace meta
    3634} // end namespace flair
  • trunk/include/FlairSensorActuator/AfroBldc.h

    r4 r13  
    1616#include "Bldc.h"
    1717
    18 namespace flair
    19 {
    20     namespace core
    21     {
    22         class FrameworkManager;
    23         class I2cPort;
    24     }
    25     namespace sensor
    26     {
    27         class BatteryMonitor;
    28     }
     18namespace flair {
     19namespace core {
     20class FrameworkManager;
     21class I2cPort;
     22}
     23namespace sensor {
     24class BatteryMonitor;
     25}
    2926}
    3027
    3128class AfroBldc_impl;
    3229
    33 namespace flair
    34 {
    35 namespace actuator
    36 {
    37     /*! \class AfroBldc
    38     *
    39     * \brief Class for Mikrokopter's blctrlv2
    40     *
    41     * blctrlv2 drivers can also monitor the battery level. See GetBatteryMonitor().
    42     */
    43     class AfroBldc : public Bldc
    44     {
    45         friend class ::AfroBldc_impl;
     30namespace flair {
     31namespace actuator {
     32/*! \class AfroBldc
     33*
     34* \brief Class for Mikrokopter's blctrlv2
     35*
     36* blctrlv2 drivers can also monitor the battery level. See GetBatteryMonitor().
     37*/
     38class AfroBldc : public Bldc {
     39  friend class ::AfroBldc_impl;
    4640
    47         public:
    48             /*!
    49             * \brief Constructor
    50             *
    51             * Construct a AfroBldc.
    52             *
    53             * \param parent parent
    54             * \param layout layout
    55             * \param name name
    56             * \param motors_count number of motors
    57             * \param i2cport I2cPort
    58             */
    59             AfroBldc(const core::IODevice* parent,gui::Layout* layout,std::string name,uint8_t motors_count,core::I2cPort* i2cport);
     41public:
     42  /*!
     43  * \brief Constructor
     44  *
     45  * Construct a AfroBldc.
     46  *
     47  * \param parent parent
     48  * \param layout layout
     49  * \param name name
     50  * \param motors_count number of motors
     51  * \param i2cport I2cPort
     52  */
     53  AfroBldc(const core::IODevice *parent, gui::Layout *layout, std::string name,
     54           uint8_t motors_count, core::I2cPort *i2cport);
    6055
    61             /*!
    62             * \brief Destructor
    63             *
    64             */
    65             ~AfroBldc();
     56  /*!
     57  * \brief Destructor
     58  *
     59  */
     60  ~AfroBldc();
    6661
    67             /*!
    68             * \brief Has speed measurement
    69             *
    70             * Reimplemented from Bldc. \n
    71             *
    72             * \return true if it has speed measurement
    73             */
    74             bool HasSpeedMeasurement(void) const{return false;};
     62  /*!
     63  * \brief Has speed measurement
     64  *
     65  * Reimplemented from Bldc. \n
     66  *
     67  * \return true if it has speed measurement
     68  */
     69  bool HasSpeedMeasurement(void) const { return false; };
    7570
    76             /*!
    77             * \brief Has current measurement
    78             *
    79             * Reimplemented from Bldc. \n
    80             *
    81             * \return true if it has current measurement
    82             */
    83             bool HasCurrentMeasurement(void) const{return false;};
     71  /*!
     72  * \brief Has current measurement
     73  *
     74  * Reimplemented from Bldc. \n
     75  *
     76  * \return true if it has current measurement
     77  */
     78  bool HasCurrentMeasurement(void) const { return false; };
    8479
    85         private:
    86             /*!
    87             * \brief Set motors values
    88             *
    89             * Reimplemented from Bldc. \n
    90             * Values size must be the same as MotorsCount()
    91             *
    92             * \param values motor values
    93             */
    94             void SetMotors(float* values);
     80private:
     81  /*!
     82  * \brief Set motors values
     83  *
     84  * Reimplemented from Bldc. \n
     85  * Values size must be the same as MotorsCount()
     86  *
     87  * \param values motor values
     88  */
     89  void SetMotors(float *values);
    9590
    96             class AfroBldc_impl* pimpl_;
    97     };
     91  class AfroBldc_impl *pimpl_;
     92};
    9893} // end namespace actuator
    9994} // end namespace flair
  • trunk/include/FlairSensorActuator/BatteryMonitor.h

    r4 r13  
    1616#include <GroupBox.h>
    1717
    18 namespace flair
    19 {
    20     namespace gui
    21     {
    22         class LayoutPosition;
    23         class Label;
    24         class DoubleSpinBox;
    25     }
     18namespace flair {
     19namespace gui {
     20class LayoutPosition;
     21class Label;
     22class DoubleSpinBox;
     23}
    2624}
    2725
    28 namespace flair
    29 {
    30 namespace sensor
    31 {
     26namespace flair {
     27namespace sensor {
    3228
    33     /*! \class BatteryMonitor
    34     *
    35     * \brief Base class for battery monitor
    36     */
     29/*! \class BatteryMonitor
     30*
     31* \brief Base class for battery monitor
     32*/
    3733
    38     class BatteryMonitor : public gui::GroupBox
    39     {
    40         public:
    41             /*!
    42             * \brief Constructor
    43             *
    44             * Construct a BatteryMonitor at given position.
    45             *
    46             * \param position position
    47             * \param name name
    48             */
    49             BatteryMonitor(const gui::LayoutPosition* position,std::string name);
     34class BatteryMonitor : public gui::GroupBox {
     35public:
     36  /*!
     37  * \brief Constructor
     38  *
     39  * Construct a BatteryMonitor at given position.
     40  *
     41  * \param position position
     42  * \param name name
     43  */
     44  BatteryMonitor(const gui::LayoutPosition *position, std::string name);
    5045
    51             /*!
    52             * \brief Destructor
    53             *
    54             */
    55             ~BatteryMonitor();
     46  /*!
     47  * \brief Destructor
     48  *
     49  */
     50  ~BatteryMonitor();
    5651
    57             /*!
    58             * \brief Is batteru low?
    59             *
    60             * \return true if battery is below threshold
    61             *
    62             */
    63             bool IsBatteryLow(void) const;
     52  /*!
     53  * \brief Is batteru low?
     54  *
     55  * \return true if battery is below threshold
     56  *
     57  */
     58  bool IsBatteryLow(void) const;
    6459
    65             /*!
    66             * \brief Set battery value
    67             *
    68             * \param battery value
    69             *
    70             */
    71             void SetBatteryValue(float value);
     60  /*!
     61  * \brief Set battery value
     62  *
     63  * \param battery value
     64  *
     65  */
     66  void SetBatteryValue(float value);
    7267
    73             /*!
    74             * \brief Get battery voltage
    75             *
    76             * \return battery voltage
    77             *
    78             */
    79             float GetVoltage(void) const;
     68  /*!
     69  * \brief Get battery voltage
     70  *
     71  * \return battery voltage
     72  *
     73  */
     74  float GetVoltage(void) const;
    8075
    81         private:
    82             float batteryvalue;
    83             gui::DoubleSpinBox *battery_thresh;
    84             gui::Label *battery;
    85     };
     76private:
     77  float batteryvalue;
     78  gui::DoubleSpinBox *battery_thresh;
     79  gui::Label *battery;
     80};
    8681} // end namespace sensor
    8782} // end namespace flair
  • trunk/include/FlairSensorActuator/BlCtrlV2.h

    r4 r13  
    1616#include "Bldc.h"
    1717
    18 namespace flair
    19 {
    20     namespace core
    21     {
    22         class FrameworkManager;
    23         class I2cPort;
    24     }
    25     namespace sensor
    26     {
    27         class BatteryMonitor;
    28     }
     18namespace flair {
     19namespace core {
     20class FrameworkManager;
     21class I2cPort;
     22}
     23namespace sensor {
     24class BatteryMonitor;
     25}
    2926}
    3027
    3128class BlCtrlV2_impl;
    3229
    33 namespace flair
    34 {
    35 namespace actuator
    36 {
    37     /*! \class BlCtrlV2
    38     *
    39     * \brief Class for Mikrokopter's blctrlv2
    40     *
    41     * blctrlv2 drivers can also monitor the battery level. See GetBatteryMonitor().
    42     */
    43     class BlCtrlV2 : public Bldc
    44     {
    45         friend class ::BlCtrlV2_impl;
     30namespace flair {
     31namespace actuator {
     32/*! \class BlCtrlV2
     33*
     34* \brief Class for Mikrokopter's blctrlv2
     35*
     36* blctrlv2 drivers can also monitor the battery level. See GetBatteryMonitor().
     37*/
     38class BlCtrlV2 : public Bldc {
     39  friend class ::BlCtrlV2_impl;
    4640
    47         public:
    48             /*!
    49             * \brief Constructor
    50             *
    51             * Construct a BlCtrlV2.
    52             *
    53             * \param parent parent
    54             * \param layout layout
    55             * \param name name
    56             * \param motors_count number of motors
    57             * \param i2cport I2cPort
    58             */
    59             BlCtrlV2(const core::IODevice* parent,gui::Layout* layout,std::string name,uint8_t motors_count,core::I2cPort* i2cport);
     41public:
     42  /*!
     43  * \brief Constructor
     44  *
     45  * Construct a BlCtrlV2.
     46  *
     47  * \param parent parent
     48  * \param layout layout
     49  * \param name name
     50  * \param motors_count number of motors
     51  * \param i2cport I2cPort
     52  */
     53  BlCtrlV2(const core::IODevice *parent, gui::Layout *layout, std::string name,
     54           uint8_t motors_count, core::I2cPort *i2cport);
    6055
    61             /*!
    62             * \brief Destructor
    63             *
    64             */
    65             ~BlCtrlV2();
     56  /*!
     57  * \brief Destructor
     58  *
     59  */
     60  ~BlCtrlV2();
    6661
    67             /*!
    68             * \brief Get battery monitor
    69             *
    70             * \return BatteryMonitor
    71             */
    72             sensor::BatteryMonitor* GetBatteryMonitor(void) const;
     62  /*!
     63  * \brief Get battery monitor
     64  *
     65  * \return BatteryMonitor
     66  */
     67  sensor::BatteryMonitor *GetBatteryMonitor(void) const;
    7368
    74             /*!
    75             * \brief Has speed measurement
    76             *
    77             * Reimplemented from Bldc. \n
    78             *
    79             * \return true if it has speed measurement
    80             */
    81             bool HasSpeedMeasurement(void) const{return true;};
     69  /*!
     70  * \brief Has speed measurement
     71  *
     72  * Reimplemented from Bldc. \n
     73  *
     74  * \return true if it has speed measurement
     75  */
     76  bool HasSpeedMeasurement(void) const { return true; };
    8277
    83             /*!
    84             * \brief Has current measurement
    85             *
    86             * Reimplemented from Bldc. \n
    87             *
    88             * \return true if it has current measurement
    89             */
    90             bool HasCurrentMeasurement(void) const{return true;};
     78  /*!
     79  * \brief Has current measurement
     80  *
     81  * Reimplemented from Bldc. \n
     82  *
     83  * \return true if it has current measurement
     84  */
     85  bool HasCurrentMeasurement(void) const { return true; };
    9186
    92         private:
    93             /*!
    94             * \brief Set motors values
    95             *
    96             * Reimplemented from Bldc. \n
    97             * Values size must be the same as MotorsCount()
    98             *
    99             * \param values motor values
    100             */
    101             void SetMotors(float* values);
     87private:
     88  /*!
     89  * \brief Set motors values
     90  *
     91  * Reimplemented from Bldc. \n
     92  * Values size must be the same as MotorsCount()
     93  *
     94  * \param values motor values
     95  */
     96  void SetMotors(float *values);
    10297
    103             class BlCtrlV2_impl* pimpl_;
    104     };
     98  class BlCtrlV2_impl *pimpl_;
     99};
    105100} // end namespace actuator
    106101} // end namespace flair
  • trunk/include/FlairSensorActuator/BlCtrlV2_x4_speed.h

    r4 r13  
    1616/*********************************************************************/
    1717
    18 
    1918#ifndef BLCTRLV2_X4_SPEED_H
    2019#define BLCTRLV2_X4_SPEED_H
     
    2322#include <Thread.h>
    2423
    25 namespace flair
    26 {
    27     namespace core
    28     {
    29         class cvmatrix;
    30         class FrameworkManager;
    31         class I2cPort;
    32 
    33     }
    34     namespace gui
    35     {
    36         class TabWidget;
    37         class Tab;
    38         class SpinBox;
    39         class DoubleSpinBox;
    40         class ComboBox;
    41         class PushButton;
    42         class GroupBox;
    43     }
     24namespace flair {
     25namespace core {
     26class cvmatrix;
     27class FrameworkManager;
     28class I2cPort;
     29}
     30namespace gui {
     31class TabWidget;
     32class Tab;
     33class SpinBox;
     34class DoubleSpinBox;
     35class ComboBox;
     36class PushButton;
     37class GroupBox;
     38}
    4439}
    4540
    46 namespace flair
    47 {
    48 namespace actuator
    49 {
    50     class BlCtrlV2_x4_speed : public core::Thread,public core::IODevice
    51     {
     41namespace flair {
     42namespace actuator {
     43class BlCtrlV2_x4_speed : public core::Thread, public core::IODevice {
    5244
    53         public:
    54             BlCtrlV2_x4_speed(core::FrameworkManager* parent,std::string name,core::I2cPort* i2cport,uint8_t base_address,uint8_t priority);
    55             ~BlCtrlV2_x4_speed();
    56             void UseDefaultPlot(void);
    57             void LockUserInterface(void);
    58             void UnlockUserInterface(void);
    59             void SetEnabled(bool status);
    60             void SetUroll(float value);
    61             void SetUpitch(float value);
    62             void SetUyaw(float value);
    63             void SetUgaz(float value);
    64             void SetRollTrim(float value);
    65             void SetPitchTrim(float value);
    66             void SetYawTrim(float value);
    67             void SetGazTrim(float value);
    68             float TrimValue(void);
    69             int StartValue(void);
     45public:
     46  BlCtrlV2_x4_speed(core::FrameworkManager *parent, std::string name,
     47                    core::I2cPort *i2cport, uint8_t base_address,
     48                    uint8_t priority);
     49  ~BlCtrlV2_x4_speed();
     50  void UseDefaultPlot(void);
     51  void LockUserInterface(void);
     52  void UnlockUserInterface(void);
     53  void SetEnabled(bool status);
     54  void SetUroll(float value);
     55  void SetUpitch(float value);
     56  void SetUyaw(float value);
     57  void SetUgaz(float value);
     58  void SetRollTrim(float value);
     59  void SetPitchTrim(float value);
     60  void SetYawTrim(float value);
     61  void SetGazTrim(float value);
     62  float TrimValue(void);
     63  int StartValue(void);
    7064
    71         private:
    72             /*!
    73             * \brief Update using provided datas
    74             *
    75             * Reimplemented from IODevice.
    76             *
    77             * \param data data from the parent to process
    78             */
    79             void UpdateFrom(core::io_data *data){};
    80             void WriteValue(uint16_t value);
    81             float GetSpeed(void);
    82             void StartTest(void);
    83             void StopTest(void);
    84             /*!
    85             * \brief Run function
    86             *
    87             * Reimplemented from Thread.
    88             *
    89             */
    90             void Run(void);
    91             void Update(void);
    92             gui::Tab* main_tab;
    93             gui::TabWidget* tab;
    94             gui::GroupBox* reglages_groupbox;
    95             gui::SpinBox *min,*max,*test;
    96             gui::PushButton *button_avg,*button_avd,*button_arg,*button_ard;
    97             gui::ComboBox *av_g,*av_d,*ar_g,*ar_d,*pas;
    98             gui::DoubleSpinBox *trim,*kp,*ki;
    99             gui::SpinBox *start_value,*poles;
    100             core::Time start_time,flight_start_time;
    101             int time_sec;
    102             float speed_av_g,speed_av_d,speed_ar_g,speed_ar_d;
    103             float int_av_g,int_av_d,int_ar_g,int_ar_d;
     65private:
     66  /*!
     67  * \brief Update using provided datas
     68  *
     69  * Reimplemented from IODevice.
     70  *
     71  * \param data data from the parent to process
     72  */
     73  void UpdateFrom(core::io_data *data){};
     74  void WriteValue(uint16_t value);
     75  float GetSpeed(void);
     76  void StartTest(void);
     77  void StopTest(void);
     78  /*!
     79  * \brief Run function
     80  *
     81  * Reimplemented from Thread.
     82  *
     83  */
     84  void Run(void);
     85  void Update(void);
     86  gui::Tab *main_tab;
     87  gui::TabWidget *tab;
     88  gui::GroupBox *reglages_groupbox;
     89  gui::SpinBox *min, *max, *test;
     90  gui::PushButton *button_avg, *button_avd, *button_arg, *button_ard;
     91  gui::ComboBox *av_g, *av_d, *ar_g, *ar_d, *pas;
     92  gui::DoubleSpinBox *trim, *kp, *ki;
     93  gui::SpinBox *start_value, *poles;
     94  core::Time start_time, flight_start_time;
     95  int time_sec;
     96  float speed_av_g, speed_av_d, speed_ar_g, speed_ar_d;
     97  float int_av_g, int_av_d, int_ar_g, int_ar_d;
    10498
    105             //matrix
    106             core::cvmatrix *input;
    107             core::cvmatrix *output;
     99  // matrix
     100  core::cvmatrix *input;
     101  core::cvmatrix *output;
    108102
    109             int tested_motor;
    110             core::I2cPort* i2cport;
    111             uint8_t slave_address;
     103  int tested_motor;
     104  core::I2cPort *i2cport;
     105  uint8_t slave_address;
    112106
    113             bool enabled;
     107  bool enabled;
    114108
    115             uint16_t SatPWM(float vel_cons,uint16_t min,uint16_t max);
    116     };
     109  uint16_t SatPWM(float vel_cons, uint16_t min, uint16_t max);
     110};
    117111} // end namespace actuator
    118112} // end namespace flair
  • trunk/include/FlairSensorActuator/Bldc.h

    r4 r13  
    1717#include <stdint.h>
    1818
    19 namespace flair
    20 {
    21     namespace core
    22     {
    23         class FrameworkManager;
    24         class cvmatrix;
    25     }
    26     namespace gui
    27     {
    28         class Layout;
    29         class TabWidget;
    30     }
     19namespace flair {
     20namespace core {
     21class FrameworkManager;
     22class cvmatrix;
     23}
     24namespace gui {
     25class Layout;
     26class TabWidget;
     27}
    3128}
    3229
    3330class Bldc_impl;
    3431
    35 namespace flair
    36 {
    37 namespace actuator
    38 {
    39     /*! \class Bldc
    40     *
    41     * \brief Base class for brushless motors drivers
    42     */
    43     class Bldc : public core::IODevice
    44     {
    45         friend class ::Bldc_impl;
     32namespace flair {
     33namespace actuator {
     34/*! \class Bldc
     35*
     36* \brief Base class for brushless motors drivers
     37*/
     38class Bldc : public core::IODevice {
     39  friend class ::Bldc_impl;
    4640
    47         public:
    48             /*!
    49             * \brief Constructor
    50             *
    51             * Construct a Bldc.
    52             *
    53             * \param parent parent
    54             * \param layout layout
    55             * \param name name
    56             * \param motors_count number of motors
    57             */
    58             Bldc(const core::IODevice* parent,gui::Layout* layout,std::string name,uint8_t motors_count);
     41public:
     42  /*!
     43  * \brief Constructor
     44  *
     45  * Construct a Bldc.
     46  *
     47  * \param parent parent
     48  * \param layout layout
     49  * \param name name
     50  * \param motors_count number of motors
     51  */
     52  Bldc(const core::IODevice *parent, gui::Layout *layout, std::string name,
     53       uint8_t motors_count);
    5954
    60             /*!
    61             * \brief Constructor
    62             *
    63             * Construct a Bldc. \n
    64             * This contructor must only be called for a simulated device.
    65             *
    66             * \param parent parent
    67             * \param name name
    68             * \param motors_count number of motors
    69             */
    70             Bldc(const core::Object* parent,std::string name,uint8_t motors_count);
     55  /*!
     56  * \brief Constructor
     57  *
     58  * Construct a Bldc. \n
     59  * This contructor must only be called for a simulated device.
     60  *
     61  * \param parent parent
     62  * \param name name
     63  * \param motors_count number of motors
     64  */
     65  Bldc(const core::Object *parent, std::string name, uint8_t motors_count);
    7166
    72             /*!
    73             * \brief Destructor
    74             *
    75             */
    76             ~Bldc();
     67  /*!
     68  * \brief Destructor
     69  *
     70  */
     71  ~Bldc();
    7772
    78             /*!
    79             * \brief Lock user interface
    80             *
    81             */
    82             void LockUserInterface(void) const;
     73  /*!
     74  * \brief Lock user interface
     75  *
     76  */
     77  void LockUserInterface(void) const;
    8378
    84             /*!
    85             * \brief Unlock user interface
    86             *
    87             */
    88             void UnlockUserInterface(void) const;
     79  /*!
     80  * \brief Unlock user interface
     81  *
     82  */
     83  void UnlockUserInterface(void) const;
    8984
    90             /*!
    91             * \brief Use default plot
    92             *
    93             * \param tabwidget TabWidget to draw plots
    94             */
    95             void UseDefaultPlot(gui::TabWidget* tabwidget);
     85  /*!
     86  * \brief Use default plot
     87  *
     88  * \param tabwidget TabWidget to draw plots
     89  */
     90  void UseDefaultPlot(gui::TabWidget *tabwidget);
    9691
    97             /*!
    98             * \brief Output from motors
    99             *
    100             * First column is real speed if available, secund column is current if available
    101             *
    102             */
    103             core::cvmatrix *Output(void) const;
     92  /*!
     93  * \brief Output from motors
     94  *
     95  * First column is real speed if available, secund column is current if
     96  *available
     97  *
     98  */
     99  core::cvmatrix *Output(void) const;
    104100
    105             /*!
    106             * \brief Motors count
    107             *
    108             * \return number of motors
    109             */
    110             uint8_t MotorsCount(void) const;
     101  /*!
     102  * \brief Motors count
     103  *
     104  * \return number of motors
     105  */
     106  uint8_t MotorsCount(void) const;
    111107
    112             /*!
    113             * \brief Enable motors
    114             *
    115             * \param true to enable all motors
    116             */
    117             void SetEnabled(bool status);
     108  /*!
     109  * \brief Enable motors
     110  *
     111  * \param true to enable all motors
     112  */
     113  void SetEnabled(bool status);
    118114
    119             /*!
    120             * \brief Are motors enabled?
    121             *
    122             * \return true if motors are enabled
    123             */
    124             bool AreEnabled(void) const;
     115  /*!
     116  * \brief Are motors enabled?
     117  *
     118  * \return true if motors are enabled
     119  */
     120  bool AreEnabled(void) const;
    125121
    126             /*!
    127             * \brief Set motor power
    128             *
    129             * Changes the power (from 0 to 1) of a specific motor. \n
    130             * By default power is set to 1 for each motor which has no effect. \n
    131             * A value <1 will decrease the power of a motor sent to the reimplemented Bldc class through SetMotors. \n
    132             * The power value is applied after applying saturation between min value and max value.
    133             * So the resulting value cannot be higher than max value
    134             * but it can be lower than min value.
    135             *
    136             * \param motor_id id of the motor
    137             * \param value power value (from 0 to 1)
    138             *
    139             */
    140             void SetPower(int motor_id,float value);
     122  /*!
     123  * \brief Set motor power
     124  *
     125  * Changes the power (from 0 to 1) of a specific motor. \n
     126  * By default power is set to 1 for each motor which has no effect. \n
     127  * A value <1 will decrease the power of a motor sent to the reimplemented Bldc
     128  *class through SetMotors. \n
     129  * The power value is applied after applying saturation between min value and
     130  *max value.
     131  * So the resulting value cannot be higher than max value
     132  * but it can be lower than min value.
     133  *
     134  * \param motor_id id of the motor
     135  * \param value power value (from 0 to 1)
     136  *
     137  */
     138  void SetPower(int motor_id, float value);
    141139
    142             /*!
    143             * \brief Layout
    144             *
    145             * This the same Layout as passed to the constructor
    146             *
    147             * \return a Layout
    148             */
    149             gui::Layout* GetLayout(void) const;
     140  /*!
     141  * \brief Layout
     142  *
     143  * This the same Layout as passed to the constructor
     144  *
     145  * \return a Layout
     146  */
     147  gui::Layout *GetLayout(void) const;
    150148
    151             /*!
    152             * \brief Has speed measurement
    153             *
    154             * \return true if it has speed measurement
    155             */
    156             virtual bool HasSpeedMeasurement(void) const=0;
     149  /*!
     150  * \brief Has speed measurement
     151  *
     152  * \return true if it has speed measurement
     153  */
     154  virtual bool HasSpeedMeasurement(void) const = 0;
    157155
    158             /*!
    159             * \brief Has current measurement
    160             *
    161             * \return true if it has current measurement
    162             */
    163             virtual bool HasCurrentMeasurement(void) const=0;
     156  /*!
     157  * \brief Has current measurement
     158  *
     159  * \return true if it has current measurement
     160  */
     161  virtual bool HasCurrentMeasurement(void) const = 0;
    164162
    165         protected:
    166             core::cvmatrix *output;
     163protected:
     164  core::cvmatrix *output;
    167165
    168         private:
    169             /*!
    170             * \brief Update using provided datas
    171             *
    172             * Reimplemented from IODevice.
    173             *
    174             * \param data data from the parent to process
    175             */
    176             void UpdateFrom(const core::io_data *data);
     166private:
     167  /*!
     168  * \brief Update using provided datas
     169  *
     170  * Reimplemented from IODevice.
     171  *
     172  * \param data data from the parent to process
     173  */
     174  void UpdateFrom(const core::io_data *data);
    177175
    178             /*!
    179             * \brief Set motors values
    180             *
    181             * values size must be the same as MotorsCount()
    182             *
    183             * \param values set motors values
    184             */
    185             virtual void SetMotors(float* values)=0;
     176  /*!
     177  * \brief Set motors values
     178  *
     179  * values size must be the same as MotorsCount()
     180  *
     181  * \param values set motors values
     182  */
     183  virtual void SetMotors(float *values) = 0;
    186184
    187             class Bldc_impl* pimpl_;
    188     };
     185  class Bldc_impl *pimpl_;
     186};
    189187} // end namespace actuator
    190188} // end namespace framewor
  • trunk/include/FlairSensorActuator/Camera.h

    r4 r13  
    1818#include <cvimage.h>
    1919
    20 namespace flair
    21 {
    22     namespace gui
    23     {
    24         class GroupBox;
    25         class Tab;
    26         class TabWidget;
    27         class Picture;
    28         class GridLayout;
    29     }
     20namespace flair {
     21namespace gui {
     22class GroupBox;
     23class Tab;
     24class TabWidget;
     25class Picture;
     26class GridLayout;
     27}
    3028}
    3129
    32 namespace flair
    33 {
    34 namespace sensor
    35 {
    36     /*! \class Camera
    37     *
    38     * \brief Base class for Camera
    39     *
    40     * Use this class to define a custom Camera.
    41     *
    42     */
    43     class Camera : public core::IODevice
    44     {
    45         public:
    46             /*!
    47             * \brief Constructor
    48             *
    49             * Construct a Camera.
    50             *
    51             * \param parent parent
    52             * \param name name
    53             * \param width width
    54             * \param height height
    55             * \param format image format
    56             */
    57             Camera(const core::FrameworkManager* parent,std::string name,uint16_t width,uint16_t height,core::cvimage::Type::Format format);
     30namespace flair {
     31namespace sensor {
     32/*! \class Camera
     33*
     34* \brief Base class for Camera
     35*
     36* Use this class to define a custom Camera.
     37*
     38*/
     39class Camera : public core::IODevice {
     40public:
     41  /*!
     42  * \brief Constructor
     43  *
     44  * Construct a Camera.
     45  *
     46  * \param parent parent
     47  * \param name name
     48  * \param width width
     49  * \param height height
     50  * \param format image format
     51  */
     52  Camera(const core::FrameworkManager *parent, std::string name, uint16_t width,
     53         uint16_t height, core::cvimage::Type::Format format);
    5854
    59             /*!
    60             * \brief Constructor
    61             *
    62             * Construct a Camera. \n
    63             * This contructor must only be called for a simulated device.
    64             *
    65             * \param parent parent
    66             * \param name name
    67             */
    68             Camera(const core::IODevice* parent,std::string name);
     55  /*!
     56  * \brief Constructor
     57  *
     58  * Construct a Camera. \n
     59  * This contructor must only be called for a simulated device.
     60  *
     61  * \param parent parent
     62  * \param name name
     63  */
     64  Camera(const core::IODevice *parent, std::string name);
    6965
    70             /*!
    71             * \brief Destructor
    72             *
    73             */
    74             ~Camera();
     66  /*!
     67  * \brief Destructor
     68  *
     69  */
     70  ~Camera();
    7571
    76             /*!
    77             * \brief Use default plot
    78             *
    79             * \param image image to display
    80             */
    81             void UseDefaultPlot(const core::cvimage *image);
     72  /*!
     73  * \brief Use default plot
     74  *
     75  * \param image image to display
     76  */
     77  void UseDefaultPlot(const core::cvimage *image);
    8278
    83             /*!
    84             * \brief get Layout
    85             *
    86             * \return a Layout available
    87             */
    88             gui::GridLayout* GetLayout(void) const;
     79  /*!
     80  * \brief get Layout
     81  *
     82  * \return a Layout available
     83  */
     84  gui::GridLayout *GetLayout(void) const;
    8985
    90             /*!
    91             * \brief plot tab
    92             *
    93             * \return plot tab
    94             */
    95             gui::Tab* GetPlotTab(void) const;
     86  /*!
     87  * \brief plot tab
     88  *
     89  * \return plot tab
     90  */
     91  gui::Tab *GetPlotTab(void) const;
    9692
    97             /*!
    98             * \brief Save picture to file
    99             *
    100             * \param filename filename
    101             */
    102             void SaveToFile(std::string filename) const;
     93  /*!
     94  * \brief Save picture to file
     95  *
     96  * \param filename filename
     97  */
     98  void SaveToFile(std::string filename) const;
    10399
    104             /*!
    105             * \brief Width
    106             *
    107             * \return width
    108             */
    109             uint16_t Width(void) const;
     100  /*!
     101  * \brief Width
     102  *
     103  * \return width
     104  */
     105  uint16_t Width(void) const;
    110106
    111             /*!
    112             * \brief Height
    113             *
    114             * \return height
    115             */
    116             uint16_t Height(void) const;
     107  /*!
     108  * \brief Height
     109  *
     110  * \return height
     111  */
     112  uint16_t Height(void) const;
    117113
    118              /*!
    119             * \brief Output matrix
    120             *
    121             * Output matrix is of the same size as declared in constructor. \n
    122             *
    123             * \return the output matrix
    124             */
    125             core::cvimage* Output(void);
     114  /*!
     115 * \brief Output matrix
     116 *
     117 * Output matrix is of the same size as declared in constructor. \n
     118 *
     119 * \return the output matrix
     120 */
     121  core::cvimage *Output(void);
    126122
    127             core::DataType const &GetOutputDataType() const;
     123  core::DataType const &GetOutputDataType() const;
    128124
    129         protected:
    130             /*!
    131             * \brief get GroupBox
    132             *
    133             * \return a GroupBox available
    134             */
    135             gui::GroupBox* GetGroupBox(void) const;
     125protected:
     126  /*!
     127  * \brief get GroupBox
     128  *
     129  * \return a GroupBox available
     130  */
     131  gui::GroupBox *GetGroupBox(void) const;
    136132
    137             core::cvimage *output;
     133  core::cvimage *output;
    138134
    139         private:
    140             gui::Tab *main_tab,*sensor_tab,*plot_tab;
    141             gui::TabWidget *tab;
    142             gui::GroupBox* setup_groupbox;
    143             gui::GridLayout* setup_layout;
    144     };
     135private:
     136  gui::Tab *main_tab, *sensor_tab, *plot_tab;
     137  gui::TabWidget *tab;
     138  gui::GroupBox *setup_groupbox;
     139  gui::GridLayout *setup_layout;
     140};
    145141} // end namespace sensor
    146142} // end namespace flair
  • trunk/include/FlairSensorActuator/Controller.h

    r4 r13  
    2323
    2424namespace flair {
    25     namespace core {
    26         class Message;
    27     }
     25namespace core {
     26class Message;
     27}
    2828}
    2929
    30 namespace flair { namespace sensor {
     30namespace flair {
     31namespace sensor {
    3132
    32     enum class ControllerAction {
    33         SetLedOn,
    34         SetLedOff,
    35         Rumble,
    36         FlashLed,
    37         Exit
    38     };
     33enum class ControllerAction { SetLedOn, SetLedOff, Rumble, FlashLed, Exit };
    3934
    40     class RumbleMessage: public core::Message {
    41     public:
    42         RumbleMessage(unsigned int leftForce,unsigned int leftTimeout,unsigned int rightForce,unsigned int rightTimeout);
    43         unsigned int GetLeftForce() const;
    44         unsigned int GetLeftTimeout() const;
    45         unsigned int GetRightForce() const;
    46         unsigned int GetRightTimeout() const;
    47         void SetLeftForce(unsigned int leftForce);
    48         void SetLeftTimeout(unsigned int leftTimeout);
    49         void SetRightForce(unsigned int rightForce);
    50         void SetRightTimeout(unsigned int rightTimeout);
    51     private:
    52         static const unsigned int leftForceOffset=sizeof(ControllerAction);
    53         static const unsigned int leftTimeoutOffset=sizeof(ControllerAction)+sizeof(unsigned int);
    54         static const unsigned int rightForceOffset=sizeof(ControllerAction)+2*sizeof(unsigned int);
    55         static const unsigned int rightTimeoutOffset=sizeof(ControllerAction)+3*sizeof(unsigned int);
    56     };
     35class RumbleMessage : public core::Message {
     36public:
     37  RumbleMessage(unsigned int leftForce, unsigned int leftTimeout,
     38                unsigned int rightForce, unsigned int rightTimeout);
     39  unsigned int GetLeftForce() const;
     40  unsigned int GetLeftTimeout() const;
     41  unsigned int GetRightForce() const;
     42  unsigned int GetRightTimeout() const;
     43  void SetLeftForce(unsigned int leftForce);
     44  void SetLeftTimeout(unsigned int leftTimeout);
     45  void SetRightForce(unsigned int rightForce);
     46  void SetRightTimeout(unsigned int rightTimeout);
    5747
    58     class SwitchLedMessage: public core::Message {
    59     public:
    60         SwitchLedMessage(bool isOn,unsigned int ledId);
    61         bool IsOn() const;
    62         unsigned int GetLedId() const;
    63         void SetOn();
    64         void SetOff();
    65         void SetLedId(unsigned int ledId);
    66     private:
    67         static const unsigned int isOnOffset=sizeof(ControllerAction);
    68         static const unsigned int ledIdOffset=sizeof(ControllerAction)+sizeof(bool);
    69     };
     48private:
     49  static const unsigned int leftForceOffset = sizeof(ControllerAction);
     50  static const unsigned int leftTimeoutOffset =
     51      sizeof(ControllerAction) + sizeof(unsigned int);
     52  static const unsigned int rightForceOffset =
     53      sizeof(ControllerAction) + 2 * sizeof(unsigned int);
     54  static const unsigned int rightTimeoutOffset =
     55      sizeof(ControllerAction) + 3 * sizeof(unsigned int);
     56};
    7057
    71     class FlashLedMessage: public core::Message {
    72     public:
    73         FlashLedMessage(unsigned int ledId,unsigned int onTime,unsigned int offTime);
    74         unsigned int GetLedId() const;
    75         unsigned int GetOnTime() const;
    76         unsigned int GetOffTime() const;
    77         void SetLedId(unsigned int ledId);
    78         void SetOnTime(unsigned int onTime);
    79         void SetOffTime(unsigned int offTime);
    80     private:
    81         static const unsigned int ledIdOffset=sizeof(ControllerAction);
    82         static const unsigned int onTimeOffset=sizeof(ControllerAction)+sizeof(unsigned int);
    83         static const unsigned int offTimeOffset=sizeof(ControllerAction)+2*sizeof(unsigned int);
    84     };
     58class SwitchLedMessage : public core::Message {
     59public:
     60  SwitchLedMessage(bool isOn, unsigned int ledId);
     61  bool IsOn() const;
     62  unsigned int GetLedId() const;
     63  void SetOn();
     64  void SetOff();
     65  void SetLedId(unsigned int ledId);
    8566
    86 }}
     67private:
     68  static const unsigned int isOnOffset = sizeof(ControllerAction);
     69  static const unsigned int ledIdOffset =
     70      sizeof(ControllerAction) + sizeof(bool);
     71};
     72
     73class FlashLedMessage : public core::Message {
     74public:
     75  FlashLedMessage(unsigned int ledId, unsigned int onTime,
     76                  unsigned int offTime);
     77  unsigned int GetLedId() const;
     78  unsigned int GetOnTime() const;
     79  unsigned int GetOffTime() const;
     80  void SetLedId(unsigned int ledId);
     81  void SetOnTime(unsigned int onTime);
     82  void SetOffTime(unsigned int offTime);
     83
     84private:
     85  static const unsigned int ledIdOffset = sizeof(ControllerAction);
     86  static const unsigned int onTimeOffset =
     87      sizeof(ControllerAction) + sizeof(unsigned int);
     88  static const unsigned int offTimeOffset =
     89      sizeof(ControllerAction) + 2 * sizeof(unsigned int);
     90};
     91}
     92}
    8793
    8894#endif // CONTROLLER_H
  • trunk/include/FlairSensorActuator/Gps.h

    r4 r13  
    1717#include <nmea/nmea.h>
    1818
    19 namespace flair
    20 {
    21     namespace core
    22     {
    23         class cvmatrix;
    24         class FrameworkManager;
    25         class GeoCoordinate;
    26         class Vector3D;
    27     }
    28     namespace gui
    29     {
    30         class Layout;
    31         class DataPlot1D;
    32         class Tab;
    33         class TabWidget;
    34         class PushButton;
    35         class Map;
    36         class Label;
    37     }
     19namespace flair {
     20namespace core {
     21class cvmatrix;
     22class FrameworkManager;
     23class GeoCoordinate;
     24class Vector3D;
    3825}
    39 
    40 namespace flair
    41 {
    42 namespace sensor
    43 {
    44     /*! \class Gps
    45     *
    46     * \brief Base class for GPS
    47     */
    48     class Gps : public core::IODevice
    49     {
    50         public:
    51             /*!
    52             \enum FixQuality_t
    53             \brief Fix qualty indicators
    54             */
    55             enum class FixQuality_t {
    56                 Invalid=0,/*!< invalid */
    57                 Gps=1,/*!< Gps */
    58                 DGps=2,/*!< Differential Gps */
    59                 Pps=3,/*!< Pps */
    60                 Rtk=4,/*!< RTK */
    61                 RtkFloat=5,/*!< RTK float */
    62                 Estimated=6,/*!< Estimated */
    63                 Manual=7,/*!< Manual */
    64                 Simulation=8,/*!< Simulation */
    65                 };
    66 
    67             /*!
    68             \enum NMEAFlags_t
    69             \brief NMEA flags
    70             */
    71             enum NMEAFlags_t {
    72                 GGA=0x01,/*!< GGA */
    73                 VTG=0x02,/*!< VTG */
    74                 GST=0x04,/*!< GST */
    75                 };
    76 
    77             /*!
    78             * \brief Constructor
    79             *
    80             * Construct a Gps.
    81             *
    82             * \param parent parent
    83             * \param name name
    84             * \param NMEAFlags NMEA sentances to enable
    85             */
    86             Gps(const core::FrameworkManager* parent,std::string name,NMEAFlags_t NMEAFlags);
    87 
    88             /*!
    89             * \brief Destructor
    90             *
    91             */
    92             ~Gps();
    93 
    94             /*!
    95             * \brief Use default plot
    96             *
    97             */
    98             void UseDefaultPlot(void);
    99 
    100             /*!
    101             * \brief East plot
    102             *
    103             * \return east plot
    104             */
    105             gui::DataPlot1D* EPlot(void) const;
    106 
    107             /*!
    108             * \brief North plot
    109             *
    110             * \return north plot
    111             */
    112             gui::DataPlot1D* NPlot(void) const;
    113 
    114             /*!
    115             * \brief Up plot
    116             *
    117             * \return up plot
    118             */
    119             gui::DataPlot1D* UPlot(void) const;
    120 
    121             /*!
    122             * \brief East velocity plot
    123             *
    124             * \return east velocity plot
    125             */
    126             gui::DataPlot1D* VEPlot(void) const;
    127 
    128             /*!
    129             * \brief North velocity plot
    130             *
    131             * \return north velocity plot
    132             */
    133             gui::DataPlot1D* VNPlot(void) const;
    134 
    135             /*!
    136             * \brief Main tab
    137             *
    138             * \return main tab
    139             */
    140             gui::TabWidget* GetTab(void) const;
    141 
    142             /*!
    143             * \brief Setup Layout
    144             *
    145             * \return setup Layout
    146             */
    147             gui::Layout* GetLayout(void) const;
    148 
    149             /*!
    150             * \brief Plot tab
    151             *
    152             * \return plot Tab
    153             */
    154             gui::Tab* GetPlotTab(void) const;
    155 
    156             /*!
    157             * \brief Number of used satellites
    158             *
    159             * \return number of used satellites
    160             */
    161             uint16_t NbSat(void) const;
    162 
    163             /*!
    164             * \brief Fix Quality
    165             *
    166             * \return fix quality
    167             */
    168             FixQuality_t FixQuality(void) const;
    169 
    170             /*!
    171             * \brief Set reference for ENU coordinates
    172             *
    173             * The actual position is used as reference to calculate
    174             * ENU coordinates.
    175             *
    176             * \return fix quality
    177             */
    178             void SetRef(void);
    179 
    180             /*!
    181             * \brief Get ENU position
    182             *
    183             * \param point to store position
    184             */
    185             void GetENUPosition(core::Vector3D *point);
    186 
    187         protected:
    188             /*!
    189             * \brief Parse a NMEA frame
    190             *
    191             * This function must be called by the reimplemented class. \n
    192             * When a frame is parsed, GPS datas are filled.
    193             *
    194             * \param frame NMEA frame
    195             * \param frame_size frame size
    196             *
    197             */
    198             void parseFrame(const char *frame, int frame_size);
    199 
    200             NMEAFlags_t NMEAFlags;
    201 
    202         protected:
    203             core::GeoCoordinate *position;
    204 
    205         private:
    206             /*!
    207             * \brief Update using provided datas
    208             *
    209             * Reimplemented from IODevice.
    210             *
    211             * \param data data from the parent to process
    212             */
    213             void UpdateFrom(const core::io_data *data){};
    214 
    215             gui::Tab *main_tab,*sensor_tab;
    216             gui::TabWidget* tab;
    217             gui::PushButton *button_ref;
    218             gui::DataPlot1D* e_plot;
    219             gui::DataPlot1D* n_plot;
    220             gui::DataPlot1D* u_plot;
    221             gui::DataPlot1D* ve_plot;
    222             gui::DataPlot1D* vn_plot;
    223             gui::Tab* plot_tab;
    224             gui::Map *map;
    225             gui::Label *nb_sat_label,*fix_label;
    226             uint16_t nb_sat;
    227             FixQuality_t fix;
    228             bool take_ref;
    229             nmeaINFO info;
    230             nmeaPARSER parser;
    231             nmeaGPGGA pack;
    232             nmeaPOS pos;
    233             double lat_ref,long_ref,alt_ref;
    234 
    235             //matrix
    236             core::cvmatrix *output;
    237     };
     26namespace gui {
     27class Layout;
     28class DataPlot1D;
     29class Tab;
     30class TabWidget;
     31class PushButton;
     32class Map;
     33class Label;
     34}
     35}
     36
     37namespace flair {
     38namespace sensor {
     39/*! \class Gps
     40*
     41* \brief Base class for GPS
     42*/
     43class Gps : public core::IODevice {
     44public:
     45  /*!
     46  \enum FixQuality_t
     47  \brief Fix qualty indicators
     48  */
     49  enum class FixQuality_t {
     50    Invalid = 0,    /*!< invalid */
     51    Gps = 1,        /*!< Gps */
     52    DGps = 2,       /*!< Differential Gps */
     53    Pps = 3,        /*!< Pps */
     54    Rtk = 4,        /*!< RTK */
     55    RtkFloat = 5,   /*!< RTK float */
     56    Estimated = 6,  /*!< Estimated */
     57    Manual = 7,     /*!< Manual */
     58    Simulation = 8, /*!< Simulation */
     59  };
     60
     61  /*!
     62  \enum NMEAFlags_t
     63  \brief NMEA flags
     64  */
     65  enum NMEAFlags_t {
     66    GGA = 0x01, /*!< GGA */
     67    VTG = 0x02, /*!< VTG */
     68    GST = 0x04, /*!< GST */
     69  };
     70
     71  /*!
     72  * \brief Constructor
     73  *
     74  * Construct a Gps.
     75  *
     76  * \param parent parent
     77  * \param name name
     78  * \param NMEAFlags NMEA sentances to enable
     79  */
     80  Gps(const core::FrameworkManager *parent, std::string name,
     81      NMEAFlags_t NMEAFlags);
     82
     83  /*!
     84  * \brief Destructor
     85  *
     86  */
     87  ~Gps();
     88
     89  /*!
     90  * \brief Use default plot
     91  *
     92  */
     93  void UseDefaultPlot(void);
     94
     95  /*!
     96  * \brief East plot
     97  *
     98  * \return east plot
     99  */
     100  gui::DataPlot1D *EPlot(void) const;
     101
     102  /*!
     103  * \brief North plot
     104  *
     105  * \return north plot
     106  */
     107  gui::DataPlot1D *NPlot(void) const;
     108
     109  /*!
     110  * \brief Up plot
     111  *
     112  * \return up plot
     113  */
     114  gui::DataPlot1D *UPlot(void) const;
     115
     116  /*!
     117  * \brief East velocity plot
     118  *
     119  * \return east velocity plot
     120  */
     121  gui::DataPlot1D *VEPlot(void) const;
     122
     123  /*!
     124  * \brief North velocity plot
     125  *
     126  * \return north velocity plot
     127  */
     128  gui::DataPlot1D *VNPlot(void) const;
     129
     130  /*!
     131  * \brief Main tab
     132  *
     133  * \return main tab
     134  */
     135  gui::TabWidget *GetTab(void) const;
     136
     137  /*!
     138  * \brief Setup Layout
     139  *
     140  * \return setup Layout
     141  */
     142  gui::Layout *GetLayout(void) const;
     143
     144  /*!
     145  * \brief Plot tab
     146  *
     147  * \return plot Tab
     148  */
     149  gui::Tab *GetPlotTab(void) const;
     150
     151  /*!
     152  * \brief Number of used satellites
     153  *
     154  * \return number of used satellites
     155  */
     156  uint16_t NbSat(void) const;
     157
     158  /*!
     159  * \brief Fix Quality
     160  *
     161  * \return fix quality
     162  */
     163  FixQuality_t FixQuality(void) const;
     164
     165  /*!
     166  * \brief Set reference for ENU coordinates
     167  *
     168  * The actual position is used as reference to calculate
     169  * ENU coordinates.
     170  *
     171  * \return fix quality
     172  */
     173  void SetRef(void);
     174
     175  /*!
     176  * \brief Get ENU position
     177  *
     178  * \param point to store position
     179  */
     180  void GetENUPosition(core::Vector3D *point);
     181
     182protected:
     183  /*!
     184  * \brief Parse a NMEA frame
     185  *
     186  * This function must be called by the reimplemented class. \n
     187  * When a frame is parsed, GPS datas are filled.
     188  *
     189  * \param frame NMEA frame
     190  * \param frame_size frame size
     191  *
     192  */
     193  void parseFrame(const char *frame, int frame_size);
     194
     195  NMEAFlags_t NMEAFlags;
     196
     197protected:
     198  core::GeoCoordinate *position;
     199
     200private:
     201  /*!
     202  * \brief Update using provided datas
     203  *
     204  * Reimplemented from IODevice.
     205  *
     206  * \param data data from the parent to process
     207  */
     208  void UpdateFrom(const core::io_data *data){};
     209
     210  gui::Tab *main_tab, *sensor_tab;
     211  gui::TabWidget *tab;
     212  gui::PushButton *button_ref;
     213  gui::DataPlot1D *e_plot;
     214  gui::DataPlot1D *n_plot;
     215  gui::DataPlot1D *u_plot;
     216  gui::DataPlot1D *ve_plot;
     217  gui::DataPlot1D *vn_plot;
     218  gui::Tab *plot_tab;
     219  gui::Map *map;
     220  gui::Label *nb_sat_label, *fix_label;
     221  uint16_t nb_sat;
     222  FixQuality_t fix;
     223  bool take_ref;
     224  nmeaINFO info;
     225  nmeaPARSER parser;
     226  nmeaGPGGA pack;
     227  nmeaPOS pos;
     228  double lat_ref, long_ref, alt_ref;
     229
     230  // matrix
     231  core::cvmatrix *output;
     232};
    238233} // end namespace sensor
    239234} // end namespace framewor
  • trunk/include/FlairSensorActuator/Gx3_25_imu.h

    r4 r13  
    1818
    1919namespace flair {
    20     namespace core {
    21         class FrameworkManager;
    22         class SerialPort;
    23     }
     20namespace core {
     21class FrameworkManager;
     22class SerialPort;
     23}
    2424}
    2525
    2626class Gx3_25_imu_impl;
    2727
    28 namespace flair { namespace sensor {
    29     /*! \class Gx3_25_imu
    30     *
    31     * \brief Class for 3dmgx3-25 Imu
    32     */
    33     class Gx3_25_imu : public Imu, public core::Thread {
    34         friend class ::Gx3_25_imu_impl;
     28namespace flair {
     29namespace sensor {
     30/*! \class Gx3_25_imu
     31*
     32* \brief Class for 3dmgx3-25 Imu
     33*/
     34class Gx3_25_imu : public Imu, public core::Thread {
     35  friend class ::Gx3_25_imu_impl;
    3536
    36         public:
    37             /*!
    38             \enum Command_t
    39             \brief Command for the continuous mode
    40             */
    41             enum Command_t{
    42                 EulerAnglesAndAngularRates=0xcf,/*!< Euler angles and angular rates */
    43                 AccelerationAngularRateAndOrientationMatrix=0xc8,/*!< Acceleration, angular rate and orientation matrix */
    44                 };
     37public:
     38  /*!
     39  \enum Command_t
     40  \brief Command for the continuous mode
     41  */
     42  enum Command_t {
     43    EulerAnglesAndAngularRates = 0xcf, /*!< Euler angles and angular rates */
     44    AccelerationAngularRateAndOrientationMatrix =
     45        0xc8, /*!< Acceleration, angular rate and orientation matrix */
     46  };
    4547
    46             /*!
    47             * \brief Constructor
    48             *
    49             * Construct a Gx3_25_imu.
    50             *
    51             * \param parent parent
    52             * \param name name
    53             * \param serialport SerialPort
    54             * \param command command for continuous mode
    55             * \param priority priority of the Thread
    56             */
    57             Gx3_25_imu(const core::FrameworkManager* parent,std::string name,core::SerialPort *serialport,Command_t command,uint8_t priority);
     48  /*!
     49  * \brief Constructor
     50  *
     51  * Construct a Gx3_25_imu.
     52  *
     53  * \param parent parent
     54  * \param name name
     55  * \param serialport SerialPort
     56  * \param command command for continuous mode
     57  * \param priority priority of the Thread
     58  */
     59  Gx3_25_imu(const core::FrameworkManager *parent, std::string name,
     60             core::SerialPort *serialport, Command_t command, uint8_t priority);
    5861
    59             /*!
    60             * \brief Destructor
    61             *
    62             */
    63             ~Gx3_25_imu();
     62  /*!
     63  * \brief Destructor
     64  *
     65  */
     66  ~Gx3_25_imu();
    6467
    65         private:
    66             /*!
    67             * \brief Run function
    68             *
    69             * Reimplemented from Thread.
    70             *
    71             */
    72             void Run(void);
     68private:
     69  /*!
     70  * \brief Run function
     71  *
     72  * Reimplemented from Thread.
     73  *
     74  */
     75  void Run(void);
    7376
    74             /*!
    75             * \brief Update using provided datas
    76             *
    77             * Reimplemented from IODevice.
    78             *
    79             * \param data data from the parent to process
    80             */
    81             void UpdateFrom(const core::io_data *data){};
     77  /*!
     78  * \brief Update using provided datas
     79  *
     80  * Reimplemented from IODevice.
     81  *
     82  * \param data data from the parent to process
     83  */
     84  void UpdateFrom(const core::io_data *data){};
    8285
    83             class Gx3_25_imu_impl* pimpl_;
    84     };
     86  class Gx3_25_imu_impl *pimpl_;
     87};
    8588} // end namespace sensor
    8689} // end namespace flair
  • trunk/include/FlairSensorActuator/HokuyoUTM30Lx.h

    r4 r13  
    2121#include <vector>
    2222
    23 namespace flair
    24 {
    25     namespace core
    26     {
    27         class cvmatrix;
    28         class FrameworkManager;
    29         class SerialPort;
    30         class Mutex;
    31     }
    32     namespace gui
    33     {
    34         class Tab;
    35         class TabWidget;
    36         class RangeFinderPlot;
    37     }
     23namespace flair {
     24namespace core {
     25class cvmatrix;
     26class FrameworkManager;
     27class SerialPort;
     28class Mutex;
     29}
     30namespace gui {
     31class Tab;
     32class TabWidget;
     33class RangeFinderPlot;
     34}
    3835}
    3936
    40 namespace flair
    41 {
    42 namespace sensor
    43 {
    44     /*! \class HokuyoUTM30Lx
    45     *
    46     * \brief Classe intégrant le telemetre laser Hokuyo UTM 30lx
    47     */
    48     class HokuyoUTM30Lx : public core::Thread, public LaserRangeFinder
    49     {
    50         public:
     37namespace flair {
     38namespace sensor {
     39/*! \class HokuyoUTM30Lx
     40*
     41* \brief Classe intégrant le telemetre laser Hokuyo UTM 30lx
     42*/
     43class HokuyoUTM30Lx : public core::Thread, public LaserRangeFinder {
     44public:
     45  /*!
     46 * \brief Constructor
     47 *
     48 * Construct a Hokuyo UTM30-Lx.
     49 *
     50 * \param parent parent
     51 * \param name name
     52 * \param serialport serialport
     53 * \param priority priority of the Thread
     54 */
     55  HokuyoUTM30Lx(const core::FrameworkManager *parent, std::string name,
     56                core::SerialPort *serialport, uint8_t priority);
     57  void getMesure(int startStep, int endStep, int clusterCount, int interval,
     58                 int scanNumber = 0);
     59  core::cvmatrix *getDatas(void);
    5160
    52              /*!
    53             * \brief Constructor
    54             *
    55             * Construct a Hokuyo UTM30-Lx.
    56             *
    57             * \param parent parent
    58             * \param name name
    59             * \param serialport serialport
    60             * \param priority priority of the Thread
    61             */
    62             HokuyoUTM30Lx(const core::FrameworkManager* parent,std::string name,core::SerialPort *serialport,uint8_t priority);
    63             void getMesure(int startStep, int endStep,int clusterCount, int interval, int scanNumber=0);
    64             core::cvmatrix* getDatas(void);
     61  /*!
     62  * \brief Use default plot
     63  *
     64  */
     65  void UseDefaultPlot(void);
     66  /*!
     67  * \brief Destructor
     68  *
     69  */
     70  ~HokuyoUTM30Lx();
    6571
    66             /*!
    67             * \brief Use default plot
    68             *
    69             */
    70             void UseDefaultPlot(void);
    71             /*!
    72             * \brief Destructor
    73             *
    74             */
    75             ~HokuyoUTM30Lx();
     72private:
     73  core::SerialPort *serialport;
     74  core::Mutex *bufRetMut;
     75  core::Mutex *sendingCmdMut;
     76  gui::Tab *main_tab;
     77  gui::TabWidget *tab;
     78  gui::RangeFinderPlot *plot;
    7679
    77         private:
    78             core::SerialPort *serialport;
    79             core::Mutex* bufRetMut;
    80             core::Mutex* sendingCmdMut;
    81             gui::Tab* main_tab;
    82             gui::TabWidget* tab;
    83             gui::RangeFinderPlot* plot;
     80  // matrix
     81  core::cvmatrix *output;
    8482
    85             //matrix
    86             core::cvmatrix *output;
     83  std::queue<std::string> bufRet;
    8784
    88                         std::queue<std::string> bufRet;
     85  /*!
     86  * \brief Run function
     87  *
     88  * Reimplemented from Thread.
     89  *
     90  */
     91  void Run(void);
     92  /*!
     93  * \brief Send a command
     94  * \param command Command to send (see Hokuyo UTM 30-LX doc for more
     95  * informations)
     96  * \return Return code
     97  */
     98  std::string sendCommand(std::string command);
     99  /*!
     100  * \brief Start the laser
     101  *
     102  */
     103  void startLaser(void);
     104  /*!
     105  * \brief Stop the laser
     106  *
     107  */
     108  void stopLaser(void);
     109  /*!
     110* \brief Stop and reset the laser's settings
     111*
     112*/
     113  void resetConfig(void);
     114  /*!
     115* \brief Decode incomming datas
     116* \param datas Datas to decode
     117* \param startStep Set the first mesured point
     118* Decode mesured points from incoming datas and fill the output matrix
     119*/
     120  void decodeDatas(std::vector<std::string> datas, int startStep);
     121  /*!
     122  * \brief Explode a string into a vector
     123  * \param str The string to explode
     124  * \param delimiter The character separating elements
     125  * \return A vector containing the elements
     126  */
     127  static std::vector<std::string> explode(const std::string str,
     128                                          char delimiter);
     129  /*!
     130* \brief Calculate the checksum
     131* \param code Data from which calculate
     132* \param byte Data's size
     133* \return A character corresponding to the code's checksum
     134*/
     135  static int encodeSum(const char *code, int byte);
     136  /*!
     137* \brief Check if a data correspond to its checksum
     138* \param data Datas to check
     139*/
     140  static bool checkSum(std::string data);
     141  /*!
     142* \brief Decode datas using the 2 character encoding
     143* \param data Datas to decode
     144* \return Decoded datas
     145*/
     146  static float decode2car(const char *data);
     147  /*!
     148* \brief Decode datas using the 3 character encoding
     149* \param data Datas to decode
     150* \return Decoded datas
     151*/
     152  static float decode3car(const char *data);
     153  /*!
     154* \brief Decode datas using the 4 character encoding
     155* \param data Datas to decode
     156* \return Decoded datas
     157*/
     158  static float decode4car(const char *data);
    89159
    90             /*!
    91             * \brief Run function
    92             *
    93             * Reimplemented from Thread.
    94             *
    95             */
    96             void Run(void);
    97             /*!
    98             * \brief Send a command
    99             * \param command Command to send (see Hokuyo UTM 30-LX doc for more informations)
    100             * \return Return code
    101             */
    102             std::string sendCommand(std::string command);
    103             /*!
    104             * \brief Start the laser
    105             *
    106             */
    107             void startLaser(void);
    108             /*!
    109             * \brief Stop the laser
    110             *
    111             */
    112                         void stopLaser(void);
    113                         /*!
    114             * \brief Stop and reset the laser's settings
    115             *
    116             */
    117                     void resetConfig(void);
    118                     /*!
    119             * \brief Decode incomming datas
    120             * \param datas Datas to decode
    121             * \param startStep Set the first mesured point
    122             * Decode mesured points from incoming datas and fill the output matrix
    123             */
    124                     void decodeDatas(std::vector<std::string> datas, int startStep);
    125             /*!
    126             * \brief Explode a string into a vector
    127             * \param str The string to explode
    128             * \param delimiter The character separating elements
    129             * \return A vector containing the elements
    130             */
    131                         static std::vector<std::string> explode(const std::string str, char delimiter);
    132                         /*!
    133             * \brief Calculate the checksum
    134             * \param code Data from which calculate
    135             * \param byte Data's size
    136             * \return A character corresponding to the code's checksum
    137             */
    138                         static int encodeSum(const char* code, int byte);
    139                         /*!
    140             * \brief Check if a data correspond to its checksum
    141             * \param data Datas to check
    142             */
    143                         static bool checkSum(std::string data);
    144                         /*!
    145             * \brief Decode datas using the 2 character encoding
    146             * \param data Datas to decode
    147             * \return Decoded datas
    148             */
    149                         static float decode2car(const char* data);
    150                         /*!
    151             * \brief Decode datas using the 3 character encoding
    152             * \param data Datas to decode
    153             * \return Decoded datas
    154             */
    155                         static float decode3car(const char* data);
    156                         /*!
    157             * \brief Decode datas using the 4 character encoding
    158             * \param data Datas to decode
    159             * \return Decoded datas
    160             */
    161                         static float decode4car(const char* data);
    162 
    163                         /*!
    164             * \brief Update using provided datas
    165             *
    166             * Reimplemented from IODevice.
    167             *
    168             * \param data data from the parent to process
    169             */
    170             void UpdateFrom(const core::io_data *data){};
    171 
    172     };
     160  /*!
     161* \brief Update using provided datas
     162*
     163* Reimplemented from IODevice.
     164*
     165* \param data data from the parent to process
     166*/
     167  void UpdateFrom(const core::io_data *data){};
     168};
    173169} // end namespace sensor
    174170} // end namespace framewor
  • trunk/include/FlairSensorActuator/HostEthController.h

    r4 r13  
    1111//  version:    $Id: $
    1212//
    13 //  purpose:    Base class for host side remote controls that talks to target side through ethernet connection
     13//  purpose:    Base class for host side remote controls that talks to target
     14//  side through ethernet connection
    1415//
    1516//
     
    2425
    2526namespace flair {
    26     namespace core {
    27         class FrameworkManager;
    28         class cvmatrix;
    29         class TcpSocket;
    30         class Socket;
    31         class Mutex;
    32     }
    33     namespace gui {
    34         class Tab;
    35         class TabWidget;
    36         class DataPlot1D;
    37     }
     27namespace core {
     28class FrameworkManager;
     29class cvmatrix;
     30class TcpSocket;
     31class Socket;
     32class Mutex;
     33}
     34namespace gui {
     35class Tab;
     36class TabWidget;
     37class DataPlot1D;
     38}
    3839}
    3940
    40 namespace flair { namespace sensor {
    41     enum class ControllerAction;
     41namespace flair {
     42namespace sensor {
     43enum class ControllerAction;
    4244
    43     /*! \class HostEthController
    44     *
    45     * \brief Base Class for host side remote controls that talks to target side through ethernet connection
    46     *
    47     * There are 2 communication channels:
    48     *   - 1 connection with the ground station to display the values. Output for analog sticks is normalized in the range [-1, 1] (float values)
    49     *   - 1 connection with the target to send the controller values (and receive controller state modification requests)
    50     */
    51     class HostEthController : public core::Thread, public core::IODevice {
    52     public:
    53         HostEthController(const core::FrameworkManager* parent,std::string name,std::string address,int port,uint32_t period=10,uint32_t _bitsPerAxis=7,uint8_t priority=0);
    54         ~HostEthController();
    55         void DrawUserInterface();
    56     protected:
    57         std::string controllerName;
    58         core::TcpSocket *controlSocket; //connection to the target
    59         core::Socket *dataSocket;
    60         std::string targetAddress;
    61         int targetPort;
    62         gui::Tab *tab;
    63         gui::TabWidget *tabWidget;
    64         virtual bool IsDataFrameReady() { return true;};
    65         virtual void CompleteDataFrameGrab() {};
    66 //        int8_t *datas;
    67 //        uint8_t dataSize;
    68         char *dataFrameBuffer;
    69         size_t dataFrameSize;
    70         virtual void ProcessMessage(core::Message *controllerAction) {};
     45/*! \class HostEthController
     46*
     47* \brief Base Class for host side remote controls that talks to target side
     48*through ethernet connection
     49*
     50* There are 2 communication channels:
     51*   - 1 connection with the ground station to display the values. Output for
     52*analog sticks is normalized in the range [-1, 1] (float values)
     53*   - 1 connection with the target to send the controller values (and receive
     54*controller state modification requests)
     55*/
     56class HostEthController : public core::Thread, public core::IODevice {
     57public:
     58  HostEthController(const core::FrameworkManager *parent, std::string name,
     59                    std::string address, int port, uint32_t period = 10,
     60                    uint32_t _bitsPerAxis = 7, uint8_t priority = 0);
     61  ~HostEthController();
     62  void DrawUserInterface();
    7163
    72         virtual std::string GetAxisDescription(unsigned int axis);
    73         virtual void GetAxisData()=0; //responsible for getting the axis data from the hardware
    74         unsigned int axisNumber;
    75         core::cvmatrix* axis;
    76         gui::DataPlot1D **axisPlot;
    77         uint32_t bitsPerAxis;
    78         uint32_t nativeBitsPerAxis;
     64protected:
     65  std::string controllerName;
     66  core::TcpSocket *controlSocket; // connection to the target
     67  core::Socket *dataSocket;
     68  std::string targetAddress;
     69  int targetPort;
     70  gui::Tab *tab;
     71  gui::TabWidget *tabWidget;
     72  virtual bool IsDataFrameReady() { return true; };
     73  virtual void CompleteDataFrameGrab(){};
     74  //        int8_t *datas;
     75  //        uint8_t dataSize;
     76  char *dataFrameBuffer;
     77  size_t dataFrameSize;
     78  virtual void ProcessMessage(core::Message *controllerAction){};
    7979
    80         virtual std::string GetButtonDescription(unsigned int button);
    81         virtual void GetButtonData()=0; //responsible for getting the button data from the hardware
    82         unsigned int buttonNumber;
    83         core::cvmatrix* button;
    84         uint8_t buttonOffset;
    85         bool meaningfulDataAvailable;
     80  virtual std::string GetAxisDescription(unsigned int axis);
     81  virtual void
     82  GetAxisData() = 0; // responsible for getting the axis data from the hardware
     83  unsigned int axisNumber;
     84  core::cvmatrix *axis;
     85  gui::DataPlot1D **axisPlot;
     86  uint32_t bitsPerAxis;
     87  uint32_t nativeBitsPerAxis;
    8688
    87     private:
    88         class DataSender : public core::Thread {
    89         public:
    90             DataSender(Object* parent,HostEthController* hostEthController,std::string name,uint8_t priority=0);
    91             void Run();
    92         private:
    93             HostEthController* hostEthController;
    94         };
    95         DataSender *dataSender;
     89  virtual std::string GetButtonDescription(unsigned int button);
     90  virtual void GetButtonData() = 0; // responsible for getting the button data
     91                                    // from the hardware
     92  unsigned int buttonNumber;
     93  core::cvmatrix *button;
     94  uint8_t buttonOffset;
     95  bool meaningfulDataAvailable;
    9696
    97         bool ControllerInitialization();
    98         bool ConnectedWithTarget();
    99         void SendControllerInfo();
    100         void Run();
    101         void BuildDataFrame();
    102         bool writeBits(uint16_t value,uint8_t valueSizeInBits,char *buffer,uint8_t offsetInBits);
    103         core::Mutex *connectionEstablishedMutex;
    104     };
     97private:
     98  class DataSender : public core::Thread {
     99  public:
     100    DataSender(Object *parent, HostEthController *hostEthController,
     101               std::string name, uint8_t priority = 0);
     102    void Run();
    105103
    106 }}
     104  private:
     105    HostEthController *hostEthController;
     106  };
     107  DataSender *dataSender;
     108
     109  bool ControllerInitialization();
     110  bool ConnectedWithTarget();
     111  void SendControllerInfo();
     112  void Run();
     113  void BuildDataFrame();
     114  bool writeBits(uint16_t value, uint8_t valueSizeInBits, char *buffer,
     115                 uint8_t offsetInBits);
     116  core::Mutex *connectionEstablishedMutex;
     117};
     118}
     119}
    107120
    108121#endif // HOSTETHCONTROLLER_H
  • trunk/include/FlairSensorActuator/Imu.h

    r4 r13  
    1717
    1818namespace flair {
    19     namespace core {
    20         class ImuData;
    21         class OneAxisRotation;
    22     }
    23     namespace gui {
    24         class Tab;
    25         class TabWidget;
    26         class GroupBox;
    27         class Layout;
    28         class DataPlot1D;
    29     }
     19namespace core {
     20class ImuData;
     21class OneAxisRotation;
     22}
     23namespace gui {
     24class Tab;
     25class TabWidget;
     26class GroupBox;
     27class Layout;
     28class DataPlot1D;
     29}
    3030}
    3131
    3232class Ahrs_impl;
    3333
    34 namespace flair { namespace sensor {
    35     /*! \class Imu
    36     *
    37     * \brief Base class for Imu
    38     *
    39     * Use this class to define a custom Imu.
    40     *
    41     */
    42     class Imu : public core::IODevice {
    43         friend class ::Ahrs_impl;
     34namespace flair {
     35namespace sensor {
     36/*! \class Imu
     37*
     38* \brief Base class for Imu
     39*
     40* Use this class to define a custom Imu.
     41*
     42*/
     43class Imu : public core::IODevice {
     44  friend class ::Ahrs_impl;
    4445
    45         public:
    46             /*!
    47             * \brief Constructor
    48             *
    49             * Construct an Imu.
    50             *
    51             * \param parent parent
    52             * \param name name
    53             */
    54             Imu(const core::FrameworkManager *parent,std::string name);
     46public:
     47  /*!
     48  * \brief Constructor
     49  *
     50  * Construct an Imu.
     51  *
     52  * \param parent parent
     53  * \param name name
     54  */
     55  Imu(const core::FrameworkManager *parent, std::string name);
    5556
    56             /*!
    57             * \brief Constructor
    58             *
    59             * Construct an Imu. \n
    60             * This contructor must only be called for a simulated device.
    61             *
    62             * \param parent parent
    63             * \param name name
    64             */
    65             Imu(const core::IODevice *parent,std::string name);
     57  /*!
     58  * \brief Constructor
     59  *
     60  * Construct an Imu. \n
     61  * This contructor must only be called for a simulated device.
     62  *
     63  * \param parent parent
     64  * \param name name
     65  */
     66  Imu(const core::IODevice *parent, std::string name);
    6667
    67             /*!
    68             * \brief Destructor
    69             *
    70             */
    71             ~Imu();
     68  /*!
     69  * \brief Destructor
     70  *
     71  */
     72  ~Imu();
    7273
    73             /*!
    74             * \brief Setup Layout
    75             *
    76             * \return setup Layout
    77             */
    78             gui::Layout *GetLayout(void) const;
     74  /*!
     75  * \brief Setup Layout
     76  *
     77  * \return setup Layout
     78  */
     79  gui::Layout *GetLayout(void) const;
    7980
    80             /*!
    81             * \brief Lock user interface
    82             *
    83             */
    84             void LockUserInterface(void) const;
     81  /*!
     82  * \brief Lock user interface
     83  *
     84  */
     85  void LockUserInterface(void) const;
    8586
    86             /*!
    87             * \brief Unlock user interface
    88             *
    89             */
    90             void UnlockUserInterface(void) const;
     87  /*!
     88  * \brief Unlock user interface
     89  *
     90  */
     91  void UnlockUserInterface(void) const;
    9192
    92             /*!
    93             * \brief Use default plot
    94             *
    95             */
    96             void UseDefaultPlot(void);
     93  /*!
     94  * \brief Use default plot
     95  *
     96  */
     97  void UseDefaultPlot(void);
    9798
    98             /*!
    99             * \brief Plot tab
    100             *
    101             * \return plot Tab
    102             */
    103             gui::Tab *GetPlotTab(void) const;
     99  /*!
     100  * \brief Plot tab
     101  *
     102  * \return plot Tab
     103  */
     104  gui::Tab *GetPlotTab(void) const;
    104105
    105         protected:
    106             /*!
    107             * \brief Setup GroupBox
    108             *
    109             * \return setup GroupBox
    110             */
    111             gui::GroupBox *GetGroupBox(void) const;
     106protected:
     107  /*!
     108  * \brief Setup GroupBox
     109  *
     110  * \return setup GroupBox
     111  */
     112  gui::GroupBox *GetGroupBox(void) const;
    112113
    113             /*!
    114             * \brief UpdateImu
    115             *
    116             * The reimplemented class must call this function as soon as IMU datas are available. \n
    117             * It handles the data rotation if it was defined.
    118             *
    119             */
    120             void UpdateImu();
     114  /*!
     115  * \brief UpdateImu
     116  *
     117  * The reimplemented class must call this function as soon as IMU datas are
     118  *available. \n
     119  * It handles the data rotation if it was defined.
     120  *
     121  */
     122  void UpdateImu();
    121123
    122             /*!
    123             * \brief Get imu datas
    124             *
    125             * \param imuData imu datas
    126             */
    127             void GetDatas(core::ImuData **imuData) const;
     124  /*!
     125  * \brief Get imu datas
     126  *
     127  * \param imuData imu datas
     128  */
     129  void GetDatas(core::ImuData **imuData) const;
    128130
     131private:
     132  gui::Tab *mainTab, *sensorTab, *plotTab;
     133  gui::TabWidget *tab;
     134  gui::GroupBox *setupGroupbox;
     135  core::OneAxisRotation *rotation;
     136  core::ImuData *imuData;
    129137
    130         private:
    131             gui::Tab *mainTab,*sensorTab,*plotTab;
    132             gui::TabWidget* tab;
    133             gui::GroupBox *setupGroupbox;
    134             core::OneAxisRotation* rotation;
    135             core::ImuData *imuData;
    136 
    137             gui::DataPlot1D *axPlot,*ayPlot,*azPlot;
    138             gui::DataPlot1D *gxPlot,*gyPlot,*gzPlot;
    139             gui::DataPlot1D *mxPlot,*myPlot,*mzPlot;
    140     };
     138  gui::DataPlot1D *axPlot, *ayPlot, *azPlot;
     139  gui::DataPlot1D *gxPlot, *gyPlot, *gzPlot;
     140  gui::DataPlot1D *mxPlot, *myPlot, *mzPlot;
     141};
    141142} // end namespace sensor
    142143} // end namespace flair
  • trunk/include/FlairSensorActuator/LaserRangeFinder.h

    r4 r13  
    1616#include <IODevice.h>
    1717
    18 namespace flair
    19 {
    20     namespace core
    21     {
    22         class FrameworkManager;
    23         class cvmatrix;
    24 
    25     }
    26     namespace gui
    27     {
    28         class Tab;
    29         class TabWidget;
    30         class GroupBox;
    31         class Layout;
    32         class RangeFinderPlot;
    33     }
     18namespace flair {
     19namespace core {
     20class FrameworkManager;
     21class cvmatrix;
     22}
     23namespace gui {
     24class Tab;
     25class TabWidget;
     26class GroupBox;
     27class Layout;
     28class RangeFinderPlot;
     29}
    3430}
    3531
    36 namespace flair
    37 {
    38 namespace sensor
    39 {
    40     /*! \class LaserRangeFinder
    41     *
    42     * \brief Classe generique intégrant les telemetres laser
    43     */
    44     class LaserRangeFinder : public core::IODevice
    45     {
    46         public:
    47             /*!
    48             * \brief Constructor
    49             *
    50             * Construct a Laser Range Finder.
    51             *
    52             * \param parent parent
    53             * \param name name
    54             */
    55             LaserRangeFinder(const core::FrameworkManager* parent,std::string name);
    56             /*!
    57             * \brief Constructor
    58             *
    59             * Construct a UsRangeFinder. Simulation part.
    60             *
    61             * \param parent parent
    62             * \param name name
    63             */
    64             LaserRangeFinder(const core::IODevice* parent,std::string name);
    65             /*!
    66             * \brief Destructor
    67             *
    68             */
    69             ~LaserRangeFinder();
     32namespace flair {
     33namespace sensor {
     34/*! \class LaserRangeFinder
     35*
     36* \brief Classe generique intégrant les telemetres laser
     37*/
     38class LaserRangeFinder : public core::IODevice {
     39public:
     40  /*!
     41  * \brief Constructor
     42  *
     43  * Construct a Laser Range Finder.
     44  *
     45  * \param parent parent
     46  * \param name name
     47  */
     48  LaserRangeFinder(const core::FrameworkManager *parent, std::string name);
     49  /*!
     50  * \brief Constructor
     51  *
     52  * Construct a UsRangeFinder. Simulation part.
     53  *
     54  * \param parent parent
     55  * \param name name
     56  */
     57  LaserRangeFinder(const core::IODevice *parent, std::string name);
     58  /*!
     59  * \brief Destructor
     60  *
     61  */
     62  ~LaserRangeFinder();
    7063
    71             /*!
    72             * \brief Use default plot
    73             *
    74             */
    75             void UseDefaultPlot(void);
     64  /*!
     65  * \brief Use default plot
     66  *
     67  */
     68  void UseDefaultPlot(void);
    7669
    77             /*!
    78             * \brief Plot
    79             *
    80             * \return DataPlot1D
    81             */
    82             gui::RangeFinderPlot* GetPlot(void) const;
     70  /*!
     71  * \brief Plot
     72  *
     73  * \return DataPlot1D
     74  */
     75  gui::RangeFinderPlot *GetPlot(void) const;
    8376
    84             /*!
    85             * \brief Setup Layout
    86             *
    87             * \return a Layout available
    88             */
    89             gui::Layout* GetLayout(void) const;
     77  /*!
     78  * \brief Setup Layout
     79  *
     80  * \return a Layout available
     81  */
     82  gui::Layout *GetLayout(void) const;
    9083
    91             /*!
    92             * \brief Plot tab
    93             *
    94             * \return plot Tab
    95             */
    96             gui::Tab* GetPlotTab(void) const;
     84  /*!
     85  * \brief Plot tab
     86  *
     87  * \return plot Tab
     88  */
     89  gui::Tab *GetPlotTab(void) const;
    9790
    98             /*!
    99             * \brief Value
    100             *
    101             * \return output value
    102             */
    103             float Value(void) const;
     91  /*!
     92  * \brief Value
     93  *
     94  * \return output value
     95  */
     96  float Value(void) const;
    10497
    105         protected:
    106         /*!
    107             * \brief Output matrix
    108             *
    109             * \return output matrix
    110             */
    111             core::cvmatrix *output;
     98protected:
     99  /*!
     100      * \brief Output matrix
     101      *
     102      * \return output matrix
     103      */
     104  core::cvmatrix *output;
    112105
    113             /*!
    114             * \brief Setup GroupBox
    115             *
    116             * \return a GroupBox available
    117             */
    118             gui::GroupBox* GetGroupBox(void) const;
     106  /*!
     107  * \brief Setup GroupBox
     108  *
     109  * \return a GroupBox available
     110  */
     111  gui::GroupBox *GetGroupBox(void) const;
    119112
    120         private:
    121             /*!
    122             * \brief Update using provided datas
    123             *
    124             * Reimplemented from IODevice.
    125             *
    126             * \param data data from the parent to process
    127             */
    128             void UpdateFrom(const core::io_data *data){};
     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  void UpdateFrom(const core::io_data *data){};
    129122
    130             gui::Tab* main_tab;
    131             gui::TabWidget *tab;
    132             gui::GroupBox* setup_groupbox;
    133             gui::Tab* sensor_tab;
    134             gui::RangeFinderPlot* plot;
    135             gui::Tab* plot_tab;
    136 
    137     };
     123  gui::Tab *main_tab;
     124  gui::TabWidget *tab;
     125  gui::GroupBox *setup_groupbox;
     126  gui::Tab *sensor_tab;
     127  gui::RangeFinderPlot *plot;
     128  gui::Tab *plot_tab;
     129};
    138130} // end namespace sensor
    139131} // end namespace framewor
  • trunk/include/FlairSensorActuator/Mb800.h

    r4 r13  
    1717#include <Gps.h>
    1818
    19 namespace flair
    20 {
    21     namespace core
    22     {
    23         class FrameworkManager;
    24         class SerialPort;
    25     }
     19namespace flair {
     20namespace core {
     21class FrameworkManager;
     22class SerialPort;
     23}
    2624}
    2725
    28 namespace flair
    29 {
    30 namespace sensor
    31 {
    32     /*! \class Mb800
    33     *
    34     * \brief Class for mb800 gps receiver
    35     */
    36     class Mb800 : public core::Thread, public Gps
    37     {
    38         public:
    39             /*!
    40             * \brief Constructor
    41             *
    42             * Construct a Mb800.
    43             *
    44             * \param parent parent
    45             * \param name name
    46             * \param serialport serialport
    47             * \param NMEAFlags NMEA sentances to enable
    48             * \param priority priority of the Thread
    49             */
    50             Mb800(const core::FrameworkManager* parent,std::string name,core::SerialPort *serialport,Gps::NMEAFlags_t NMEAFlags,uint8_t priority);
     26namespace flair {
     27namespace sensor {
     28/*! \class Mb800
     29*
     30* \brief Class for mb800 gps receiver
     31*/
     32class Mb800 : public core::Thread, public Gps {
     33public:
     34  /*!
     35  * \brief Constructor
     36  *
     37  * Construct a Mb800.
     38  *
     39  * \param parent parent
     40  * \param name name
     41  * \param serialport serialport
     42  * \param NMEAFlags NMEA sentances to enable
     43  * \param priority priority of the Thread
     44  */
     45  Mb800(const core::FrameworkManager *parent, std::string name,
     46        core::SerialPort *serialport, Gps::NMEAFlags_t NMEAFlags,
     47        uint8_t priority);
    5148
    52             /*!
    53             * \brief Destructor
    54             *
    55             */
    56             ~Mb800();
     49  /*!
     50  * \brief Destructor
     51  *
     52  */
     53  ~Mb800();
    5754
    58         private:
    59             /*!
    60             * \brief Update using provided datas
    61             *
    62             * Reimplemented from IODevice.
    63             *
    64             * \param data data from the parent to process
    65             */
    66             void UpdateFrom(const core::io_data *data){};
     55private:
     56  /*!
     57  * \brief Update using provided datas
     58  *
     59  * Reimplemented from IODevice.
     60  *
     61  * \param data data from the parent to process
     62  */
     63  void UpdateFrom(const core::io_data *data){};
    6764
    68             /*!
    69             * \brief Run function
    70             *
    71             * Reimplemented from Thread.
    72             *
    73             */
    74             void Run(void);
     65  /*!
     66  * \brief Run function
     67  *
     68  * Reimplemented from Thread.
     69  *
     70  */
     71  void Run(void);
    7572
    76             void Sync(void);
    77             core::SerialPort *serialport;
    78     };
     73  void Sync(void);
     74  core::SerialPort *serialport;
     75};
    7976} // end namespace sensor
    8077} // end namespace framewor
  • trunk/include/FlairSensorActuator/Novatel.h

    r4 r13  
    1717#include <Gps.h>
    1818
    19 namespace flair
    20 {
    21     namespace core
    22     {
    23         class FrameworkManager;
    24         class SerialPort;
    25     }
     19namespace flair {
     20namespace core {
     21class FrameworkManager;
     22class SerialPort;
     23}
    2624}
    2725
    28 namespace flair
    29 {
    30 namespace sensor
    31 {
    32     /*! \class Novatel
    33     *
    34     * \brief Class for Novatel gps receiver
    35     */
    36     class Novatel : public core::Thread, public Gps
    37     {
    38         public:
    39             /*!
    40             * \brief Constructor
    41             *
    42             * Construct a Novatel.
    43             *
    44             * \param parent parent
    45             * \param name name
    46             * \param serialport serialport
    47             * \param NMEAFlags NMEA sentances to enable
    48             * \param priority priority of the Thread
    49             */
    50             Novatel(const core::FrameworkManager* parent,std::string name,core::SerialPort *serialport,Gps::NMEAFlags_t NMEAFlags,uint8_t priority);
     26namespace flair {
     27namespace sensor {
     28/*! \class Novatel
     29*
     30* \brief Class for Novatel gps receiver
     31*/
     32class Novatel : public core::Thread, public Gps {
     33public:
     34  /*!
     35  * \brief Constructor
     36  *
     37  * Construct a Novatel.
     38  *
     39  * \param parent parent
     40  * \param name name
     41  * \param serialport serialport
     42  * \param NMEAFlags NMEA sentances to enable
     43  * \param priority priority of the Thread
     44  */
     45  Novatel(const core::FrameworkManager *parent, std::string name,
     46          core::SerialPort *serialport, Gps::NMEAFlags_t NMEAFlags,
     47          uint8_t priority);
    5148
    52             /*!
    53             * \brief Destructor
    54             *
    55             */
    56             ~Novatel();
     49  /*!
     50  * \brief Destructor
     51  *
     52  */
     53  ~Novatel();
    5754
    58         private:
    59             /*!
    60             * \brief Update using provided datas
    61             *
    62             * Reimplemented from IODevice.
    63             *
    64             * \param data data from the parent to process
    65             */
    66             void UpdateFrom(const core::io_data *data){};
     55private:
     56  /*!
     57  * \brief Update using provided datas
     58  *
     59  * Reimplemented from IODevice.
     60  *
     61  * \param data data from the parent to process
     62  */
     63  void UpdateFrom(const core::io_data *data){};
    6764
    68             /*!
    69             * \brief Run function
    70             *
    71             * Reimplemented from Thread.
    72             *
    73             */
    74             void Run(void);
     65  /*!
     66  * \brief Run function
     67  *
     68  * Reimplemented from Thread.
     69  *
     70  */
     71  void Run(void);
    7572
    76             core::SerialPort *serialport;
    77             void Sync(void);
    78     };
     73  core::SerialPort *serialport;
     74  void Sync(void);
     75};
    7976} // end namespace sensor
    8077} // end namespace framewor
  • trunk/include/FlairSensorActuator/Ps3Eye.h

    r4 r13  
    1616#include "V4LCamera.h"
    1717
    18 namespace flair
    19 {
    20     namespace core
    21     {
    22         class cvimage;
    23         class FrameworkManager;
    24     }
    25     namespace gui
    26     {
    27         class GridLayout;
    28         class DoubleSpinBox;
    29         class CheckBox;
    30     }
     18namespace flair {
     19namespace core {
     20class cvimage;
     21class FrameworkManager;
     22}
     23namespace gui {
     24class GridLayout;
     25class DoubleSpinBox;
     26class CheckBox;
     27}
    3128}
    3229
    33 namespace flair
    34 {
    35 namespace sensor
    36 {
    37     /*! \class Ps3Eye
    38     *
    39     * \brief Class for Ps3Eye camera
    40     */
    41     class Ps3Eye : public V4LCamera
    42     {
     30namespace flair {
     31namespace sensor {
     32/*! \class Ps3Eye
     33*
     34* \brief Class for Ps3Eye camera
     35*/
     36class Ps3Eye : public V4LCamera {
    4337
    44         public:
    45             /*!
    46             * \brief Constructor
    47             *
    48             * Construct a Ps3Eye.
    49             *
    50             * \param parent parent
    51             * \param name name
    52             * \param camera_index index of the camera, ie /dev/videox
    53             * \param priority priority of the Thread
    54             */
    55             Ps3Eye(const core::FrameworkManager* parent,std::string name,int camera_index,uint8_t priority);
     38public:
     39  /*!
     40  * \brief Constructor
     41  *
     42  * Construct a Ps3Eye.
     43  *
     44  * \param parent parent
     45  * \param name name
     46  * \param camera_index index of the camera, ie /dev/videox
     47  * \param priority priority of the Thread
     48  */
     49  Ps3Eye(const core::FrameworkManager *parent, std::string name,
     50         int camera_index, uint8_t priority);
    5651
    57             /*!
    58             * \brief Destructor
    59             *
    60             */
    61             ~Ps3Eye();
     52  /*!
     53  * \brief Destructor
     54  *
     55  */
     56  ~Ps3Eye();
    6257
    63         private:
    64     };
     58private:
     59};
    6560} // end namespace sensor
    6661} // end namespace flair
  • trunk/include/FlairSensorActuator/RadioReceiver.h

    r4 r13  
    1717#include <stdint.h>
    1818
    19 namespace flair
    20 {
    21     namespace core
    22     {
    23         class FrameworkManager;
    24         class cvmatrix;
    25     }
    26     namespace gui
    27     {
    28         class Tab;
    29         class TabWidget;
    30         class Layout;
    31     }
     19namespace flair {
     20namespace core {
     21class FrameworkManager;
     22class cvmatrix;
     23}
     24namespace gui {
     25class Tab;
     26class TabWidget;
     27class Layout;
     28}
    3229}
    3330
    34 namespace flair
    35 {
    36 namespace sensor
    37 {
    38     /*! \class RadioReceiver
    39     *
    40     * \brief Base class for radio receiver
    41     */
    42     class RadioReceiver : public core::IODevice
    43     {
    44         public:
    45             /*!
    46             * \brief Constructor
    47             *
    48             * Construct a RadioReceiver.
    49             *
    50             * \param parent parent
    51             * \param name name
    52             * \param nb_channels number of supported channels
    53             */
    54             RadioReceiver(const core::FrameworkManager* parent,std::string name,unsigned int nb_channels);
     31namespace flair {
     32namespace sensor {
     33/*! \class RadioReceiver
     34*
     35* \brief Base class for radio receiver
     36*/
     37class RadioReceiver : public core::IODevice {
     38public:
     39  /*!
     40  * \brief Constructor
     41  *
     42  * Construct a RadioReceiver.
     43  *
     44  * \param parent parent
     45  * \param name name
     46  * \param nb_channels number of supported channels
     47  */
     48  RadioReceiver(const core::FrameworkManager *parent, std::string name,
     49                unsigned int nb_channels);
    5550
    56             /*!
    57             * \brief Destructor
    58             *
    59             */
    60             ~RadioReceiver();
     51  /*!
     52  * \brief Destructor
     53  *
     54  */
     55  ~RadioReceiver();
    6156
    62             /*!
    63             * \brief get channel value
    64             *
    65             * \param id channel id
    66             * \return value of the channel, between 0 and 1.
    67             *  Returns -1 if channel is out of bound
    68             */
    69             float ChannelValue(unsigned int id) const;
     57  /*!
     58  * \brief get channel value
     59  *
     60  * \param id channel id
     61  * \return value of the channel, between 0 and 1.
     62  *  Returns -1 if channel is out of bound
     63  */
     64  float ChannelValue(unsigned int id) const;
    7065
    71             /*!
    72             * \brief Is transmitter connected?
    73             *
    74             * \return true if transmitter is connected
    75             */
    76             bool IsConnected(void) const;
     66  /*!
     67  * \brief Is transmitter connected?
     68  *
     69  * \return true if transmitter is connected
     70  */
     71  bool IsConnected(void) const;
    7772
    78             /*!
    79             * \brief Setup Layout
    80             *
    81             * \return a Layout available
    82             */
    83             gui::Layout* GetLayout(void) const;
     73  /*!
     74  * \brief Setup Layout
     75  *
     76  * \return a Layout available
     77  */
     78  gui::Layout *GetLayout(void) const;
    8479
    85         private:
    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){};
     80private:
     81  /*!
     82  * \brief Update using provided datas
     83  *
     84  * Reimplemented from IODevice.
     85  *
     86  * \param data data from the parent to process
     87  */
     88  void UpdateFrom(const core::io_data *data){};
    9489
    95             core::cvmatrix *output;
    96             bool is_connected;
    97             unsigned int nb_channels;
    98             gui::Tab* main_tab;
    99             gui::TabWidget* tab;
    100             gui::Tab* setup_tab;
    101     };
     90  core::cvmatrix *output;
     91  bool is_connected;
     92  unsigned int nb_channels;
     93  gui::Tab *main_tab;
     94  gui::TabWidget *tab;
     95  gui::Tab *setup_tab;
     96};
    10297} // end namespace sensor
    10398} // end namespace flair
  • trunk/include/FlairSensorActuator/SimuBldc.h

    r4 r13  
    1616#include <Bldc.h>
    1717
    18 namespace flair
    19 {
    20     namespace core
    21     {
    22         class SharedMem;
    23         class IODevice;
    24         class cvmatrix;
    25     }
    26     namespace gui
    27     {
    28         class DoubleSpinBox;
    29         class Layout;
    30     }
     18namespace flair {
     19namespace core {
     20class SharedMem;
     21class IODevice;
     22class cvmatrix;
     23}
     24namespace gui {
     25class DoubleSpinBox;
     26class Layout;
     27}
    3128}
    3229
    33 namespace flair
    34 {
    35 namespace actuator
    36 {
    37     /*! \class SimuBldc
    38     *
    39     * \brief Class for a simulation bldc
    40     *
    41     */
    42     class SimuBldc : public Bldc
    43     {
    44         public:
    45             /*!
    46             * \brief Constructor
    47             *
    48             * Construct a SimuBldc. Control part.
    49             *
    50             * \param parent parent
    51             * \param layout layout
    52             * \param name name
    53             * \param motors_count number of motors
    54             * \param dev_id device id
    55             */
    56             SimuBldc(const core::IODevice* parent,gui::Layout* layout,std::string name,uint8_t motors_count,uint32_t dev_id);
     30namespace flair {
     31namespace actuator {
     32/*! \class SimuBldc
     33*
     34* \brief Class for a simulation bldc
     35*
     36*/
     37class SimuBldc : public Bldc {
     38public:
     39  /*!
     40  * \brief Constructor
     41  *
     42  * Construct a SimuBldc. Control part.
     43  *
     44  * \param parent parent
     45  * \param layout layout
     46  * \param name name
     47  * \param motors_count number of motors
     48  * \param dev_id device id
     49  */
     50  SimuBldc(const core::IODevice *parent, gui::Layout *layout, std::string name,
     51           uint8_t motors_count, uint32_t dev_id);
    5752
    58             /*!
    59             * \brief Constructor
    60             *
    61             * Construct a SimuBldc. Simulation part.
    62             *
    63             * \param parent parent
    64             * \param name name
    65             * \param motors_count number of motors
    66             * \param dev_id device id
    67             */
    68             SimuBldc(const core::Object* parent,std::string name,uint8_t motors_count,uint32_t dev_id);
     53  /*!
     54  * \brief Constructor
     55  *
     56  * Construct a SimuBldc. Simulation part.
     57  *
     58  * \param parent parent
     59  * \param name name
     60  * \param motors_count number of motors
     61  * \param dev_id device id
     62  */
     63  SimuBldc(const core::Object *parent, std::string name, uint8_t motors_count,
     64           uint32_t dev_id);
    6965
    70             /*!
    71             * \brief Destructor
    72             *
    73             */
    74             ~SimuBldc();
     66  /*!
     67  * \brief Destructor
     68  *
     69  */
     70  ~SimuBldc();
    7571
    76             /*!
    77             * \brief Get motors speeds.
    78             *
    79             * This function should only be used for the simulation part.
    80             *
    81             * \param value array to store motors speeds
    82             */
    83             void GetSpeeds(float* value) const;
     72  /*!
     73  * \brief Get motors speeds.
     74  *
     75  * This function should only be used for the simulation part.
     76  *
     77  * \param value array to store motors speeds
     78  */
     79  void GetSpeeds(float *value) const;
    8480
    85             /*!
    86             * \brief Has speed measurement
    87             *
    88             * Reimplemented from Bldc. \n
    89             *
    90             * \return true if it has speed measurement
    91             */
    92             bool HasSpeedMeasurement(void) const{return false;};
     81  /*!
     82  * \brief Has speed measurement
     83  *
     84  * Reimplemented from Bldc. \n
     85  *
     86  * \return true if it has speed measurement
     87  */
     88  bool HasSpeedMeasurement(void) const { return false; };
    9389
    94             /*!
    95             * \brief Has current measurement
    96             *
    97             * Reimplemented from Bldc. \n
    98             *
    99             * \return true if it has current measurement
    100             */
    101             bool HasCurrentMeasurement(void) const{return false;};
     90  /*!
     91  * \brief Has current measurement
     92  *
     93  * Reimplemented from Bldc. \n
     94  *
     95  * \return true if it has current measurement
     96  */
     97  bool HasCurrentMeasurement(void) const { return false; };
    10298
    103         private:
    104             /*!
    105             * \brief Set motors values
    106             *
    107             * Reimplemented from Bldc. \n
    108             * Values size must be the same as MotorsCount()
    109             *
    110             * \param values motor values
    111             */
    112             void SetMotors(float* value);
     99private:
     100  /*!
     101  * \brief Set motors values
     102  *
     103  * Reimplemented from Bldc. \n
     104  * Values size must be the same as MotorsCount()
     105  *
     106  * \param values motor values
     107  */
     108  void SetMotors(float *value);
    113109
    114             core::SharedMem *shmem;
    115             gui::DoubleSpinBox *k;
    116     };
     110  core::SharedMem *shmem;
     111  gui::DoubleSpinBox *k;
     112};
    117113} // end namespace actuator
    118114} // end namespace flair
  • trunk/include/FlairSensorActuator/SimuCamera.h

    r4 r13  
    1818#include <cxcore.h>
    1919
    20 namespace flair
    21 {
    22     namespace core
    23     {
    24         class SharedMem;
    25     }
    26     namespace gui
    27     {
    28         class SpinBox;
    29     }
     20namespace flair {
     21namespace core {
     22class SharedMem;
     23}
     24namespace gui {
     25class SpinBox;
     26}
    3027}
    3128
    32 namespace flair
    33 {
    34 namespace sensor
    35 {
    36     /*! \class SimuCamera
    37     *
    38     * \brief Class for a simulation camera
    39     */
    40     class SimuCamera : public core::Thread, public Camera
    41     {
    42         public:
    43             /*!
    44             * \brief Constructor
    45             *
    46             * Construct a SimuCamera. Control part.
    47             *
    48             * \param parent parent
    49             * \param name name
    50             * \param width width
    51             * \param height height
    52             * \param channels number of channels
    53             * \param dev_id device id
    54             * \param priority priority of the Thread
    55             */
    56             SimuCamera(const core::FrameworkManager* parent,std::string name,uint16_t width,uint16_t height,uint8_t channels,uint32_t dev_id,uint8_t priority);
     29namespace flair {
     30namespace sensor {
     31/*! \class SimuCamera
     32*
     33* \brief Class for a simulation camera
     34*/
     35class SimuCamera : public core::Thread, public Camera {
     36public:
     37  /*!
     38  * \brief Constructor
     39  *
     40  * Construct a SimuCamera. Control part.
     41  *
     42  * \param parent parent
     43  * \param name name
     44  * \param width width
     45  * \param height height
     46  * \param channels number of channels
     47  * \param dev_id device id
     48  * \param priority priority of the Thread
     49  */
     50  SimuCamera(const core::FrameworkManager *parent, std::string name,
     51             uint16_t width, uint16_t height, uint8_t channels, uint32_t dev_id,
     52             uint8_t priority);
    5753
    58             /*!
    59             * \brief Constructor
    60             *
    61             * Construct a SimuCamera. Simulation part.\n
    62             * The Thread of this class should not be run.
    63             *
    64             * \param parent parent
    65             * \param name name
    66             * \param width width
    67             * \param height height
    68             * \param channels number of channels
    69             * \param dev_id device id
    70             */
    71             SimuCamera(const core::IODevice* parent,std::string name,uint16_t width,uint16_t height,uint8_t channels,uint32_t dev_id);
     54  /*!
     55  * \brief Constructor
     56  *
     57  * Construct a SimuCamera. Simulation part.\n
     58  * The Thread of this class should not be run.
     59  *
     60  * \param parent parent
     61  * \param name name
     62  * \param width width
     63  * \param height height
     64  * \param channels number of channels
     65  * \param dev_id device id
     66  */
     67  SimuCamera(const core::IODevice *parent, std::string name, uint16_t width,
     68             uint16_t height, uint8_t channels, uint32_t dev_id);
    7269
    73             /*!
    74             * \brief Destructor
    75             *
    76             */
    77             ~SimuCamera();
     70  /*!
     71  * \brief Destructor
     72  *
     73  */
     74  ~SimuCamera();
    7875
    79         protected:
    80             /*!
    81             * \brief SharedMem to access datas
    82             *
    83             */
    84             core::SharedMem *shmem;
     76protected:
     77  /*!
     78  * \brief SharedMem to access datas
     79  *
     80  */
     81  core::SharedMem *shmem;
    8582
    86         private:
    87             /*!
    88             * \brief Run function
    89             *
    90             * Reimplemented from Thread.
    91             *
    92             */
    93             void Run(void);
     83private:
     84  /*!
     85  * \brief Run function
     86  *
     87  * Reimplemented from Thread.
     88  *
     89  */
     90  void Run(void);
    9491
    95             /*!
    96             * \brief Update using provided datas
    97             *
    98             * Reimplemented from IODevice.
    99             *
    100             * \param data data from the parent to process
    101             */
    102             void UpdateFrom(const core::io_data *data){};
     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){};
    103100
    104             gui::SpinBox *data_rate;
    105             size_t buf_size;
    106             IplImage* img;
    107     };
     101  gui::SpinBox *data_rate;
     102  size_t buf_size;
     103  IplImage *img;
     104};
    108105} // end namespace sensor
    109106} // end namespace flair
  • trunk/include/FlairSensorActuator/SimuGps.h

    r4 r13  
    1717#include <Gps.h>
    1818
    19 namespace flair
    20 {
    21     namespace core
    22     {
    23         class FrameworkManager;
    24     }
     19namespace flair {
     20namespace core {
     21class FrameworkManager;
     22}
    2523}
    2624
    27 namespace flair
    28 {
    29 namespace sensor
    30 {
    31     /*! \class SimuGps
    32     *
    33     * \brief Class for a simulation GPS
    34     */
    35     class SimuGps : public core::Thread, public Gps
    36     {
    37         public:
    38             /*!
    39             * \brief Constructor
    40             *
    41             * Construct a Novatel.
    42             *
    43             * \param parent parent
    44             * \param name name
    45             * \param NMEAFlags NMEA sentances to enable
    46             * \param priority priority of the Thread
    47             */
    48             SimuGps(const core::FrameworkManager* parent,std::string name,Gps::NMEAFlags_t NMEAFlags,uint8_t priority);
     25namespace flair {
     26namespace sensor {
     27/*! \class SimuGps
     28*
     29* \brief Class for a simulation GPS
     30*/
     31class SimuGps : public core::Thread, public Gps {
     32public:
     33  /*!
     34  * \brief Constructor
     35  *
     36  * Construct a Novatel.
     37  *
     38  * \param parent parent
     39  * \param name name
     40  * \param NMEAFlags NMEA sentances to enable
     41  * \param priority priority of the Thread
     42  */
     43  SimuGps(const core::FrameworkManager *parent, std::string name,
     44          Gps::NMEAFlags_t NMEAFlags, uint8_t priority);
    4945
    50             /*!
    51             * \brief Destructor
    52             *
    53             */
    54             ~SimuGps();
     46  /*!
     47  * \brief Destructor
     48  *
     49  */
     50  ~SimuGps();
    5551
    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){};
     52private:
     53  /*!
     54  * \brief Update using provided datas
     55  *
     56  * Reimplemented from IODevice.
     57  *
     58  * \param data data from the parent to process
     59  */
     60  void UpdateFrom(const core::io_data *data){};
    6561
    66             /*!
    67             * \brief Run function
    68             *
    69             * Reimplemented from Thread.
    70             *
    71             */
    72             void Run(void);
    73     };
     62  /*!
     63  * \brief Run function
     64  *
     65  * Reimplemented from Thread.
     66  *
     67  */
     68  void Run(void);
     69};
    7470} // end namespace sensor
    7571} // end namespace framewor
  • trunk/include/FlairSensorActuator/SimuImu.h

    r4 r13  
    1818
    1919namespace flair {
    20     namespace core    {
    21         class SharedMem;
    22         class AhrsData;
    23     }
    24     namespace gui {
    25         class SpinBox;
    26     }
     20namespace core {
     21class SharedMem;
     22class AhrsData;
     23}
     24namespace gui {
     25class SpinBox;
     26}
    2727}
    2828
    29 namespace flair { namespace sensor {
    30     /*! \class SimuImu
    31     *
    32     * \brief Class for a simulation Imu
    33     */
    34     class SimuImu : public Imu, public core::Thread {
    35         public:
    36             /*!
    37             * \brief Constructor
    38             *
    39             * Construct a SimuImu. Control part.
    40             *
    41             * \param parent parent
    42             * \param name name
    43             * \param dev_id device id
    44             * \param priority priority of the Thread
    45             */
    46             SimuImu(const core::FrameworkManager* parent,std::string name,uint32_t dev_id,uint8_t priority);
     29namespace flair {
     30namespace sensor {
     31/*! \class SimuImu
     32*
     33* \brief Class for a simulation Imu
     34*/
     35class SimuImu : public Imu, public core::Thread {
     36public:
     37  /*!
     38  * \brief Constructor
     39  *
     40  * Construct a SimuImu. Control part.
     41  *
     42  * \param parent parent
     43  * \param name name
     44  * \param dev_id device id
     45  * \param priority priority of the Thread
     46  */
     47  SimuImu(const core::FrameworkManager *parent, std::string name,
     48          uint32_t dev_id, uint8_t priority);
    4749
    48             /*!
    49             * \brief Constructor
    50             *
    51             * Construct a SimuImu. Simulation part.\n
    52             * The Thread of this class should not be run.
    53             *
    54             * \param parent parent
    55             * \param name name
    56             * \param dev_id device id
    57             */
    58             SimuImu(const core::IODevice* parent,std::string name,uint32_t dev_id);
     50  /*!
     51  * \brief Constructor
     52  *
     53  * Construct a SimuImu. Simulation part.\n
     54  * The Thread of this class should not be run.
     55  *
     56  * \param parent parent
     57  * \param name name
     58  * \param dev_id device id
     59  */
     60  SimuImu(const core::IODevice *parent, std::string name, uint32_t dev_id);
    5961
    60             /*!
    61             * \brief Destructor
    62             *
    63             */
    64             ~SimuImu();
     62  /*!
     63  * \brief Destructor
     64  *
     65  */
     66  ~SimuImu();
    6567
    66         private:
    67             /*!
    68             * \brief Run function
    69             *
    70             * Reimplemented from Thread.
    71             *
    72             */
    73             void Run(void);
     68private:
     69  /*!
     70  * \brief Run function
     71  *
     72  * Reimplemented from Thread.
     73  *
     74  */
     75  void Run(void);
    7476
    75             /*!
    76             * \brief Update using provided datas
    77             *
    78             * Reimplemented from IODevice.
    79             *
    80             * \param data data from the parent to process
    81             */
    82             void UpdateFrom(const core::io_data *data);
     77  /*!
     78  * \brief Update using provided datas
     79  *
     80  * Reimplemented from IODevice.
     81  *
     82  * \param data data from the parent to process
     83  */
     84  void UpdateFrom(const core::io_data *data);
    8385
    84             typedef struct {
    85                 float q0;
    86                 float q1;
    87                 float q2;
    88                 float q3;
    89                 float wx;
    90                 float wy;
    91                 float wz;
    92             } imu_states_t;
    93             gui::SpinBox *data_rate;
    94             core::SharedMem *shmem;
    95             core::AhrsData *ahrsData;
    96     };
     86  typedef struct {
     87    float q0;
     88    float q1;
     89    float q2;
     90    float q3;
     91    float wx;
     92    float wy;
     93    float wz;
     94  } imu_states_t;
     95  gui::SpinBox *data_rate;
     96  core::SharedMem *shmem;
     97  core::AhrsData *ahrsData;
     98};
    9799} // end namespace sensor
    98100} // end namespace flair
  • trunk/include/FlairSensorActuator/SimuLaser.h

    r4 r13  
    1717#include <Thread.h>
    1818
    19 namespace flair
    20 {
    21     namespace core
    22     {
    23         class SharedMem;
    24     }
    25     namespace gui
    26     {
    27         class SpinBox;
    28     }
     19namespace flair {
     20namespace core {
     21class SharedMem;
     22}
     23namespace gui {
     24class SpinBox;
     25}
    2926}
    3027
    31 namespace flair
    32 {
    33 namespace sensor
    34 {
    35     /*! \class SimuUs
    36     *
    37     * \brief Class for a simulation UsRangeFinder
    38     */
    39     class SimuLaser : public core::Thread, public LaserRangeFinder
    40     {
    41         public:
    42             /*!
    43             * \brief Constructor
    44             *
    45             * Construct a SimuUs. Control part.
    46             *
    47             * \param parent parent
    48             * \param name name
    49             * \param dev_id device id
    50             * \param priority priority of the Thread
    51             */
    52             SimuLaser(const core::FrameworkManager* parent,std::string name,uint32_t dev_id,uint8_t priority);
     28namespace flair {
     29namespace sensor {
     30/*! \class SimuUs
     31*
     32* \brief Class for a simulation UsRangeFinder
     33*/
     34class SimuLaser : public core::Thread, public LaserRangeFinder {
     35public:
     36  /*!
     37  * \brief Constructor
     38  *
     39  * Construct a SimuUs. Control part.
     40  *
     41  * \param parent parent
     42  * \param name name
     43  * \param dev_id device id
     44  * \param priority priority of the Thread
     45  */
     46  SimuLaser(const core::FrameworkManager *parent, std::string name,
     47            uint32_t dev_id, uint8_t priority);
    5348
    54             /*!
    55             * \brief Constructor
    56             *
    57             * Construct a SimuUs. Simulation part.\n
    58             * The Thread of this class should not be run.
    59             *
    60             * \param parent parent
    61             * \param name name
    62             * \param dev_id device id
    63             */
    64             SimuLaser(const core::IODevice* parent,std::string name,uint32_t dev_id);
     49  /*!
     50  * \brief Constructor
     51  *
     52  * Construct a SimuUs. Simulation part.\n
     53  * The Thread of this class should not be run.
     54  *
     55  * \param parent parent
     56  * \param name name
     57  * \param dev_id device id
     58  */
     59  SimuLaser(const core::IODevice *parent, std::string name, uint32_t dev_id);
    6560
    66             /*!
    67             * \brief Destructor
    68             *
    69             */
    70             ~SimuLaser();
     61  /*!
     62  * \brief Destructor
     63  *
     64  */
     65  ~SimuLaser();
    7166
    72         protected:
    73             /*!
    74             * \brief SharedMem to access datas
    75             *
    76             */
    77             core::SharedMem *shmem;
     67protected:
     68  /*!
     69  * \brief SharedMem to access datas
     70  *
     71  */
     72  core::SharedMem *shmem;
    7873
    79         private:
    80             /*!
    81             * \brief Update using provided datas
    82             *
    83             * Reimplemented from IODevice.
    84             *
    85             * \param data data from the parent to process
    86             */
    87             void UpdateFrom(const core::io_data *data){};
     74private:
     75  /*!
     76  * \brief Update using provided datas
     77  *
     78  * Reimplemented from IODevice.
     79  *
     80  * \param data data from the parent to process
     81  */
     82  void UpdateFrom(const core::io_data *data){};
    8883
    89             /*!
    90             * \brief Run function
    91             *
    92             * Reimplemented from Thread.
    93             *
    94             */
    95             void Run(void);
     84  /*!
     85  * \brief Run function
     86  *
     87  * Reimplemented from Thread.
     88  *
     89  */
     90  void Run(void);
    9691
    97             gui::SpinBox *data_rate;
    98     };
     92  gui::SpinBox *data_rate;
     93};
    9994} // end namespace sensor
    10095} // end namespace flair
  • trunk/include/FlairSensorActuator/SimuUs.h

    r4 r13  
    1717#include <Thread.h>
    1818
    19 namespace flair
    20 {
    21     namespace core
    22     {
    23         class SharedMem;
    24     }
    25     namespace gui
    26     {
    27         class SpinBox;
    28     }
     19namespace flair {
     20namespace core {
     21class SharedMem;
     22}
     23namespace gui {
     24class SpinBox;
     25}
    2926}
    3027
    31 namespace flair
    32 {
    33 namespace sensor
    34 {
    35     /*! \class SimuUs
    36     *
    37     * \brief Class for a simulation UsRangeFinder
    38     */
    39     class SimuUs : public core::Thread, public UsRangeFinder
    40     {
    41         public:
    42             /*!
    43             * \brief Constructor
    44             *
    45             * Construct a SimuUs. Control part.
    46             *
    47             * \param parent parent
    48             * \param name name
    49             * \param dev_id device id
    50             * \param priority priority of the Thread
    51             */
    52             SimuUs(const core::FrameworkManager* parent,std::string name,uint32_t dev_id,uint8_t priority);
     28namespace flair {
     29namespace sensor {
     30/*! \class SimuUs
     31*
     32* \brief Class for a simulation UsRangeFinder
     33*/
     34class SimuUs : public core::Thread, public UsRangeFinder {
     35public:
     36  /*!
     37  * \brief Constructor
     38  *
     39  * Construct a SimuUs. Control part.
     40  *
     41  * \param parent parent
     42  * \param name name
     43  * \param dev_id device id
     44  * \param priority priority of the Thread
     45  */
     46  SimuUs(const core::FrameworkManager *parent, std::string name,
     47         uint32_t dev_id, uint8_t priority);
    5348
    54             /*!
    55             * \brief Constructor
    56             *
    57             * Construct a SimuUs. Simulation part.\n
    58             * The Thread of this class should not be run.
    59             *
    60             * \param parent parent
    61             * \param name name
    62             * \param dev_id device id
    63             */
    64             SimuUs(const core::IODevice* parent,std::string name,uint32_t dev_id);
     49  /*!
     50  * \brief Constructor
     51  *
     52  * Construct a SimuUs. Simulation part.\n
     53  * The Thread of this class should not be run.
     54  *
     55  * \param parent parent
     56  * \param name name
     57  * \param dev_id device id
     58  */
     59  SimuUs(const core::IODevice *parent, std::string name, uint32_t dev_id);
    6560
    66             /*!
    67             * \brief Destructor
    68             *
    69             */
    70             ~SimuUs();
     61  /*!
     62  * \brief Destructor
     63  *
     64  */
     65  ~SimuUs();
    7166
    72         protected:
    73             /*!
    74             * \brief SharedMem to access datas
    75             *
    76             */
    77             core::SharedMem *shmem;
     67protected:
     68  /*!
     69  * \brief SharedMem to access datas
     70  *
     71  */
     72  core::SharedMem *shmem;
    7873
    79         private:
    80             /*!
    81             * \brief Update using provided datas
    82             *
    83             * Reimplemented from IODevice.
    84             *
    85             * \param data data from the parent to process
    86             */
    87             void UpdateFrom(const core::io_data *data){};
     74private:
     75  /*!
     76  * \brief Update using provided datas
     77  *
     78  * Reimplemented from IODevice.
     79  *
     80  * \param data data from the parent to process
     81  */
     82  void UpdateFrom(const core::io_data *data){};
    8883
    89             /*!
    90             * \brief Run function
    91             *
    92             * Reimplemented from Thread.
    93             *
    94             */
    95             void Run(void);
     84  /*!
     85  * \brief Run function
     86  *
     87  * Reimplemented from Thread.
     88  *
     89  */
     90  void Run(void);
    9691
    97             gui::SpinBox *data_rate;
    98     };
     92  gui::SpinBox *data_rate;
     93};
    9994} // end namespace sensor
    10095} // end namespace flair
  • trunk/include/FlairSensorActuator/Srf08.h

    r4 r13  
    1717#include <UsRangeFinder.h>
    1818
    19 namespace flair
    20 {
    21     namespace core
    22     {
    23         class FrameworkManager;
    24         class I2cPort;
    25     }
    26     namespace gui
    27     {
    28         class SpinBox;;
    29     }
     19namespace flair {
     20namespace core {
     21class FrameworkManager;
     22class I2cPort;
     23}
     24namespace gui {
     25class SpinBox;
     26;
     27}
    3028}
    3129
    32 namespace flair
    33 {
    34 namespace sensor
    35 {
    36     /*! \class Srf08
    37     *
    38     * \brief Class for ultra sonic SRF08
    39     */
    40     class Srf08 : public core::Thread, public UsRangeFinder
    41     {
     30namespace flair {
     31namespace sensor {
     32/*! \class Srf08
     33*
     34* \brief Class for ultra sonic SRF08
     35*/
     36class Srf08 : public core::Thread, public UsRangeFinder {
    4237
    43         public:
    44             /*!
    45             * \brief Constructor
    46             *
    47             * Construct a SimuUs. Control part.
    48             *
    49             * \param parent parent
    50             * \param name name
    51             * \param i2cport i2c port
    52             * \param address i2c slave address
    53             * \param priority priority of the Thread
    54             */
    55             Srf08(const core::FrameworkManager* parent,std::string name,core::I2cPort* i2cport,uint16_t address,uint8_t priority);
     38public:
     39  /*!
     40  * \brief Constructor
     41  *
     42  * Construct a SimuUs. Control part.
     43  *
     44  * \param parent parent
     45  * \param name name
     46  * \param i2cport i2c port
     47  * \param address i2c slave address
     48  * \param priority priority of the Thread
     49  */
     50  Srf08(const core::FrameworkManager *parent, std::string name,
     51        core::I2cPort *i2cport, uint16_t address, uint8_t priority);
    5652
    57             /*!
    58             * \brief Destructor
    59             *
    60             */
    61             ~Srf08();
     53  /*!
     54  * \brief Destructor
     55  *
     56  */
     57  ~Srf08();
    6258
    63             /*!
    64             * \brief Set Range
    65             *
    66             * check datasheet for values
    67             */
    68             void SetRange(void);
     59  /*!
     60  * \brief Set Range
     61  *
     62  * check datasheet for values
     63  */
     64  void SetRange(void);
    6965
    70             /*!
    71             * \brief Set Max Gain
    72             *
    73             * check datasheet for values
    74             */
    75             void SetMaxGain(void);
     66  /*!
     67  * \brief Set Max Gain
     68  *
     69  * check datasheet for values
     70  */
     71  void SetMaxGain(void);
    7672
    77         private:
    78             /*!
    79             * \brief Update using provided datas
    80             *
    81             * Reimplemented from IODevice.
    82             *
    83             * \param data data from the parent to process
    84             */
    85             void UpdateFrom(const core::io_data *data){};
     73private:
     74  /*!
     75  * \brief Update using provided datas
     76  *
     77  * Reimplemented from IODevice.
     78  *
     79  * \param data data from the parent to process
     80  */
     81  void UpdateFrom(const core::io_data *data){};
    8682
    87             /*!
    88             * \brief Run function
    89             *
    90             * Reimplemented from Thread.
    91             *
    92             */
    93             void Run(void);
     83  /*!
     84  * \brief Run function
     85  *
     86  * Reimplemented from Thread.
     87  *
     88  */
     89  void Run(void);
    9490
    95             void SendEcho(void);
    96             void GetEcho(void);
     91  void SendEcho(void);
     92  void GetEcho(void);
    9793
    98             bool is_init;
    99             core::Time echo_time;
    100             float z_1,z_2;
    101             gui::SpinBox *gain,*range;
    102             uint16_t address;
    103             core::I2cPort* i2cport;
    104     };
     94  bool is_init;
     95  core::Time echo_time;
     96  float z_1, z_2;
     97  gui::SpinBox *gain, *range;
     98  uint16_t address;
     99  core::I2cPort *i2cport;
     100};
    105101} // end namespace sensor
    106102} // end namespace flair
  • trunk/include/FlairSensorActuator/TargetController.h

    r4 r13  
    2525
    2626namespace flair {
    27     namespace core {
    28         class FrameworkManager;
    29         class cvmatrix;
    30         class Socket;
    31         class io_data;
    32     }
    33     namespace gui {
    34         class Tab;
    35         class TabWidget;
    36         class DataPlot1D;
    37     }
     27namespace core {
     28class FrameworkManager;
     29class cvmatrix;
     30class Socket;
     31class io_data;
     32}
     33namespace gui {
     34class Tab;
     35class TabWidget;
     36class DataPlot1D;
     37}
    3838}
    3939
    40 namespace flair { namespace sensor {
    41     enum class ControllerAction;
     40namespace flair {
     41namespace sensor {
     42enum class ControllerAction;
    4243
    43     /*! \class TargetController
    44     *
    45     * \brief Base Class for target side remote controls
    46     *
    47     */
    48     class TargetController : public core::Thread, public core::IODevice {
    49     public:
    50         TargetController(const core::FrameworkManager* parent,std::string name,uint8_t priority=0);
    51         ~TargetController();
    52         //void DrawUserInterface();
    53         virtual bool IsConnected() const=0;
    54         virtual bool IsDataFrameReady()=0;
    55         //axis stuff
    56         unsigned int GetAxisNumber() const;
    57         virtual std::string GetAxisName(unsigned int axisId) const;
    58         float GetAxisValue(unsigned int axisId) const;// always in the range [-1.0,1.0]
    59         //button stuff
    60         unsigned int GetButtonNumber() const;
    61         bool IsButtonPressed(unsigned int buttonId) const;
    62         virtual std::string GetButtonName(unsigned int axisId) const;
    63         //controller state stuff
    64         virtual bool IsControllerActionSupported(ControllerAction action) const {return false;};
    65         bool SetLedOn(unsigned int ledId);
    66         bool SetLedOff(unsigned int ledId);
    67         bool Rumble(unsigned int left_force,unsigned int left_timeout,unsigned int right_force,unsigned int right_timeout);
    68         bool FlashLed(unsigned int ledId,unsigned int on_timeout,unsigned int off_timeout);
    69         void UpdateFrom(const core::io_data *data){}; //TODO
    70         gui::Tab* GetTab(void) const;
     44/*! \class TargetController
     45*
     46* \brief Base Class for target side remote controls
     47*
     48*/
     49class TargetController : public core::Thread, public core::IODevice {
     50public:
     51  TargetController(const core::FrameworkManager *parent, std::string name,
     52                   uint8_t priority = 0);
     53  ~TargetController();
     54  // void DrawUserInterface();
     55  virtual bool IsConnected() const = 0;
     56  virtual bool IsDataFrameReady() = 0;
     57  // axis stuff
     58  unsigned int GetAxisNumber() const;
     59  virtual std::string GetAxisName(unsigned int axisId) const;
     60  float
     61  GetAxisValue(unsigned int axisId) const; // always in the range [-1.0,1.0]
     62  // button stuff
     63  unsigned int GetButtonNumber() const;
     64  bool IsButtonPressed(unsigned int buttonId) const;
     65  virtual std::string GetButtonName(unsigned int axisId) const;
     66  // controller state stuff
     67  virtual bool IsControllerActionSupported(ControllerAction action) const {
     68    return false;
     69  };
     70  bool SetLedOn(unsigned int ledId);
     71  bool SetLedOff(unsigned int ledId);
     72  bool Rumble(unsigned int left_force, unsigned int left_timeout,
     73              unsigned int right_force, unsigned int right_timeout);
     74  bool FlashLed(unsigned int ledId, unsigned int on_timeout,
     75                unsigned int off_timeout);
     76  void UpdateFrom(const core::io_data *data){}; // TODO
     77  gui::Tab *GetTab(void) const;
    7178
    72     protected:
    73         virtual bool ProcessMessage(core::Message *msg)=0;
    74         void QueueMessage(core::Message msg);
    75         virtual bool ControllerInitialization()=0;// {return true;};
    76         //axis stuff
    77         unsigned int axisNumber;
    78         core::cvmatrix* axis=NULL;
    79         virtual void AcquireAxisData(core::cvmatrix &axis)=0; //responsible for getting the axis data from the hardware
    80         uint16_t bitsPerAxis;
    81         //button stuff
    82         unsigned int buttonNumber;
    83         core::cvmatrix* button=NULL;
    84         virtual void AcquireButtonData(core::cvmatrix &button)=0; //responsible for getting the button data from the hardware
    85         //controller state stuff
    86         unsigned int ledNumber;
    87     private:
    88         void Run();
    89         std::queue<core::Message *> changeStateQueue;
    90         flair::gui::Tab* main_tab;
    91         flair::gui::Tab* setup_tab;
    92     };
     79protected:
     80  virtual bool ProcessMessage(core::Message *msg) = 0;
     81  void QueueMessage(core::Message msg);
     82  virtual bool ControllerInitialization() = 0; // {return true;};
     83  // axis stuff
     84  unsigned int axisNumber;
     85  core::cvmatrix *axis = NULL;
     86  virtual void AcquireAxisData(core::cvmatrix &axis) = 0; // responsible for
     87                                                          // getting the axis
     88                                                          // data from the
     89                                                          // hardware
     90  uint16_t bitsPerAxis;
     91  // button stuff
     92  unsigned int buttonNumber;
     93  core::cvmatrix *button = NULL;
     94  virtual void AcquireButtonData(core::cvmatrix &button) = 0; // responsible for
     95                                                              // getting the
     96                                                              // button data
     97                                                              // from the
     98                                                              // hardware
     99  // controller state stuff
     100  unsigned int ledNumber;
    93101
    94 }}
     102private:
     103  void Run();
     104  std::queue<core::Message *> changeStateQueue;
     105  flair::gui::Tab *main_tab;
     106  flair::gui::Tab *setup_tab;
     107};
     108}
     109}
    95110
    96111#endif // TARGETCONTROLLER_H
  • trunk/include/FlairSensorActuator/TargetEthController.h

    r4 r13  
    1212//
    1313//  purpose:    class that gets remote controls through an ethernet connection.
    14 //              Typical use case: a remote control is plugged in a workstation and sends remote control
     14//              Typical use case: a remote control is plugged in a workstation
     15//              and sends remote control
    1516//              data to a distant target (this class) through Wifi
    1617//
     
    2425
    2526namespace flair {
    26     namespace core {
    27         class FrameworkManager;
    28         class cvmatrix;
    29         class TcpSocket;
    30         class Socket;
    31     }
    32     namespace gui {
    33         class Tab;
    34         class TabWidget;
    35         class DataPlot1D;
    36     }
     27namespace core {
     28class FrameworkManager;
     29class cvmatrix;
     30class TcpSocket;
     31class Socket;
     32}
     33namespace gui {
     34class Tab;
     35class TabWidget;
     36class DataPlot1D;
     37}
    3738}
    3839
    39 namespace flair { namespace sensor {
    40     /*! \class TargetController
    41     *
    42     * \brief Base Class for target side remote controls
    43     *
    44     */
    45     class TargetEthController : public TargetController {
    46     public:
    47         TargetEthController(const core::FrameworkManager* parent,std::string name,uint16_t port,uint8_t priority=0);
    48         ~TargetEthController();
    49         //void DrawUserInterface();
    50     protected:
    51         bool IsConnected() const;
    52         //axis stuff
    53         std::string GetAxisName(unsigned int axisId) const;
    54         //button stuff
    55         std::string GetButtonName(unsigned int axisId) const;
    56         //controller state stuff
    57         bool ProcessMessage(core::Message *msg);
    58         bool IsControllerActionSupported(ControllerAction action) const;
     40namespace flair {
     41namespace sensor {
     42/*! \class TargetController
     43*
     44* \brief Base Class for target side remote controls
     45*
     46*/
     47class TargetEthController : public TargetController {
     48public:
     49  TargetEthController(const core::FrameworkManager *parent, std::string name,
     50                      uint16_t port, uint8_t priority = 0);
     51  ~TargetEthController();
     52  // void DrawUserInterface();
     53protected:
     54  bool IsConnected() const;
     55  // axis stuff
     56  std::string GetAxisName(unsigned int axisId) const;
     57  // button stuff
     58  std::string GetButtonName(unsigned int axisId) const;
     59  // controller state stuff
     60  bool ProcessMessage(core::Message *msg);
     61  bool IsControllerActionSupported(ControllerAction action) const;
    5962
    60         bool IsDataFrameReady();
    61         void AcquireAxisData(core::cvmatrix &axis); //responsible for getting the axis data from the hardware
    62         void AcquireButtonData(core::cvmatrix &button); //responsible for getting the button data from the hardware
     63  bool IsDataFrameReady();
     64  void AcquireAxisData(core::cvmatrix &axis); // responsible for getting the
     65                                              // axis data from the hardware
     66  void AcquireButtonData(core::cvmatrix &button); // responsible for getting the
     67                                                  // button data from the
     68                                                  // hardware
    6369
    64         bool ControllerInitialization();
     70  bool ControllerInitialization();
    6571
    66     private:
    67         uint16_t readBits(uint8_t offsetInBits,uint8_t valueSizeInBits,char *buffer,size_t bufferSize);
    68         uint8_t getByteOrNull(char *buffer,int byte,size_t bufferSize);
    69         uint32_t charBufferToUint32(char *buffer, size_t bufferSize);
    70         core::TcpSocket *listeningSocket;
    71         int listeningPort;
    72         core::TcpSocket *controlSocket=NULL;
    73         core::Socket *dataSocket;
    74         std::string *axisName=NULL;
    75         std::string *buttonName=NULL;
    76         size_t dataFrameSize;
    77         char *dataFrameBuffer;
    78         char *receiveFrameBuffer;
    79         size_t receiveCurrentPosition;
    80         uint8_t buttonOffset;
    81     };
    82 
    83 }}
     72private:
     73  uint16_t readBits(uint8_t offsetInBits, uint8_t valueSizeInBits, char *buffer,
     74                    size_t bufferSize);
     75  uint8_t getByteOrNull(char *buffer, int byte, size_t bufferSize);
     76  uint32_t charBufferToUint32(char *buffer, size_t bufferSize);
     77  core::TcpSocket *listeningSocket;
     78  int listeningPort;
     79  core::TcpSocket *controlSocket = NULL;
     80  core::Socket *dataSocket;
     81  std::string *axisName = NULL;
     82  std::string *buttonName = NULL;
     83  size_t dataFrameSize;
     84  char *dataFrameBuffer;
     85  char *receiveFrameBuffer;
     86  size_t receiveCurrentPosition;
     87  uint8_t buttonOffset;
     88};
     89}
     90}
    8491
    8592#endif // TARGETCONTROLLER_H
  • trunk/include/FlairSensorActuator/UsRangeFinder.h

    r4 r13  
    1616#include <IODevice.h>
    1717
    18 namespace flair
    19 {
    20     namespace core
    21     {
    22         class cvmatrix;
    23     }
    24     namespace gui
    25     {
    26         class Tab;
    27         class TabWidget;
    28         class GroupBox;
    29         class Layout;
    30         class DataPlot1D;
    31     }
     18namespace flair {
     19namespace core {
     20class cvmatrix;
     21}
     22namespace gui {
     23class Tab;
     24class TabWidget;
     25class GroupBox;
     26class Layout;
     27class DataPlot1D;
     28}
    3229}
    3330
    34 namespace flair
    35 {
    36 namespace sensor
    37 {
    38     /*! \class UsRangeFinder
    39     *
    40     * \brief Base class for UsRangeFinder
    41     *
    42     * Use this class to define a custom UsRangeFinder.
    43     *
    44     */
    45     class UsRangeFinder : public core::IODevice
    46     {
    47         public:
    48             /*!
    49             * \brief Constructor
    50             *
    51             * Construct a UsRangeFinder. Control part.
    52             *
    53             * \param parent parent
    54             * \param name name
    55             */
    56             UsRangeFinder(const core::FrameworkManager* parent,std::string name);
     31namespace flair {
     32namespace sensor {
     33/*! \class UsRangeFinder
     34*
     35* \brief Base class for UsRangeFinder
     36*
     37* Use this class to define a custom UsRangeFinder.
     38*
     39*/
     40class UsRangeFinder : public core::IODevice {
     41public:
     42  /*!
     43  * \brief Constructor
     44  *
     45  * Construct a UsRangeFinder. Control part.
     46  *
     47  * \param parent parent
     48  * \param name name
     49  */
     50  UsRangeFinder(const core::FrameworkManager *parent, std::string name);
    5751
    58             /*!
    59             * \brief Constructor
    60             *
    61             * Construct a UsRangeFinder. Simulation part.
    62             *
    63             * \param parent parent
    64             * \param name name
    65             */
    66             UsRangeFinder(const core::IODevice* parent,std::string name);
     52  /*!
     53  * \brief Constructor
     54  *
     55  * Construct a UsRangeFinder. Simulation part.
     56  *
     57  * \param parent parent
     58  * \param name name
     59  */
     60  UsRangeFinder(const core::IODevice *parent, std::string name);
    6761
    68             /*!
    69             * \brief Destructor
    70             *
    71             */
    72             ~UsRangeFinder();
     62  /*!
     63  * \brief Destructor
     64  *
     65  */
     66  ~UsRangeFinder();
    7367
    74             /*!
    75             * \brief Lock user interface
    76             *
    77             */
    78             void LockUserInterface(void) const;
     68  /*!
     69  * \brief Lock user interface
     70  *
     71  */
     72  void LockUserInterface(void) const;
    7973
    80             /*!
    81             * \brief Unlock user interface
    82             *
    83             */
    84             void UnlockUserInterface(void) const;
     74  /*!
     75  * \brief Unlock user interface
     76  *
     77  */
     78  void UnlockUserInterface(void) const;
    8579
    86             /*!
    87             * \brief Use default plot
    88             *
    89             * Should no be used for the simulation part.
    90             */
    91             void UseDefaultPlot(void);
     80  /*!
     81  * \brief Use default plot
     82  *
     83  * Should no be used for the simulation part.
     84  */
     85  void UseDefaultPlot(void);
    9286
    93             /*!
    94             * \brief Plot
    95             *
    96             * \return DataPlot1D
    97             */
    98             gui::DataPlot1D* GetPlot(void) const;
     87  /*!
     88  * \brief Plot
     89  *
     90  * \return DataPlot1D
     91  */
     92  gui::DataPlot1D *GetPlot(void) const;
    9993
    100             /*!
    101             * \brief Setup Layout
    102             *
    103             * \return a Layout available
    104             */
    105             gui::Layout* GetLayout(void) const;
     94  /*!
     95  * \brief Setup Layout
     96  *
     97  * \return a Layout available
     98  */
     99  gui::Layout *GetLayout(void) const;
    106100
    107             /*!
    108             * \brief Plot tab
    109             *
    110             * \return plot Tab
    111             */
    112             gui::Tab* GetPlotTab(void) const;
     101  /*!
     102  * \brief Plot tab
     103  *
     104  * \return plot Tab
     105  */
     106  gui::Tab *GetPlotTab(void) const;
    113107
    114             /*!
    115             * \brief Value
    116             *
    117             * \return output value
    118             */
    119             float Value(void) const;
     108  /*!
     109  * \brief Value
     110  *
     111  * \return output value
     112  */
     113  float Value(void) const;
    120114
    121         protected:
    122             /*!
    123             * \brief Output matrix
    124             *
    125             * \return output matrix
    126             */
    127             core::cvmatrix *output;
     115protected:
     116  /*!
     117  * \brief Output matrix
     118  *
     119  * \return output matrix
     120  */
     121  core::cvmatrix *output;
    128122
    129             /*!
    130             * \brief Setup GroupBox
    131             *
    132             * \return a GroupBox available
    133             */
    134             gui::GroupBox* GetGroupBox(void) const;
     123  /*!
     124  * \brief Setup GroupBox
     125  *
     126  * \return a GroupBox available
     127  */
     128  gui::GroupBox *GetGroupBox(void) const;
    135129
    136         private:
    137             /*!
    138             * \brief Update using provided datas
    139             *
    140             * Reimplemented from IODevice.
    141             *
    142             * \param data data from the parent to process
    143             */
    144             void UpdateFrom(const core::io_data *data){};
     130private:
     131  /*!
     132  * \brief Update using provided datas
     133  *
     134  * Reimplemented from IODevice.
     135  *
     136  * \param data data from the parent to process
     137  */
     138  void UpdateFrom(const core::io_data *data){};
    145139
    146             gui::Tab* main_tab;
    147             gui::TabWidget *tab;
    148             gui::GroupBox* setup_groupbox;
    149             gui::Tab* sensor_tab;
    150             gui::DataPlot1D* plot;
    151             gui::Tab* plot_tab;
    152     };
     140  gui::Tab *main_tab;
     141  gui::TabWidget *tab;
     142  gui::GroupBox *setup_groupbox;
     143  gui::Tab *sensor_tab;
     144  gui::DataPlot1D *plot;
     145  gui::Tab *plot_tab;
     146};
    153147} // end namespace sensor
    154148} // end namespace flair
  • trunk/include/FlairSensorActuator/V4LCamera.h

    r4 r13  
    1818#include <highgui.h>
    1919
    20 namespace flair
    21 {
    22     namespace core
    23     {
    24         class cvimage;
    25         class FrameworkManager;
    26     }
    27     namespace gui
    28     {
    29         class GridLayout;
    30         class DoubleSpinBox;
    31         class CheckBox;
    32         class Label;
    33     }
     20namespace flair {
     21namespace core {
     22class cvimage;
     23class FrameworkManager;
     24}
     25namespace gui {
     26class GridLayout;
     27class DoubleSpinBox;
     28class CheckBox;
     29class Label;
     30}
    3431}
    3532
    36 namespace flair
    37 {
    38 namespace sensor
    39 {
    40     /*! \class V4LCamera
    41     *
    42     * \brief Base class for V4l camera
    43     */
    44     class V4LCamera : public core::Thread, public Camera
    45     {
    46         public:
    47             /*!
    48             * \brief Constructor
    49             *
    50             * Construct a Camera.
    51             *
    52             * \param parent parent
    53             * \param name name
    54             * \param camera_index camera index
    55             * \param width width
    56             * \param height height
    57             * \param format image format
    58             * \param priority priority of the Thread
    59             */
    60             V4LCamera(const core::FrameworkManager* parent,std::string name,uint8_t camera_index,uint16_t width,uint16_t height,core::cvimage::Type::Format format,uint8_t priority);
     33namespace flair {
     34namespace sensor {
     35/*! \class V4LCamera
     36*
     37* \brief Base class for V4l camera
     38*/
     39class V4LCamera : public core::Thread, public Camera {
     40public:
     41  /*!
     42  * \brief Constructor
     43  *
     44  * Construct a Camera.
     45  *
     46  * \param parent parent
     47  * \param name name
     48  * \param camera_index camera index
     49  * \param width width
     50  * \param height height
     51  * \param format image format
     52  * \param priority priority of the Thread
     53  */
     54  V4LCamera(const core::FrameworkManager *parent, std::string name,
     55            uint8_t camera_index, uint16_t width, uint16_t height,
     56            core::cvimage::Type::Format format, uint8_t priority);
    6157
    62             /*!
    63             * \brief Destructor
    64             *
    65             */
    66             ~V4LCamera();
     58  /*!
     59  * \brief Destructor
     60  *
     61  */
     62  ~V4LCamera();
    6763
    68         protected:
    69             /*!
    70             * \brief Set Gain
    71             *
    72             * \param value value between 0 and 1
    73             */
    74             virtual void SetGain(float value);
     64protected:
     65  /*!
     66  * \brief Set Gain
     67  *
     68  * \param value value between 0 and 1
     69  */
     70  virtual void SetGain(float value);
    7571
    76             /*!
    77             * \brief Set Auto Gain
    78             *
    79             * \param value value
    80             */
    81             virtual void SetAutoGain(bool value);
     72  /*!
     73  * \brief Set Auto Gain
     74  *
     75  * \param value value
     76  */
     77  virtual void SetAutoGain(bool value);
    8278
    83             /*!
    84             * \brief Set Exposure
    85             *
    86             * \param value value between 0 and 1
    87             */
    88             virtual void SetExposure(float value);
     79  /*!
     80  * \brief Set Exposure
     81  *
     82  * \param value value between 0 and 1
     83  */
     84  virtual void SetExposure(float value);
    8985
    90             /*!
    91             * \brief Set Auto Exposure
    92             *
    93             * \param value value
    94             */
    95             virtual void SetAutoExposure(bool value);
     86  /*!
     87  * \brief Set Auto Exposure
     88  *
     89  * \param value value
     90  */
     91  virtual void SetAutoExposure(bool value);
    9692
    97             /*!
    98             * \brief Set Brightness
    99             *
    100             * \param value value between 0 and 1
    101             */
    102             virtual void SetBrightness(float value);
     93  /*!
     94  * \brief Set Brightness
     95  *
     96  * \param value value between 0 and 1
     97  */
     98  virtual void SetBrightness(float value);
    10399
    104             /*!
    105             * \brief Set Saturation
    106             *
    107             * \param value value between 0 and 1
    108             */
    109             virtual void SetSaturation(float value);
     100  /*!
     101  * \brief Set Saturation
     102  *
     103  * \param value value between 0 and 1
     104  */
     105  virtual void SetSaturation(float value);
    110106
    111             /*!
    112             * \brief Set Hue
    113             *
    114             * \param value value between 0 and 1
    115             */
    116             virtual void SetHue(float value);
     107  /*!
     108  * \brief Set Hue
     109  *
     110  * \param value value between 0 and 1
     111  */
     112  virtual void SetHue(float value);
    117113
    118             /*!
    119             * \brief Set Contrast
    120             *
    121             * \param value value between 0 and 1
    122             */
    123             virtual void SetContrast(float value);
     114  /*!
     115  * \brief Set Contrast
     116  *
     117  * \param value value between 0 and 1
     118  */
     119  virtual void SetContrast(float value);
    124120
    125         private:
    126             /*!
    127             * \brief Update using provided datas
    128             *
    129             * Reimplemented from IODevice.
    130             *
    131             * \param data data from the parent to process
    132             */
    133             void UpdateFrom(const core::io_data *data){};
     121private:
     122  /*!
     123  * \brief Update using provided datas
     124  *
     125  * Reimplemented from IODevice.
     126  *
     127  * \param data data from the parent to process
     128  */
     129  void UpdateFrom(const core::io_data *data){};
    134130
    135             /*!
    136             * \brief Run function
    137             *
    138             * Reimplemented from Thread.
    139             *
    140             */
    141             void Run(void);
     131  /*!
     132  * \brief Run function
     133  *
     134  * Reimplemented from Thread.
     135  *
     136  */
     137  void Run(void);
    142138
    143             CvCapture* capture;
     139  CvCapture *capture;
    144140
    145             gui::Tab* sensor_tab;
    146             gui::DoubleSpinBox *bright,*exposure,*gain,*contrast,*hue,*sharpness,*sat;
    147             gui::CheckBox *autogain,*awb,*autoexposure;
    148             gui::Label *fps;
    149     };
     141  gui::Tab *sensor_tab;
     142  gui::DoubleSpinBox *bright, *exposure, *gain, *contrast, *hue, *sharpness,
     143      *sat;
     144  gui::CheckBox *autogain, *awb, *autoexposure;
     145  gui::Label *fps;
     146};
    150147} // end namespace sensor
    151148} // end namespace flair
  • trunk/include/FlairSensorActuator/VrpnClient.h

    r4 r13  
    66 * \file VrpnClient.h
    77 * \brief Class to connect to a Vrpn server
    8  * \author César Richard, Guillaume Sanahuja, Copyright Heudiasyc UMR UTC/CNRS 7253
     8 * \author César Richard, Guillaume Sanahuja, Copyright Heudiasyc UMR UTC/CNRS
     9 * 7253
    910 * \date 2013/04/03
    1011 * \version 4.0
     
    1617#include <Thread.h>
    1718
    18 namespace flair
    19 {
    20     namespace core
    21     {
    22         class FrameworkManager;
    23         class SerialPort;
    24     }
    25     namespace gui
    26     {
    27         class TabWidget;
    28         class Layout;
    29     }
     19namespace flair {
     20namespace core {
     21class FrameworkManager;
     22class SerialPort;
     23}
     24namespace gui {
     25class TabWidget;
     26class Layout;
     27}
    3028}
    3129
     
    3331class VrpnObject_impl;
    3432
    35 namespace flair
    36 {
    37 namespace sensor
    38 {
    39     /*! \class VrpnClient
    40     *
    41     * \brief Class to connect to a Vrpn server
    42     */
    43     class VrpnClient:public core::Thread
    44     {
    45         friend class ::VrpnObject_impl;
     33namespace flair {
     34namespace sensor {
     35/*! \class VrpnClient
     36*
     37* \brief Class to connect to a Vrpn server
     38*/
     39class VrpnClient : public core::Thread {
     40  friend class ::VrpnObject_impl;
    4641
    47         public:
    48             /*!
    49             * \brief Constructor
    50             *
    51             * Construct a VrpnClient. Connection is done by IP.
    52             *
    53             * \param parent parent
    54             * \param name name
    55             * \param address server address
    56             * \param us_period Thread period in us
    57             * \param priority priority of the Thread
    58             */
    59             VrpnClient(const core::FrameworkManager* parent,std::string name,std::string address,uint16_t us_period,uint8_t priority);
     42public:
     43  /*!
     44  * \brief Constructor
     45  *
     46  * Construct a VrpnClient. Connection is done by IP.
     47  *
     48  * \param parent parent
     49  * \param name name
     50  * \param address server address
     51  * \param us_period Thread period in us
     52  * \param priority priority of the Thread
     53  */
     54  VrpnClient(const core::FrameworkManager *parent, std::string name,
     55             std::string address, uint16_t us_period, uint8_t priority);
    6056
    61             /*!
    62             * \brief Constructor
    63             *
    64             * Construct a VrpnClient. Connection is done by XBee modem.
    65             *
    66             * \param parent parent
    67             * \param name name
    68             * \param serialport SerialPort for XBee modem
    69             * \param us_period Xbee RX timeout in us
    70             * \param priority priority of the Thread
    71             */
    72             VrpnClient(const core::FrameworkManager* parent,std::string name,core::SerialPort* serialport,uint16_t us_period,uint8_t priority);
     57  /*!
     58  * \brief Constructor
     59  *
     60  * Construct a VrpnClient. Connection is done by XBee modem.
     61  *
     62  * \param parent parent
     63  * \param name name
     64  * \param serialport SerialPort for XBee modem
     65  * \param us_period Xbee RX timeout in us
     66  * \param priority priority of the Thread
     67  */
     68  VrpnClient(const core::FrameworkManager *parent, std::string name,
     69             core::SerialPort *serialport, uint16_t us_period,
     70             uint8_t priority);
    7371
    74             /*!
    75             * \brief Destructor
    76             *
    77             */
    78             ~VrpnClient();
     72  /*!
     73  * \brief Destructor
     74  *
     75  */
     76  ~VrpnClient();
    7977
    80             /*!
    81             * \brief Setup Layout
    82             *
    83             * \return a Layout available
    84             */
    85             gui::Layout* GetLayout(void) const;
     78  /*!
     79  * \brief Setup Layout
     80  *
     81  * \return a Layout available
     82  */
     83  gui::Layout *GetLayout(void) const;
    8684
    87             /*!
    88             * \brief Setup Tab
    89             *
    90             * \return a Tab available
    91             */
    92             gui::TabWidget* GetTabWidget(void) const;
     85  /*!
     86  * \brief Setup Tab
     87  *
     88  * \return a Tab available
     89  */
     90  gui::TabWidget *GetTabWidget(void) const;
    9391
    94             /*!
    95             * \brief Is XBee used?
    96             *
    97             * \return true if connection is based on XBee modem
    98             */
    99             bool UseXbee(void) const;
     92  /*!
     93  * \brief Is XBee used?
     94  *
     95  * \return true if connection is based on XBee modem
     96  */
     97  bool UseXbee(void) const;
    10098
    101         private:
    102             /*!
    103             * \brief Run function
    104             *
    105             * Reimplemented from Thread.
    106             *
    107             */
    108             void Run(void);
     99private:
     100  /*!
     101  * \brief Run function
     102  *
     103  * Reimplemented from Thread.
     104  *
     105  */
     106  void Run(void);
    109107
    110             class VrpnClient_impl* pimpl_;
    111     };
     108  class VrpnClient_impl *pimpl_;
     109};
    112110} // end namespace sensor
    113111} // end namespace flair
  • trunk/include/FlairSensorActuator/VrpnObject.h

    r4 r13  
    66 * \file VrpnObject.h
    77 * \brief Class for VRPN object
    8  * \author César Richard, Guillaume Sanahuja, Copyright Heudiasyc UMR UTC/CNRS 7253
     8 * \author César Richard, Guillaume Sanahuja, Copyright Heudiasyc UMR UTC/CNRS
     9 * 7253
    910 * \date 2013/04/03
    1011 * \version 4.0
     
    1718#include <stdint.h>
    1819
    19 namespace flair
    20 {
    21     namespace core
    22     {
    23         class cvmatrix;
    24         class Vector3D;
    25         class Euler;
    26         class Quaternion;
    27     }
    28     namespace gui
    29     {
    30         class TabWidget;
    31         class Tab;
    32         class DataPlot1D;
    33     }
     20namespace flair {
     21namespace core {
     22class cvmatrix;
     23class Vector3D;
     24class Euler;
     25class Quaternion;
     26}
     27namespace gui {
     28class TabWidget;
     29class Tab;
     30class DataPlot1D;
     31}
    3432}
    3533
     
    3735class VrpnClient_impl;
    3836
    39 namespace flair
    40 {
    41 namespace sensor
    42 {
    43     class VrpnClient;
     37namespace flair {
     38namespace sensor {
     39class VrpnClient;
    4440
    45     /*! \class VrpnObject
    46     *
    47     * \brief Class for VRPN object
    48     */
    49     class VrpnObject: public core::IODevice
    50     {
    51         friend class ::VrpnObject_impl;
    52         friend class ::VrpnClient_impl;
     41/*! \class VrpnObject
     42*
     43* \brief Class for VRPN object
     44*/
     45class VrpnObject : public core::IODevice {
     46  friend class ::VrpnObject_impl;
     47  friend class ::VrpnClient_impl;
    5348
    54         public:
    55             /*!
    56             * \brief Constructor
    57             *
    58             * Construct a VrpnObject. Connection is done by IP.
    59             *
    60             * \param parent parent
    61             * \param name VRPN object name, should be the same as defined in the server
    62             * \param tab Tab for the user interface
    63             */
    64             VrpnObject(const VrpnClient *parent,std::string name,const gui::TabWidget* tab);
     49public:
     50  /*!
     51  * \brief Constructor
     52  *
     53  * Construct a VrpnObject. Connection is done by IP.
     54  *
     55  * \param parent parent
     56  * \param name VRPN object name, should be the same as defined in the server
     57  * \param tab Tab for the user interface
     58  */
     59  VrpnObject(const VrpnClient *parent, std::string name,
     60             const gui::TabWidget *tab);
    6561
    66             /*!
    67             * \brief Constructor
    68             *
    69             * Construct a VrpnObject. Connection is done by IP.
    70             *
    71             * \param parent parent
    72             * \param name name
    73             * \param id VRPN object id, should be the same as defined in the server
    74             * \param tab Tab for the user interface
    75             */
    76             VrpnObject(const VrpnClient *parent,std::string name,uint8_t id,const gui::TabWidget* tab);
     62  /*!
     63  * \brief Constructor
     64  *
     65  * Construct a VrpnObject. Connection is done by IP.
     66  *
     67  * \param parent parent
     68  * \param name name
     69  * \param id VRPN object id, should be the same as defined in the server
     70  * \param tab Tab for the user interface
     71  */
     72  VrpnObject(const VrpnClient *parent, std::string name, uint8_t id,
     73             const gui::TabWidget *tab);
    7774
    78             /*!
    79             * \brief Destructor
    80             *
    81             */
    82             ~VrpnObject(void);
     75  /*!
     76  * \brief Destructor
     77  *
     78  */
     79  ~VrpnObject(void);
    8380
    84             /*!
    85             * \brief Plot tab
    86             *
    87             * \return plot Tab
    88             */
    89             gui::Tab* GetPlotTab(void) const;
     81  /*!
     82  * \brief Plot tab
     83  *
     84  * \return plot Tab
     85  */
     86  gui::Tab *GetPlotTab(void) const;
    9087
    91             /*!
    92             * \brief Get Last Packet Time
    93             *
    94             * \return Time of last received packe
    95             */
    96             core::Time GetLastPacketTime(void) const;
     88  /*!
     89  * \brief Get Last Packet Time
     90  *
     91  * \return Time of last received packe
     92  */
     93  core::Time GetLastPacketTime(void) const;
    9794
    98             /*!
    99             * \brief Is object tracked?
    100             *
    101             * \param timeout_ms timeout
    102             * \return true if object is tracked during timeout_ms time
    103             */
    104             bool IsTracked(unsigned int timeout_ms) const;
     95  /*!
     96  * \brief Is object tracked?
     97  *
     98  * \param timeout_ms timeout
     99  * \return true if object is tracked during timeout_ms time
     100  */
     101  bool IsTracked(unsigned int timeout_ms) const;
    105102
    106             /*!
    107             * \brief Get Euler angles
    108             *
    109             * \param euler output datas
    110             */
    111             void GetEuler(core::Euler &euler) const;
     103  /*!
     104  * \brief Get Euler angles
     105  *
     106  * \param euler output datas
     107  */
     108  void GetEuler(core::Euler &euler) const;
    112109
    113             /*!
    114             * \brief Get Quaternion
    115             *
    116             * \param quaternion output datas
    117             */
    118             void GetQuaternion(core::Quaternion &quaternion) const;
    119             /*!
    120             * \brief Get Position
    121             *
    122             * \param point output datas
    123             */
    124             void GetPosition(core::Vector3D &point) const;
     110  /*!
     111  * \brief Get Quaternion
     112  *
     113  * \param quaternion output datas
     114  */
     115  void GetQuaternion(core::Quaternion &quaternion) const;
     116  /*!
     117  * \brief Get Position
     118  *
     119  * \param point output datas
     120  */
     121  void GetPosition(core::Vector3D &point) const;
    125122
    126             /*!
    127             * \brief Output matrix
    128             *
    129             * Matrix is of type float and as follows: \n
    130             * (0,0) roll (rad) \n
    131             * (1,0) pitch (rad) \n
    132             * (2,0) yaw (rad) \n
    133             * (3,0) x \n
    134             * (4,0) y \n
    135             * (5,0) z \n
    136             *
    137             * \return Output metrix
    138             */
    139             core::cvmatrix *Output(void) const;
     123  /*!
     124  * \brief Output matrix
     125  *
     126  * Matrix is of type float and as follows: \n
     127  * (0,0) roll (rad) \n
     128  * (1,0) pitch (rad) \n
     129  * (2,0) yaw (rad) \n
     130  * (3,0) x \n
     131  * (4,0) y \n
     132  * (5,0) z \n
     133  *
     134  * \return Output metrix
     135  */
     136  core::cvmatrix *Output(void) const;
    140137
    141             /*!
    142             * \brief State matrix
    143             *
    144             * Matrix is of type float and as follows: \n
    145             * (0,0) roll (deg) \n
    146             * (1,0) pitch (deg) \n
    147             * (2,0) yaw (deg) \n
    148             *
    149             * \return State metrix
    150             */
    151             core::cvmatrix *State(void) const;
     138  /*!
     139  * \brief State matrix
     140  *
     141  * Matrix is of type float and as follows: \n
     142  * (0,0) roll (deg) \n
     143  * (1,0) pitch (deg) \n
     144  * (2,0) yaw (deg) \n
     145  *
     146  * \return State metrix
     147  */
     148  core::cvmatrix *State(void) const;
    152149
    153             /*!
    154             * \brief x plot
    155             *
    156             * \return x plot
    157             */
    158             gui::DataPlot1D* xPlot(void) const;
     150  /*!
     151  * \brief x plot
     152  *
     153  * \return x plot
     154  */
     155  gui::DataPlot1D *xPlot(void) const;
    159156
    160             /*!
    161             * \brief y plot
    162             *
    163             * \return y plot
    164             */
    165             gui::DataPlot1D* yPlot(void) const;
     157  /*!
     158  * \brief y plot
     159  *
     160  * \return y plot
     161  */
     162  gui::DataPlot1D *yPlot(void) const;
    166163
    167             /*!
    168             * \brief z plot
    169             *
    170             * \return z plot
    171             */
    172             gui::DataPlot1D* zPlot(void) const;
     164  /*!
     165  * \brief z plot
     166  *
     167  * \return z plot
     168  */
     169  gui::DataPlot1D *zPlot(void) const;
    173170
    174         private:
    175             /*!
    176             * \brief Update using provided datas
    177             *
    178             * Reimplemented from IODevice.
    179             *
    180             * \param data data from the parent to process
    181             */
    182             void UpdateFrom(const core::io_data *data){};
     171private:
     172  /*!
     173  * \brief Update using provided datas
     174  *
     175  * Reimplemented from IODevice.
     176  *
     177  * \param data data from the parent to process
     178  */
     179  void UpdateFrom(const core::io_data *data){};
    183180
    184             void mainloop(void);
    185             class VrpnObject_impl* pimpl_;
    186     };
     181  void mainloop(void);
     182  class VrpnObject_impl *pimpl_;
     183};
    187184} // end namespace sensor
    188185} // end namespace flair
  • trunk/include/FlairSensorActuator/XBldc.h

    r4 r13  
    1616#include "Bldc.h"
    1717
    18 namespace flair
    19 {
    20     namespace core
    21     {
    22         class IODevice;
    23         class I2cPort;
    24     }
    25     namespace gui
    26     {
    27         class Layout;
    28     }
     18namespace flair {
     19namespace core {
     20class IODevice;
     21class I2cPort;
     22}
     23namespace gui {
     24class Layout;
     25}
    2926}
    3027
    3128class XBldc_impl;
    3229
    33 namespace flair
    34 {
    35 namespace actuator
    36 {
    37     /*! \class XBldc
    38     *
    39     * \brief Class for Xufo Bldc
    40     */
    41     class XBldc : public Bldc
    42     {
    43         public:
    44             /*!
    45             * \brief Constructor
    46             *
    47             * Construct a XBldc.
    48             *
    49             * \param parent parent
    50             * \param layout layout
    51             * \param name name
    52             * \param i2cport i2cport
    53             */
    54             XBldc(const core::IODevice* parent,gui::Layout* layout,std::string name,core::I2cPort* i2cport);
     30namespace flair {
     31namespace actuator {
     32/*! \class XBldc
     33*
     34* \brief Class for Xufo Bldc
     35*/
     36class XBldc : public Bldc {
     37public:
     38  /*!
     39  * \brief Constructor
     40  *
     41  * Construct a XBldc.
     42  *
     43  * \param parent parent
     44  * \param layout layout
     45  * \param name name
     46  * \param i2cport i2cport
     47  */
     48  XBldc(const core::IODevice *parent, gui::Layout *layout, std::string name,
     49        core::I2cPort *i2cport);
    5550
    56             /*!
    57             * \brief Destructor
    58             *
    59             */
    60             ~XBldc();
     51  /*!
     52  * \brief Destructor
     53  *
     54  */
     55  ~XBldc();
    6156
    62             /*!
    63             * \brief Has speed measurement
    64             *
    65             * Reimplemented from Bldc. \n
    66             *
    67             * \return true if it has speed measurement
    68             */
    69             bool HasSpeedMeasurement(void) const{return false;};
     57  /*!
     58  * \brief Has speed measurement
     59  *
     60  * Reimplemented from Bldc. \n
     61  *
     62  * \return true if it has speed measurement
     63  */
     64  bool HasSpeedMeasurement(void) const { return false; };
    7065
    71             /*!
    72             * \brief Has current measurement
    73             *
    74             * Reimplemented from Bldc. \n
    75             *
    76             * \return true if it has current measurement
    77             */
    78             bool HasCurrentMeasurement(void) const{return false;};
     66  /*!
     67  * \brief Has current measurement
     68  *
     69  * Reimplemented from Bldc. \n
     70  *
     71  * \return true if it has current measurement
     72  */
     73  bool HasCurrentMeasurement(void) const { return false; };
    7974
    80         private:
    81             /*!
    82             * \brief Set motors values
    83             *
    84             * Reimplemented from Bldc. \n
    85             * Values size must be the same as MotorsCount()
    86             *
    87             * \param values motor values
    88             */
    89             void SetMotors(float* value);
     75private:
     76  /*!
     77  * \brief Set motors values
     78  *
     79  * Reimplemented from Bldc. \n
     80  * Values size must be the same as MotorsCount()
     81  *
     82  * \param values motor values
     83  */
     84  void SetMotors(float *value);
    9085
    91             class XBldc_impl* pimpl_;
    92     };
     86  class XBldc_impl *pimpl_;
     87};
    9388} // end namespace actuator
    9489} // end namespace flair
  • trunk/include/FlairSimulator/Blade.h

    r9 r13  
    2020#include <ISceneNode.h>
    2121
    22 namespace irr
    23 {
    24     namespace scene
    25     {
    26         class IMesh;
    27     }
     22namespace irr {
     23namespace scene {
     24class IMesh;
     25}
    2826}
    2927
    30 namespace flair
    31 {
    32 namespace simulator
    33 {
    34     class MeshSceneNode;
    35     class Model;
     28namespace flair {
     29namespace simulator {
     30class MeshSceneNode;
     31class Model;
    3632
    37     class Blade : public irr::scene::ISceneNode
    38     {
    39         public:
     33class Blade : public irr::scene::ISceneNode {
     34public:
     35  Blade(Model *parent,
     36        const irr::core::vector3df &position = irr::core::vector3df(0, 0, 0),
     37        bool inverted = false, irr::s32 id = -1);
     38  virtual void OnRegisterSceneNode(void);
     39  virtual void render(void);
     40  virtual const irr::core::aabbox3d<irr::f32> &getBoundingBox(void) const {
     41    return Box;
     42  }
     43  void SetRotationSpeed(float value);
    4044
    41             Blade(Model* parent,const irr::core::vector3df& position = irr::core::vector3df(0,0,0),bool inverted=false,irr::s32 id=-1);
    42             virtual void OnRegisterSceneNode(void);
    43             virtual void render(void);
    44             virtual const irr::core::aabbox3d<irr::f32>& getBoundingBox(void) const
    45             {
    46                 return Box;
    47             }
    48             void SetRotationSpeed(float value);
    49 
    50 
    51         private:
    52             irr::scene::IMesh *pale;
    53             irr::core::aabbox3d<irr::f32> Box;
    54             MeshSceneNode *pale_1,*pale_2;
    55             irr::scene::ISceneNodeAnimator *anim;
    56     };
     45private:
     46  irr::scene::IMesh *pale;
     47  irr::core::aabbox3d<irr::f32> Box;
     48  MeshSceneNode *pale_1, *pale_2;
     49  irr::scene::ISceneNodeAnimator *anim;
     50};
    5751} // end namespace simulator
    5852} // end namespace flair
  • trunk/include/FlairSimulator/Castle.h

    r9 r13  
    1919
    2020#include <Gui.h>
    21 namespace flair
    22 {
    23 namespace simulator
    24 {
    25     class Castle:public Gui
    26     {
    27         public:
    28             Castle(const flair::simulator::Simulator* parent,int app_width, int app_height,int scene_width, int scene_height,std::string media_path);
    29             ~Castle();
     21namespace flair {
     22namespace simulator {
     23class Castle : public Gui {
     24public:
     25  Castle(const flair::simulator::Simulator *parent, int app_width,
     26         int app_height, int scene_width, int scene_height,
     27         std::string media_path);
     28  ~Castle();
    3029
    31         private:
    32 
    33     };
     30private:
     31};
    3432} // end namespace simulator
    3533} // end namespace flair
  • trunk/include/FlairSimulator/DiscreteTimeVariable.h

    r9 r13  
    2020#include <stdlib.h>
    2121
    22 namespace flair
    23 {
    24 namespace simulator
    25 {
    26     template <typename T,size_t size>
    27     class DiscreteTimeVariable
    28     {
    29         public:
    30             DiscreteTimeVariable(){};
    31             ~DiscreteTimeVariable(){};
    32             T& operator[](ssize_t idx)
    33             {
    34                 if(idx>0) idx=0;
    35                 if(idx<(ssize_t)(-size+1)) idx=-size+1;
    36                 return array[-idx];
    37             }
    38             const T&operator[](ssize_t idx) const
    39             {
    40                 return const_cast<T&>(*this)[idx];
    41             };
    42             void Update(void)
    43             {
    44                 for(int i=size-1;i>0;i--)
    45                 {
    46                     array[i]=array[i-1];
    47                 }
    48             }
     22namespace flair {
     23namespace simulator {
     24template <typename T, size_t size> class DiscreteTimeVariable {
     25public:
     26  DiscreteTimeVariable(){};
     27  ~DiscreteTimeVariable(){};
     28  T &operator[](ssize_t idx) {
     29    if (idx > 0)
     30      idx = 0;
     31    if (idx < (ssize_t)(-size + 1))
     32      idx = -size + 1;
     33    return array[-idx];
     34  }
     35  const T &operator[](ssize_t idx) const {
     36    return const_cast<T &>(*this)[idx];
     37  };
     38  void Update(void) {
     39    for (int i = size - 1; i > 0; i--) {
     40      array[i] = array[i - 1];
     41    }
     42  }
    4943
    50         private:
    51             T array[size];
    52 
    53     };
     44private:
     45  T array[size];
     46};
    5447} // end namespace simulator
    5548} // end namespace flair
  • trunk/include/FlairSimulator/Gui.h

    r9 r13  
    2222#include <vector3d.h>
    2323
    24 namespace irr
    25 {
    26     class IrrlichtDevice;
    27     namespace video
    28     {
    29         class ITexture;
    30     }
    31     namespace scene
    32     {
    33         class IAnimatedMesh;
    34         class ISceneManager;
    35     }
     24namespace irr {
     25class IrrlichtDevice;
     26namespace video {
     27class ITexture;
     28}
     29namespace scene {
     30class IAnimatedMesh;
     31class ISceneManager;
     32}
    3633}
    3734
    38 namespace flair
    39 {
    40     namespace core
    41     {
    42        class Object;
    43        class Vector3D;
    44        class Euler;
    45        class Quaternion;
    46     }
     35namespace flair {
     36namespace core {
     37class Object;
     38class Vector3D;
     39class Euler;
     40class Quaternion;
     41}
    4742}
    4843
     
    5146class Model_impl;
    5247
    53 namespace flair
    54 {
    55 namespace simulator
    56 {
    57     class Simulator;
     48namespace flair {
     49namespace simulator {
     50class Simulator;
    5851
    59     class Gui: public core::Object
    60     {
    61         friend class ::Simulator_impl;
     52class Gui : public core::Object {
     53  friend class ::Simulator_impl;
    6254
    63         public:
    64             Gui(const Simulator* parent,std::string name,int app_width, int app_height,int scene_width, int scene_height,std::string media_path,irr::video::E_DRIVER_TYPE driver_type=irr::video::EDT_OPENGL);
    65             ~Gui();
    66             irr::core::vector3df getRotation(void) const;
    67             irr::video::ITexture* getTexture(std::string filename) const;
    68             irr::scene::IAnimatedMesh* getMesh(std::string filename) const;
    69             irr::scene::ISceneManager* getSceneManager(void) const;
    70             float getAspectRatio(void) const;
     55public:
     56  Gui(const Simulator *parent, std::string name, int app_width, int app_height,
     57      int scene_width, int scene_height, std::string media_path,
     58      irr::video::E_DRIVER_TYPE driver_type = irr::video::EDT_OPENGL);
     59  ~Gui();
     60  irr::core::vector3df getRotation(void) const;
     61  irr::video::ITexture *getTexture(std::string filename) const;
     62  irr::scene::IAnimatedMesh *getMesh(std::string filename) const;
     63  irr::scene::ISceneManager *getSceneManager(void) const;
     64  float getAspectRatio(void) const;
    7165
    72         protected:
    73             irr::IrrlichtDevice *getDevice(void) const;
    74             void setMesh(std::string file,irr::core::vector3df position = irr::core::vector3df(0,0,0),irr::core::vector3df rotation= irr::core::vector3df(0,0,0),irr::core::vector3df scale= irr::core::vector3df(1,1,1));
     66protected:
     67  irr::IrrlichtDevice *getDevice(void) const;
     68  void setMesh(std::string file,
     69               irr::core::vector3df position = irr::core::vector3df(0, 0, 0),
     70               irr::core::vector3df rotation = irr::core::vector3df(0, 0, 0),
     71               irr::core::vector3df scale = irr::core::vector3df(1, 1, 1));
    7572
    76         private:
    77             Gui_impl *pimpl_;
    78     };
     73private:
     74  Gui_impl *pimpl_;
     75};
    7976
    80     /*!
    81     * \brief get Gui
    82     *
    83     * \return the Gui
    84     */
    85     Gui* getGui(void);
     77/*!
     78* \brief get Gui
     79*
     80* \return the Gui
     81*/
     82Gui *getGui(void);
    8683
    87     bool noGui(void);
     84bool noGui(void);
    8885
    89     bool isGlExtensionSupported(const std::string& ext); // check if a extension is supported
     86bool isGlExtensionSupported(
     87    const std::string &ext); // check if a extension is supported
    9088
    91     /*!
    92     * \brief Convert to irrlicht scale
    93     *
    94     * \param value value in simulator scale
    95     *
    96     * \return value in irrlicht scale
    97     */
    98     float ToIrrlichtScale(float value);
     89/*!
     90* \brief Convert to irrlicht scale
     91*
     92* \param value value in simulator scale
     93*
     94* \return value in irrlicht scale
     95*/
     96float ToIrrlichtScale(float value);
    9997
    100     /*!
    101     * \brief Convert to simulator scale
    102     *
    103     * \param value value in irrlicht scale
    104     *
    105     * \return value in simulator scale
    106     */
    107     float ToSimulatorScale(float value);
     98/*!
     99* \brief Convert to simulator scale
     100*
     101* \param value value in irrlicht scale
     102*
     103* \return value in simulator scale
     104*/
     105float ToSimulatorScale(float value);
    108106
    109     /*!
    110     * \brief Convert to irrlicht coordinates
    111     *
    112     * irrlicht is left handed and as a different scale
    113     *
    114     * \param vect vector in simulator coordinates
    115     *
    116     * \return vector in irrlicht coordinates
    117     */
    118     irr::core::vector3df ToIrrlichtCoordinates(irr::core::vector3df vect);
     107/*!
     108* \brief Convert to irrlicht coordinates
     109*
     110* irrlicht is left handed and as a different scale
     111*
     112* \param vect vector in simulator coordinates
     113*
     114* \return vector in irrlicht coordinates
     115*/
     116irr::core::vector3df ToIrrlichtCoordinates(irr::core::vector3df vect);
    119117
    120     /*!
    121     * \brief Convert to irrlicht coordinates
    122     *
    123     * irrlicht is left handed and as a different scale
    124     *
    125     * \param vect vector in simulator coordinates
    126     *
    127     * \return vector in irrlicht coordinates
    128     */
    129     irr::core::vector3df ToIrrlichtCoordinates(core::Vector3D vect);
     118/*!
     119* \brief Convert to irrlicht coordinates
     120*
     121* irrlicht is left handed and as a different scale
     122*
     123* \param vect vector in simulator coordinates
     124*
     125* \return vector in irrlicht coordinates
     126*/
     127irr::core::vector3df ToIrrlichtCoordinates(core::Vector3D vect);
    130128
    131     /*!
    132     * \brief Convert to simulator coordinates
    133     *
    134     * irrlicht is left handed and as a different scale
    135     *
    136     * \param vect vector in irrlicht coordinates
    137     *
    138     * \return vector in simulator coordinates
    139     */
    140     core::Vector3D ToSimulatorCoordinates(irr::core::vector3df vect);
     129/*!
     130* \brief Convert to simulator coordinates
     131*
     132* irrlicht is left handed and as a different scale
     133*
     134* \param vect vector in irrlicht coordinates
     135*
     136* \return vector in simulator coordinates
     137*/
     138core::Vector3D ToSimulatorCoordinates(irr::core::vector3df vect);
    141139
    142     /*!
    143     * \brief Convert to irrlicht orientation
    144     *
    145     * irrlicht is left handed
    146     *
    147     * \param quat quaternion in simulator frame
    148     *
    149     * \return quaternion in irrlicht frame
    150     */
    151     core::Quaternion ToIrrlichtOrientation(core::Quaternion quat);
     140/*!
     141* \brief Convert to irrlicht orientation
     142*
     143* irrlicht is left handed
     144*
     145* \param quat quaternion in simulator frame
     146*
     147* \return quaternion in irrlicht frame
     148*/
     149core::Quaternion ToIrrlichtOrientation(core::Quaternion quat);
    152150
    153151} // end namespace simulator
  • trunk/include/FlairSimulator/Man.h

    r9 r13  
    2020#include <Model.h>
    2121
    22 namespace irr
    23 {
    24     namespace scene
    25     {
    26         class IAnimatedMeshSceneNode;
    27     }
     22namespace irr {
     23namespace scene {
     24class IAnimatedMeshSceneNode;
     25}
    2826}
    2927
    30 namespace flair
    31 {
    32     namespace gui
    33     {
    34         class DoubleSpinBox;
    35     }
     28namespace flair {
     29namespace gui {
     30class DoubleSpinBox;
     31}
    3632}
    3733
    38 namespace flair
    39 {
    40 namespace simulator
    41 {
    42     class Simulator;
     34namespace flair {
     35namespace simulator {
     36class Simulator;
    4337
    44     class Man: private Model
    45     {
    46         public:
    47             Man(const Simulator* parent,std::string name);
    48             ~Man();
     38class Man : private Model {
     39public:
     40  Man(const Simulator *parent, std::string name);
     41  ~Man();
    4942
    50         private:
    51             size_t dbtSize(void) const;
    52             void WritedbtBuf(char* dbtbuf);
    53             void ReaddbtBuf(char* dbtbuf);
    54             void CalcModel(void);
    55             void AnimateModel(void){};
    56             bool OnEvent(const irr::SEvent& event);
     43private:
     44  size_t dbtSize(void) const;
     45  void WritedbtBuf(char *dbtbuf);
     46  void ReaddbtBuf(char *dbtbuf);
     47  void CalcModel(void);
     48  void AnimateModel(void){};
     49  bool OnEvent(const irr::SEvent &event);
    5750
    58             irr::scene::IAnimatedMeshSceneNode* node;
    59             gui::DoubleSpinBox *t_speed,*r_speed;
    60     };
     51  irr::scene::IAnimatedMeshSceneNode *node;
     52  gui::DoubleSpinBox *t_speed, *r_speed;
     53};
    6154} // end namespace simulator
    6255} // end namespace flair
  • trunk/include/FlairSimulator/MeshSceneNode.h

    r9 r13  
    2020#include <IMeshSceneNode.h>
    2121
    22 namespace flair
    23 {
    24 namespace simulator
    25 {
    26     class Model;
     22namespace flair {
     23namespace simulator {
     24class Model;
    2725
    28     class MeshSceneNode : public irr::scene::IMeshSceneNode
    29     {
    30         public:
    31             MeshSceneNode(Model* parent,irr::scene::IMesh* mesh,
    32                 const irr::core::vector3df& position = irr::core::vector3df(0,0,0),
    33                 const irr::core::vector3df& rotation = irr::core::vector3df(0,0,0),
    34                 irr::video::ITexture* texture=NULL, irr::s32 id=-1);
     26class MeshSceneNode : public irr::scene::IMeshSceneNode {
     27public:
     28  MeshSceneNode(
     29      Model *parent, irr::scene::IMesh *mesh,
     30      const irr::core::vector3df &position = irr::core::vector3df(0, 0, 0),
     31      const irr::core::vector3df &rotation = irr::core::vector3df(0, 0, 0),
     32      irr::video::ITexture *texture = NULL, irr::s32 id = -1);
    3533
    36             virtual void OnRegisterSceneNode(void);
    37             virtual void render(void);
    38             virtual const irr::core::aabbox3d<irr::f32>& getBoundingBox() const
    39             {
    40                 return Box;
    41             }
    42             virtual irr::u32 getMaterialCount(void) const
    43             {
    44                 return 1;
    45             }
    46             virtual irr::video::SMaterial& getMaterial(irr::u32 i);
    47             virtual void setMesh( irr::scene::IMesh* ptr);
    48             virtual  irr::scene::IMesh* getMesh(void);
    49             virtual void setReadOnlyMaterials(bool readonly);
    50             virtual bool isReadOnlyMaterials(void) const
    51             {
    52                 return false;
    53             }
    54             virtual irr::scene::IShadowVolumeSceneNode* addShadowVolumeSceneNode(const irr::scene::IMesh* shadowMesh=0,
    55             irr::s32 id=-1, bool zfailmethod=true, irr::f32 infinity=1000.0f)
    56             {
    57                 return NULL;
    58             }
     34  virtual void OnRegisterSceneNode(void);
     35  virtual void render(void);
     36  virtual const irr::core::aabbox3d<irr::f32> &getBoundingBox() const {
     37    return Box;
     38  }
     39  virtual irr::u32 getMaterialCount(void) const { return 1; }
     40  virtual irr::video::SMaterial &getMaterial(irr::u32 i);
     41  virtual void setMesh(irr::scene::IMesh *ptr);
     42  virtual irr::scene::IMesh *getMesh(void);
     43  virtual void setReadOnlyMaterials(bool readonly);
     44  virtual bool isReadOnlyMaterials(void) const { return false; }
     45  virtual irr::scene::IShadowVolumeSceneNode *
     46  addShadowVolumeSceneNode(const irr::scene::IMesh *shadowMesh = 0,
     47                           irr::s32 id = -1, bool zfailmethod = true,
     48                           irr::f32 infinity = 1000.0f) {
     49    return NULL;
     50  }
    5951
    60         private:
    61             irr::scene::IMesh *mesh;
    62             irr::core::aabbox3d<irr::f32> Box;
    63             irr::video::SMaterial Material;
    64     };
     52private:
     53  irr::scene::IMesh *mesh;
     54  irr::core::aabbox3d<irr::f32> Box;
     55  irr::video::SMaterial Material;
     56};
    6557} // end namespace simulator
    6658} // end namespace flair
  • trunk/include/FlairSimulator/Model.h

    r9 r13  
    2525#ifdef GL
    2626#include <aabbox3d.h>
    27 namespace irr
    28 {
    29     class SEvent;
    30     namespace scene
    31     {
    32         class ISceneManager;
    33         class ISceneNode;
    34         class ITriangleSelector;
    35     }
     27namespace irr {
     28class SEvent;
     29namespace scene {
     30class ISceneManager;
     31class ISceneNode;
     32class ITriangleSelector;
     33}
    3634}
    3735#endif
    3836
    39 namespace flair
    40 {
    41     namespace gui
    42     {
    43         class TabWidget;
    44     }
    45     namespace sensor
    46     {
    47         class SensorGL;
    48     }
     37namespace flair {
     38namespace gui {
     39class TabWidget;
     40}
     41namespace sensor {
     42class SensorGL;
     43}
    4944}
    5045
     
    5348class Model_impl;
    5449
    55 namespace flair
    56 {
    57 namespace simulator
    58 {
    59     class Simulator;
    60     class AnimPoursuite;
     50namespace flair {
     51namespace simulator {
     52class Simulator;
     53class AnimPoursuite;
    6154
    62     class Model : public core::IODevice
    63     {
    64         friend class ::Gui_impl;
    65         friend class ::Simulator_impl;
    66         friend class ::Model_impl;
    67         friend class AnimPoursuite;
    68         friend class sensor::SensorGL;
     55class Model : public core::IODevice {
     56  friend class ::Gui_impl;
     57  friend class ::Simulator_impl;
     58  friend class ::Model_impl;
     59  friend class AnimPoursuite;
     60  friend class sensor::SensorGL;
    6961
    70         public:
    71             Model(const Simulator* parent,std::string name);
    72             virtual ~Model();
     62public:
     63  Model(const Simulator *parent, std::string name);
     64  virtual ~Model();
    7365
     66  typedef struct simu_state {
     67    core::Quaternion Quat;
     68    core::Vector3D W;
     69    core::Vector3D Pos;
     70    core::Vector3D Vel;
     71  } simu_state_t;
    7472
    75             typedef struct simu_state {
    76                 core::Quaternion Quat;
    77                 core::Vector3D W;
    78                 core::Vector3D Pos;
    79                 core::Vector3D Vel;
    80             } simu_state_t;
     73#ifdef GL
     74  irr::scene::ISceneNode *getSceneNode() const;
     75  irr::core::aabbox3d<irr::f32> *Box() const;
    8176
    82     #ifdef GL
    83             irr::scene::ISceneNode* getSceneNode() const;
    84             irr::core::aabbox3d<irr::f32>* Box() const;
     77  virtual size_t dbtSize(void) const = 0;
     78  virtual void Draw(void){};
     79  virtual void ExtraDraw(void){};
     80  virtual void WritedbtBuf(char *dbtbuf) = 0;
     81  virtual void ReaddbtBuf(char *dbtbuf) = 0;
     82  virtual bool OnEvent(const irr::SEvent &event) = 0;
    8583
    86             virtual size_t dbtSize(void) const =0;
    87             virtual void Draw(void){};
    88             virtual void ExtraDraw(void){};
    89             virtual void WritedbtBuf(char* dbtbuf)=0;
    90             virtual void ReaddbtBuf(char* dbtbuf)=0;
    91             virtual bool OnEvent(const irr::SEvent& event)=0;
     84  //! Sets the value of the camera's far clipping plane (default: 2000.0f)
     85  /** \param zf: New z far value. */
     86  void setCameraFarValue(float zf);
     87#endif
     88  gui::TabWidget *GetTabWidget(void) const;
    9289
    93             //! Sets the value of the camera's far clipping plane (default: 2000.0f)
    94             /** \param zf: New z far value. */
    95             void setCameraFarValue(float zf);
    96     #endif
    97             gui::TabWidget* GetTabWidget(void) const;
     90protected:
     91  DiscreteTimeVariable<simu_state_t, 3> state;
     92  float dT(void) const;
     93  virtual void CalcModel(void) = 0;
     94#ifdef GL
     95  AnimPoursuite *getCamera(void) const;
     96  virtual void AnimateModel(void) = 0;
     97  // void setPosition(core::Vector3D pos);
     98  void setScale(float value);
     99  void setTriangleSelector(irr::scene::ITriangleSelector *selector);
     100#endif
    98101
    99         protected:
    100             DiscreteTimeVariable<simu_state_t,3> state;
    101             float dT(void) const;
    102             virtual void CalcModel(void)=0;
    103     #ifdef GL
    104             AnimPoursuite* getCamera(void) const;
    105             virtual void AnimateModel(void)=0;
    106             //void setPosition(core::Vector3D pos);
    107             void setScale(float value);
    108             void setTriangleSelector(irr::scene::ITriangleSelector* selector);
    109     #endif
    110 
    111         private:
    112             void UpdateFrom(const core::io_data *data){};
    113             class Model_impl* pimpl_;
    114     };
     102private:
     103  void UpdateFrom(const core::io_data *data){};
     104  class Model_impl *pimpl_;
     105};
    115106} // end namespace simulator
    116107} // end namespace flair
  • trunk/include/FlairSimulator/Parser.h

    r9 r13  
    2222#include <libxml/tree.h>
    2323
    24 namespace flair
    25 {
    26 namespace simulator
    27 {
    28 class Parser:public Gui
    29 {
     24namespace flair {
     25namespace simulator {
     26class Parser : public Gui {
    3027
    31 /*can create:
    32 - cylinders: in y axis
     28  /*can create:
     29  - cylinders: in y axis
    3330
    34 */
    35     public:
    36         Parser(Simulator* parent,int app_width, int app_height,int scene_width, int scene_height,std::string media_path, std::string xmlFile);
    37         ~Parser();
     31  */
     32public:
     33  Parser(Simulator *parent, int app_width, int app_height, int scene_width,
     34         int scene_height, std::string media_path, std::string xmlFile);
     35  ~Parser();
    3836
    39 
    40     private:
    41         xmlDoc *doc;
    42         std::string media_path;
    43         Simulator* parent;
    44         void processElements(xmlNode * a_node);
    45         void processObjects(xmlNode * a_node);
    46         void processParams(xmlNode * a_node);
    47         irr::core::vector3df getMeshVect(xmlNode * mesh_node, xmlChar * param);
    48         irr::core::vector3df getSceneVect(xmlNode * mesh_node, xmlChar * param, bool isScale=false);
     37private:
     38  xmlDoc *doc;
     39  std::string media_path;
     40  Simulator *parent;
     41  void processElements(xmlNode *a_node);
     42  void processObjects(xmlNode *a_node);
     43  void processParams(xmlNode *a_node);
     44  irr::core::vector3df getMeshVect(xmlNode *mesh_node, xmlChar *param);
     45  irr::core::vector3df getSceneVect(xmlNode *mesh_node, xmlChar *param,
     46                                    bool isScale = false);
    4947};
    5048}
  • trunk/include/FlairSimulator/SensorGL.h

    r9 r13  
    1818#define SENSORGL_H
    1919
    20 namespace irr
    21 {
    22     namespace scene
    23     {
    24         class ISceneNode;
    25         class ISceneCollisionManager;
    26     }
     20namespace irr {
     21namespace scene {
     22class ISceneNode;
     23class ISceneCollisionManager;
     24}
    2725}
    2826
    29 namespace flair
    30 {
    31     namespace simulator
    32     {
    33         class Model;
    34     }
     27namespace flair {
     28namespace simulator {
     29class Model;
     30}
    3531}
    3632
    37 namespace flair
    38 {
    39 namespace sensor
    40 {
    41     class SensorGL
    42     {
    43         public:
    44             SensorGL(const simulator::Model *parent);
    45             virtual ~SensorGL()=0;
     33namespace flair {
     34namespace sensor {
     35class SensorGL {
     36public:
     37  SensorGL(const simulator::Model *parent);
     38  virtual ~SensorGL() = 0;
    4639
    47         protected:
    48     #ifdef GL
    49             irr::scene::ISceneCollisionManager* CollMan(void) const;
    50             irr::scene::ISceneNode* Node(void) const;
    51     #endif
    52         private:
    53     #ifdef GL
    54             irr::scene::ISceneCollisionManager* collMan;
    55             irr::scene::ISceneNode* node;
    56     #endif
    57     };
     40protected:
     41#ifdef GL
     42  irr::scene::ISceneCollisionManager *CollMan(void) const;
     43  irr::scene::ISceneNode *Node(void) const;
     44#endif
     45private:
     46#ifdef GL
     47  irr::scene::ISceneCollisionManager *collMan;
     48  irr::scene::ISceneNode *node;
     49#endif
     50};
    5851} // end namespace sensor
    5952} // end namespace flair
  • trunk/include/FlairSimulator/SimuCameraGL.h

    r9 r13  
    1818#include <ISceneNodeAnimator.h>
    1919
    20 // in order to get function prototypes from glext.h, define GL_GLEXT_PROTOTYPES before including glext.h
     20// in order to get function prototypes from glext.h, define GL_GLEXT_PROTOTYPES
     21// before including glext.h
    2122#define GL_GLEXT_PROTOTYPES
    2223#include <GL/gl.h>
    2324
    24 namespace irr
    25 {
    26     namespace scene
    27     {
    28         class ICameraSceneNode;
    29     }
     25namespace irr {
     26namespace scene {
     27class ICameraSceneNode;
     28}
    3029}
    3130
    32 namespace flair
    33 {
    34     namespace gui
    35     {
    36         class DoubleSpinBox;
    37         class Vector3DSpinBox;
    38     }
    39     namespace simulator
    40     {
    41         class Model;
    42     }
     31namespace flair {
     32namespace gui {
     33class DoubleSpinBox;
     34class Vector3DSpinBox;
     35}
     36namespace simulator {
     37class Model;
     38}
    4339}
    4440
    45 namespace flair
    46 {
    47 namespace sensor
    48 {
    49     /*! \class SimuCameraGL
    50     * \brief Class for a simulation camera
    51     *
    52     */
    53     class SimuCameraGL : public SimuCamera, public SensorGL, public irr::scene::ISceneNodeAnimator
    54     {
    55         public:
    56             //top left origin
    57             SimuCameraGL(const simulator::Model* parent,std::string name,int width,int height,int x,int y,int dev_id);
    58             ~SimuCameraGL();
    59             //! Sets the value of the near clipping plane. (default: 1.0f)
    60             /** \param zn: New z near value. */
    61             void setNearValue(float zn);
     41namespace flair {
     42namespace sensor {
     43/*! \class SimuCameraGL
     44* \brief Class for a simulation camera
     45*
     46*/
     47class SimuCameraGL : public SimuCamera,
     48                     public SensorGL,
     49                     public irr::scene::ISceneNodeAnimator {
     50public:
     51  // top left origin
     52  SimuCameraGL(const simulator::Model *parent, std::string name, int width,
     53               int height, int x, int y, int dev_id);
     54  ~SimuCameraGL();
     55  //! Sets the value of the near clipping plane. (default: 1.0f)
     56  /** \param zn: New z near value. */
     57  void setNearValue(float zn);
    6258
    63             //! Sets the value of the far clipping plane (default: 2000.0f)
    64             /** \param zf: New z far value. */
    65             void setFarValue(float zf);
     59  //! Sets the value of the far clipping plane (default: 2000.0f)
     60  /** \param zf: New z far value. */
     61  void setFarValue(float zf);
    6662
    67         private:
    68             void UpdateFrom(const core::io_data *data);
    69             void animateNode(irr::scene::ISceneNode* node, irr::u32 timeMs);
    70             ISceneNodeAnimator* createClone(irr::scene::ISceneNode* node,irr::scene::ISceneManager* newManager=0);
    71             void getImage(void);
    72             void putImage(char* pixels);
    73             irr::scene::ICameraSceneNode* camera;
    74             irr::scene::ISceneManager* smgr;
    75             gui::Vector3DSpinBox *position,*direction,*up;
    76             gui::DoubleSpinBox *fov;
    77             int width,height,x,y;
    78             char* buffer;
    79             bool use_pbo,invert_pixel,disable_output;
    80             GLuint *pboIds;
    81             int index ;
    82     };
     63private:
     64  void UpdateFrom(const core::io_data *data);
     65  void animateNode(irr::scene::ISceneNode *node, irr::u32 timeMs);
     66  ISceneNodeAnimator *createClone(irr::scene::ISceneNode *node,
     67                                  irr::scene::ISceneManager *newManager = 0);
     68  void getImage(void);
     69  void putImage(char *pixels);
     70  irr::scene::ICameraSceneNode *camera;
     71  irr::scene::ISceneManager *smgr;
     72  gui::Vector3DSpinBox *position, *direction, *up;
     73  gui::DoubleSpinBox *fov;
     74  int width, height, x, y;
     75  char *buffer;
     76  bool use_pbo, invert_pixel, disable_output;
     77  GLuint *pboIds;
     78  int index;
     79};
    8380} // end namespace simulator
    8481} // end namespace flair
  • trunk/include/FlairSimulator/SimuLaserGL.h

    r9 r13  
    1717#include <SensorGL.h>
    1818
    19 namespace flair
    20 {
    21     namespace gui
    22     {
    23         class DoubleSpinBox;
    24         class Vector3DSpinBox;
    25     }
     19namespace flair {
     20namespace gui {
     21class DoubleSpinBox;
     22class Vector3DSpinBox;
     23}
    2624}
    2725
    28 namespace flair
    29 {
    30     namespace simulator
    31     {
    32         class Model;
    33     }
     26namespace flair {
     27namespace simulator {
     28class Model;
     29}
    3430}
    3531
    36 namespace flair
    37 {
    38 namespace sensor
    39 {
    40     /*! \class SimuUsGL
    41     * \brief Class for a simulation us
    42     *
    43     */
    44     class SimuLaserGL : public SimuLaser, public SensorGL
    45     {
    46         public:
    47             SimuLaserGL(const simulator::Model* parent,std::string name,int dev_id);
    48             ~SimuLaserGL();
     32namespace flair {
     33namespace sensor {
     34/*! \class SimuUsGL
     35* \brief Class for a simulation us
     36*
     37*/
     38class SimuLaserGL : public SimuLaser, public SensorGL {
     39public:
     40  SimuLaserGL(const simulator::Model *parent, std::string name, int dev_id);
     41  ~SimuLaserGL();
    4942
    50         private:
    51             void UpdateFrom(const core::io_data *data);
    52             gui::DoubleSpinBox *range;
    53             gui::Vector3DSpinBox *position,*direction;
    54     };
     43private:
     44  void UpdateFrom(const core::io_data *data);
     45  gui::DoubleSpinBox *range;
     46  gui::Vector3DSpinBox *position, *direction;
     47};
    5548} // end namespace sensor
    5649} // end namespace flair
  • trunk/include/FlairSimulator/SimuUsGL.h

    r9 r13  
    1717#include <SensorGL.h>
    1818
    19 namespace flair
    20 {
    21     namespace gui
    22     {
    23         class DoubleSpinBox;
    24         class Vector3DSpinBox;
    25     }
     19namespace flair {
     20namespace gui {
     21class DoubleSpinBox;
     22class Vector3DSpinBox;
     23}
    2624}
    2725
    28 namespace flair
    29 {
    30     namespace simulator
    31     {
    32         class Model;
    33     }
     26namespace flair {
     27namespace simulator {
     28class Model;
     29}
    3430}
    3531
    36 namespace flair
    37 {
    38 namespace sensor
    39 {
    40     /*! \class SimuUsGL
    41     * \brief Class for a simulation us
    42     *
    43     */
    44     class SimuUsGL : public SimuUs, public SensorGL
    45     {
    46         public:
    47             SimuUsGL(const simulator::Model* parent,std::string name,int dev_id);
    48             ~SimuUsGL();
     32namespace flair {
     33namespace sensor {
     34/*! \class SimuUsGL
     35* \brief Class for a simulation us
     36*
     37*/
     38class SimuUsGL : public SimuUs, public SensorGL {
     39public:
     40  SimuUsGL(const simulator::Model *parent, std::string name, int dev_id);
     41  ~SimuUsGL();
    4942
    50         private:
    51             void UpdateFrom(const core::io_data *data);
    52             gui::DoubleSpinBox *range;
    53             gui::Vector3DSpinBox *position,*direction;
    54     };
     43private:
     44  void UpdateFrom(const core::io_data *data);
     45  gui::DoubleSpinBox *range;
     46  gui::Vector3DSpinBox *position, *direction;
     47};
    5548} // end namespace sensor
    5649} // end namespace flair
  • trunk/include/FlairSimulator/Simulator.h

    r9 r13  
    2424
    2525namespace flair {
    26     namespace core {
    27         class Quaternion;
    28         class Vector3D;
    29     }
     26namespace core {
     27class Quaternion;
     28class Vector3D;
     29}
    3030}
    3131
    32 namespace flair
    33 {
    34 namespace simulator
    35 {
    36     class Model;
    37     class Gui;
     32namespace flair {
     33namespace simulator {
     34class Model;
     35class Gui;
    3836
    39     class Simulator: public core::FrameworkManager
    40     {
    41         friend class Model;
    42         friend class Gui;
    43         friend class GenericObject;
     37class Simulator : public core::FrameworkManager {
     38  friend class Model;
     39  friend class Gui;
     40  friend class GenericObject;
    4441
    45         public:
    46             //yaw_deg: rotation of the vrpn coordinate with respect to the earth coordinate, around z axis
    47             Simulator(std::string name,int optitrack_mstime=10,float yaw_deg=30);
    48             ~Simulator();
    49             void RunSimu(void);
    50             //get rotation of the vrpn coordinate with respect to the earth coordinate, around z axis; in radians
    51             float Yaw(void) const;
    52             //compute rotation of the vrpn coordinate with respect to the earth coordinate, around z axis
    53             core::Quaternion ToVRPNReference(core::Quaternion quat_in);
    54             core::Vector3D ToVRPNReference(core::Vector3D point_in);
     42public:
     43  // yaw_deg: rotation of the vrpn coordinate with respect to the earth
     44  // coordinate, around z axis
     45  Simulator(std::string name, int optitrack_mstime = 10, float yaw_deg = 30);
     46  ~Simulator();
     47  void RunSimu(void);
     48  // get rotation of the vrpn coordinate with respect to the earth coordinate,
     49  // around z axis; in radians
     50  float Yaw(void) const;
     51  // compute rotation of the vrpn coordinate with respect to the earth
     52  // coordinate, around z axis
     53  core::Quaternion ToVRPNReference(core::Quaternion quat_in);
     54  core::Vector3D ToVRPNReference(core::Vector3D point_in);
    5555
    56         private:
    57             Simulator_impl* pimpl_;
    58     };
     56private:
     57  Simulator_impl *pimpl_;
     58};
    5959
    60     /*!
    61     * \brief get Simulator
    62     *
    63     * \return the Simulator
    64     */
    65     Simulator* getSimulator(void);
     60/*!
     61* \brief get Simulator
     62*
     63* \return the Simulator
     64*/
     65Simulator *getSimulator(void);
    6666
    6767} // end namespace simulator
  • trunk/include/FlairSimulator/X4.h

    r9 r13  
    2222#include <stdio.h>
    2323
    24 namespace flair
    25 {
    26     namespace core
    27     {
    28         class Mutex;
    29     }
    30     namespace gui
    31     {
    32         class DoubleSpinBox;
    33     }
    34     namespace actuator
    35     {
    36         class SimuBldc;
    37     }
     24namespace flair {
     25namespace core {
     26class Mutex;
     27}
     28namespace gui {
     29class DoubleSpinBox;
     30}
     31namespace actuator {
     32class SimuBldc;
     33}
    3834}
    3935
    4036#ifdef GL
    41 namespace irr
    42 {
    43     namespace scene
    44     {
    45         class IMesh;
    46     }
     37namespace irr {
     38namespace scene {
     39class IMesh;
     40}
    4741}
    4842#endif
    4943
    50 namespace flair
    51 {
    52 namespace simulator
    53 {
    54     class Simulator;
    55     class Blade;
    56     class MeshSceneNode;
     44namespace flair {
     45namespace simulator {
     46class Simulator;
     47class Blade;
     48class MeshSceneNode;
    5749
    58     class X4 : public Model
    59     {
    60         public:
    61             X4(const Simulator* parent,std::string name, int dev_id);
    62             ~X4();
     50class X4 : public Model {
     51public:
     52  X4(const Simulator *parent, std::string name, int dev_id);
     53  ~X4();
    6354#ifdef GL
    64             virtual void Draw(void);
    65             virtual void ExtraDraw(void){};
     55  virtual void Draw(void);
     56  virtual void ExtraDraw(void){};
    6657
    67         protected:
    68                     irr::scene::IMesh *red_arm,*black_arm,*motor;
    69                     MeshSceneNode *fl_arm,*fr_arm,*rl_arm,*rr_arm;
    70                     MeshSceneNode *fl_motor,*fr_motor,*rl_motor,*rr_motor;
    71                     Blade *fl_blade,*fr_blade,*rl_blade,*rr_blade;
    72                     core::Mutex *motor_speed_mutex;
     58protected:
     59  irr::scene::IMesh *red_arm, *black_arm, *motor;
     60  MeshSceneNode *fl_arm, *fr_arm, *rl_arm, *rr_arm;
     61  MeshSceneNode *fl_motor, *fr_motor, *rl_motor, *rr_motor;
     62  Blade *fl_blade, *fr_blade, *rl_blade, *rr_blade;
     63  core::Mutex *motor_speed_mutex;
    7364#endif
    74         private:
    75             void CalcModel(void);
    76     #ifdef GL
    77             bool OnEvent(const irr::SEvent& event){};
    78             void AnimateModel(void);
    79             size_t dbtSize(void) const;
    80             void WritedbtBuf(char* dbtbuf);
    81             void ReaddbtBuf(char* dbtbuf);
    82     #endif
     65private:
     66  void CalcModel(void);
     67#ifdef GL
     68  bool OnEvent(const irr::SEvent &event){};
     69  void AnimateModel(void);
     70  size_t dbtSize(void) const;
     71  void WritedbtBuf(char *dbtbuf);
     72  void ReaddbtBuf(char *dbtbuf);
     73#endif
    8374
    84             actuator::SimuBldc *motors;
    85             float motor_speed[4];
    86             gui::DoubleSpinBox *m,*arm_length,*l_cg;
    87             gui::DoubleSpinBox *k_mot,*c_mot;
    88             gui::DoubleSpinBox *f_air_vert,*f_air_lat;
    89             gui::DoubleSpinBox *j_roll,*j_pitch,*j_yaw;
    90     };
     75  actuator::SimuBldc *motors;
     76  float motor_speed[4];
     77  gui::DoubleSpinBox *m, *arm_length, *l_cg;
     78  gui::DoubleSpinBox *k_mot, *c_mot;
     79  gui::DoubleSpinBox *f_air_vert, *f_air_lat;
     80  gui::DoubleSpinBox *j_roll, *j_pitch, *j_yaw;
     81};
    9182} // end namespace simulator
    9283} // end namespace flair
  • trunk/include/FlairSimulator/X8.h

    r9 r13  
    2121#include <stdint.h>
    2222
    23 namespace flair
    24 {
    25     namespace core
    26     {
    27         class Mutex;
    28     }
    29     namespace gui
    30     {
    31         class DoubleSpinBox;
    32     }
    33     namespace actuator
    34     {
    35         class SimuBldc;
    36     }
     23namespace flair {
     24namespace core {
     25class Mutex;
     26}
     27namespace gui {
     28class DoubleSpinBox;
     29}
     30namespace actuator {
     31class SimuBldc;
     32}
    3733}
    3834
    3935#ifdef GL
    40 namespace irr
    41 {
    42     namespace scene
    43     {
    44         class IMesh;
    45     }
     36namespace irr {
     37namespace scene {
     38class IMesh;
     39}
    4640}
    4741#endif
    4842
    49 namespace flair
    50 {
    51 namespace simulator
    52 {
    53     class Simulator;
    54     class Blade;
    55     class MeshSceneNode;
     43namespace flair {
     44namespace simulator {
     45class Simulator;
     46class Blade;
     47class MeshSceneNode;
    5648
    57     class X8 : public Model
    58     {
    59         public:
    60             X8(const Simulator* parent,std::string name, int dev_id);
    61             ~X8();
    62             virtual void Draw(void);
    63                         virtual void ExtraDraw(void){};
    64         protected:
     49class X8 : public Model {
     50public:
     51  X8(const Simulator *parent, std::string name, int dev_id);
     52  ~X8();
     53  virtual void Draw(void);
     54  virtual void ExtraDraw(void){};
     55
     56protected:
    6557#ifdef GL
    66             irr::scene::IMesh *red_arm,*black_arm,*motor;
    67                         MeshSceneNode *fl_arm,*fr_arm,*rl_arm,*rr_arm;
    68                         MeshSceneNode *tfl_motor,*tfr_motor,*trl_motor,*trr_motor;
    69                         MeshSceneNode *bfl_motor,*bfr_motor,*brl_motor,*brr_motor;
    70                         Blade *tfl_blade,*tfr_blade,*trl_blade,*trr_blade;
    71                         Blade *bfl_blade,*bfr_blade,*brl_blade,*brr_blade;
     58  irr::scene::IMesh *red_arm, *black_arm, *motor;
     59  MeshSceneNode *fl_arm, *fr_arm, *rl_arm, *rr_arm;
     60  MeshSceneNode *tfl_motor, *tfr_motor, *trl_motor, *trr_motor;
     61  MeshSceneNode *bfl_motor, *bfr_motor, *brl_motor, *brr_motor;
     62  Blade *tfl_blade, *tfr_blade, *trl_blade, *trr_blade;
     63  Blade *bfl_blade, *bfr_blade, *brl_blade, *brr_blade;
    7264#endif
    73         private:
    74             void CalcModel(void);
    75     #ifdef GL
    76             bool OnEvent(const irr::SEvent& event){};
    77             void AnimateModel(void);
    78             size_t dbtSize(void) const;
    79             void WritedbtBuf(char* dbtbuf);
    80             void ReaddbtBuf(char* dbtbuf);
    81             core::Mutex *motor_speed_mutex;
    82     #endif
     65private:
     66  void CalcModel(void);
     67#ifdef GL
     68  bool OnEvent(const irr::SEvent &event){};
     69  void AnimateModel(void);
     70  size_t dbtSize(void) const;
     71  void WritedbtBuf(char *dbtbuf);
     72  void ReaddbtBuf(char *dbtbuf);
     73  core::Mutex *motor_speed_mutex;
     74#endif
    8375
    84             actuator::SimuBldc *motors;
    85             float motor_speed[8];
    86             gui::DoubleSpinBox *m,*arm_length,*l_cg;
    87             gui::DoubleSpinBox *k_mot,*c_mot;
    88             gui::DoubleSpinBox *f_air_vert,*f_air_lat;
    89             gui::DoubleSpinBox *j_roll,*j_pitch,*j_yaw;
    90             gui::DoubleSpinBox *j_r,*sigma,*S;
    91     };
     76  actuator::SimuBldc *motors;
     77  float motor_speed[8];
     78  gui::DoubleSpinBox *m, *arm_length, *l_cg;
     79  gui::DoubleSpinBox *k_mot, *c_mot;
     80  gui::DoubleSpinBox *f_air_vert, *f_air_lat;
     81  gui::DoubleSpinBox *j_roll, *j_pitch, *j_yaw;
     82  gui::DoubleSpinBox *j_r, *sigma, *S;
     83};
    9284} // end namespace simulator
    9385} // end namespace flair
Note: See TracChangeset for help on using the changeset viewer.