Changeset 13 in flair-dev for trunk/include/FlairCore
- Timestamp:
- Apr 8, 2016, 3:39:24 PM (9 years ago)
- Location:
- trunk/include/FlairCore
- Files:
-
- 56 edited
Legend:
- Unmodified
- Added
- Removed
-
trunk/include/FlairCore/AhrsData.h
r2 r13 18 18 #include <Quaternion.h> 19 19 20 namespace flair { namespace core { 20 namespace flair { 21 namespace core { 21 22 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 */ 30 class AhrsData : public io_data { 31 public: 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(); } 43 39 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 }; 55 43 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; 66 66 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); 72 77 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(); 83 83 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; 93 94 94 95 * \brief Get quaternion96 97 98 99 * \return quaternion100 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); 103 104 104 105 * \brief Set angular rates106 107 108 109 * \param angularRates angular rates110 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; 113 114 114 115 * \brief Get angular rates116 117 118 119 * \returnangular rates120 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); 123 124 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; 134 134 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; 145 146 146 const Type &GetDataType() const {return dataType;}147 private:148 /*!149 * \brief Copy datas150 151 * Reimplemented from io_data. \n152 * See io_data::CopyDatas.153 154 * \param dst destination buffer155 */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); 157 158 158 void Queue(char **dst,const void *src,size_t size) const;159 const Type &GetDataType() const { return dataType; } 159 160 160 /*! 161 * \brief %Quaternion 162 * 163 */ 164 Quaternion quaternion; 161 private: 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; 165 171 166 /*! 167 * \brief Angular rates 168 * 169 */ 170 Vector3D angularRates; 172 void Queue(char **dst, const void *src, size_t size) const; 171 173 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 }; 174 188 175 189 } // end namespace core -
trunk/include/FlairCore/Box.h
r2 r13 16 16 #include <Widget.h> 17 17 18 namespace flair 19 { 20 namespace gui 21 { 18 namespace flair { 19 namespace gui { 22 20 23 24 21 class Layout; 22 class LayoutPosition; 25 23 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 */ 35 class Box : public Widget { 36 public: 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); 52 52 53 54 55 56 57 53 /*! 54 * \brief Destructor 55 * 56 */ 57 ~Box(); 58 58 59 60 61 62 63 64 65 66 67 68 69 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); 70 70 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); 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. 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); 82 84 83 84 85 86 87 88 89 90 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; 91 93 92 93 94 95 96 97 98 99 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; 100 102 101 102 private: 103 bool value_changed; 104 }; 103 private: 104 bool value_changed; 105 }; 105 106 106 107 } // end namespace gui -
trunk/include/FlairCore/CheckBox.h
r2 r13 16 16 #include <Box.h> 17 17 18 namespace flair 19 { 20 namespace gui 21 { 18 namespace flair { 19 namespace gui { 22 20 23 21 class LayoutPosition; 24 22 25 26 27 28 29 30 class CheckBox: public Box 31 { 32 public:33 /*!34 * \brief Constructor35 *36 * Construct a QCheckBox at given position.37 *38 * \param position position to display the QCheckBox39 * \param name name40 * \param default_value default value if not in the xml config file41 */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 */ 28 class CheckBox : public Box { 29 public: 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); 43 41 44 45 46 47 48 42 /*! 43 * \brief Destructor 44 * 45 */ 46 ~CheckBox(); 49 47 50 51 52 53 54 55 48 /*! 49 * \brief Is checked? 50 * 51 * \return true if checked 52 */ 53 bool IsChecked(void) const; 56 54 57 58 59 60 61 62 55 /*! 56 * \brief Value 57 * 58 * \return 1 if checked, 0 otherwise 59 */ 60 int Value(void) const; 63 61 64 65 66 67 68 69 70 71 62 private: 63 /*! 64 * \brief XmlEvent from ground station 65 * 66 * Reimplemented from Widget. 67 * 68 */ 69 void XmlEvent(void); 72 70 73 74 71 bool box_value; 72 }; 75 73 76 74 } // end namespace gui -
trunk/include/FlairCore/ComboBox.h
r2 r13 16 16 #include <Box.h> 17 17 18 namespace flair 19 { 20 namespace gui 21 { 18 namespace flair { 19 namespace gui { 22 20 23 21 class LayoutPosition; 24 22 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 */ 28 class ComboBox : public Box { 29 public: 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); 42 39 43 44 45 46 47 40 /*! 41 * \brief Destructor 42 * 43 */ 44 ~ComboBox(); 48 45 49 50 51 52 53 54 55 56 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); 57 54 58 59 60 61 62 63 64 65 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; 66 63 67 68 69 70 71 72 73 74 64 private: 65 /*! 66 * \brief XmlEvent from ground station 67 * 68 * Reimplemented from Widget. 69 * 70 */ 71 void XmlEvent(void); 75 72 76 77 73 int box_value; 74 }; 78 75 79 76 } // end namespace gui -
trunk/include/FlairCore/ConditionVariable.h
r2 r13 18 18 class ConditionVariable_impl; 19 19 20 namespace flair 21 { 22 namespace core 23 { 20 namespace flair { 21 namespace core { 24 22 25 26 27 28 29 23 /*! \class ConditionVariable 24 * 25 * \brief Class defining a condition variable 26 * 27 */ 30 28 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); 29 class ConditionVariable : public Mutex { 30 public: 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); 43 40 44 45 46 47 48 41 /*! 42 * \brief Destructor 43 * 44 */ 45 ~ConditionVariable(); 49 46 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); 59 59 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); 72 76 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); 81 87 82 83 class ConditionVariable_impl*pimpl_;84 88 private: 89 class ConditionVariable_impl *pimpl_; 90 }; 85 91 86 92 } // end namespace core -
trunk/include/FlairCore/ConnectedSocket.h
r2 r13 16 16 #include <Object.h> 17 17 18 namespace flair 19 { 20 namespace core 21 { 18 namespace flair { 19 namespace core { 22 20 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 */ 27 class ConnectedSocket : public Object { 28 public: 29 /*! 30 * \brief Constructor 31 * 32 */ 33 ConnectedSocket(const Object *parent, const std::string name); 35 34 36 37 38 39 40 35 /*! 36 * \brief Destructor 37 * 38 */ 39 ~ConnectedSocket(); 41 40 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; 51 51 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 58 59 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; 69 71 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; 78 81 79 80 81 82 83 84 85 86 87 88 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; 91 94 92 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); 97 100 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; 103 107 }; 104 108 -
trunk/include/FlairCore/DataPlot.h
r2 r13 18 18 class DataPlot_impl; 19 19 20 namespace flair 21 { 22 namespace core 23 { 24 class IODataElement; 25 } 20 namespace flair { 21 namespace core { 22 class IODataElement; 26 23 } 27 namespace flair 28 { 29 namespace gui 30 { 31 class LayoutPosition; 24 } 25 namespace flair { 26 namespace gui { 27 class LayoutPosition; 32 28 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 */ 34 class DataPlot : public SendData { 35 public: 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; 53 48 54 55 56 57 58 59 60 61 62 63 64 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); 67 62 68 69 70 71 72 63 /*! 64 * \brief Destructor 65 * 66 */ 67 ~DataPlot(); 73 68 74 75 76 77 78 79 80 81 82 69 protected: 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); 83 78 84 85 86 87 88 89 90 91 92 void CopyDatas(char*buf) const;79 private: 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; 93 88 94 95 96 97 98 99 89 /*! 90 * \brief Extra Xml event 91 * 92 * Reimplemented from SendData. 93 */ 94 void ExtraXmlEvent(void){}; 100 95 101 class DataPlot_impl*pimpl_;102 96 class DataPlot_impl *pimpl_; 97 }; 103 98 104 105 106 107 108 109 110 111 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 */ 108 void RGBFromColor(DataPlot::Color_t color, uint8_t &r, uint8_t &g, uint8_t &b); 114 109 115 110 } // end namespace gui -
trunk/include/FlairCore/DataPlot1D.h
r2 r13 17 17 #include <stdint.h> 18 18 19 namespace flair 20 { 21 namespace core 22 { 23 class IODataElement; 19 namespace flair { 20 namespace core { 21 class IODataElement; 24 22 } 25 23 26 namespace gui 27 { 24 namespace gui { 28 25 29 26 class LayoutPosition; 30 27 31 32 33 34 35 36 class DataPlot1D: private DataPlot 37 { 38 public:39 /*!40 * \brief Constructor41 *42 * Construct a 1D plot at given position.43 *44 * \param position position to display the plot45 * \param name name46 * \param ymin default yminof the plot47 * \param ymax default ymax of the plot48 */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 */ 33 class DataPlot1D : private DataPlot { 34 public: 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); 50 47 51 52 53 54 55 48 /*! 49 * \brief Destructor 50 * 51 */ 52 ~DataPlot1D(); 56 53 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 = ""); 67 66 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 }; 81 82 82 83 } // end namespace gui -
trunk/include/FlairCore/DataPlot2D.h
r2 r13 17 17 #include <stdint.h> 18 18 19 namespace flair 20 { 21 namespace core 22 { 23 class IODataElement; 24 } 19 namespace flair { 20 namespace core { 21 class IODataElement; 25 22 } 26 namespace flair 27 { 28 namespace gui 29 { 23 } 24 namespace flair { 25 namespace gui { 30 26 31 27 class LayoutPosition; 32 28 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 */ 34 class DataPlot2D : private DataPlot { 35 public: 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); 56 53 57 58 59 60 61 54 /*! 55 * \brief Destructor 56 * 57 */ 58 ~DataPlot2D(); 62 59 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 = ""); 74 73 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 }; 89 90 90 91 } // end namespace gui -
trunk/include/FlairCore/DoubleSpinBox.h
r2 r13 16 16 #include <Box.h> 17 17 18 namespace flair 19 { 20 namespace gui 21 { 18 namespace flair { 19 namespace gui { 22 20 23 21 class Layout; 24 22 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 */ 28 class DoubleSpinBox : public Box { 29 public: 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); 48 47 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); 65 66 66 67 68 69 70 67 /*! 68 * \brief Destructor 69 * 70 */ 71 ~DoubleSpinBox(); 71 72 72 73 74 75 76 77 73 /*! 74 * \brief Value 75 * 76 * \return value 77 */ 78 double Value(void) const; 78 79 79 80 81 82 83 84 85 86 80 private: 81 /*! 82 * \brief XmlEvent from ground station 83 * 84 * Reimplemented from Widget. 85 * 86 */ 87 void XmlEvent(void); 87 88 88 89 89 double box_value; 90 }; 90 91 91 92 } // end namespace gui -
trunk/include/FlairCore/Euler.h
r2 r13 14 14 #define EULER_H 15 15 16 namespace flair { namespace core { 17 class Quaternion; 16 namespace flair { 17 namespace core { 18 class Quaternion; 18 19 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 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 */ 27 class Euler { 28 public: 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); 38 39 39 40 41 42 43 40 /*! 41 * \brief Destructor 42 * 43 */ 44 ~Euler(); 44 45 45 46 47 48 49 50 //todo: passer par un quaternion51 //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); 52 53 53 54 55 56 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); 59 60 60 61 62 63 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); 66 67 67 68 69 70 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); 73 74 74 75 76 77 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); 80 81 81 82 83 84 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); 87 88 88 89 90 91 92 93 89 /*! 90 * \brief Convert to quaternion 91 * 92 * \param quaternion output quaternion 93 */ 94 void ToQuaternion(Quaternion &quaternion) const; 94 95 95 96 97 98 99 100 101 102 103 104 105 106 107 108 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); 109 110 110 111 112 113 114 115 116 117 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); 118 119 119 120 121 122 123 124 125 126 127 128 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; 129 130 130 131 132 133 131 /*! 132 * \brief roll value 133 */ 134 float roll; 134 135 135 136 137 138 136 /*! 137 * \brief pitch value 138 */ 139 float pitch; 139 140 140 141 142 143 141 /*! 142 * \brief yaw value 143 */ 144 float yaw; 144 145 145 Euler& operator=(const Euler &euler); 146 147 }; 146 Euler &operator=(const Euler &euler); 147 }; 148 148 149 149 } // end namespace core -
trunk/include/FlairCore/FrameworkManager.h
r2 r13 18 18 class FrameworkManager_impl; 19 19 20 namespace flair 21 { 22 namespace gui 23 { 24 class TabWidget; 25 class SendData; 26 } 20 namespace flair { 21 namespace gui { 22 class TabWidget; 23 class SendData; 27 24 } 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 } 26 namespace flair { 27 namespace core { 28 class 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 */ 45 class FrameworkManager : public Object { 46 public: 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 208 private: 209 class FrameworkManager_impl *pimpl_; 210 }; 211 212 /*! 213 * \brief get FrameworkManager 214 * 215 * \return the FrameworkManager 216 */ 217 FrameworkManager *getFrameworkManager(void); 218 219 /*! 220 * \brief is big endian? 221 * 222 * \return true if big endian, false if little endian 223 */ 224 bool IsBigEndian(void); 218 225 219 226 } // end namespace core -
trunk/include/FlairCore/GeoCoordinate.h
r2 r13 15 15 #include <io_data.h> 16 16 17 namespace flair { namespace core { 17 namespace flair { 18 namespace core { 18 19 19 20 21 22 23 class GeoCoordinate: public io_data {24 25 class Type: public DataType {26 27 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 */ 24 class GeoCoordinate : public io_data { 25 public: 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 }; 32 33 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); 44 46 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); 58 61 59 60 61 62 63 62 /*! 63 * \brief Destructor 64 * 65 */ 66 ~GeoCoordinate(); 64 67 65 66 67 68 69 70 68 /*! 69 * \brief Copy 70 * 71 * \param point class to copy 72 */ 73 void CopyFrom(const GeoCoordinate *point); 71 74 72 73 74 75 76 77 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); 80 83 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; 89 93 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; } 101 95 102 double latitude; 103 double longitude; 104 double altitude; 105 Type dataType; 106 }; 96 private: 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 }; 107 112 108 113 } // end namespace core -
trunk/include/FlairCore/GridLayout.h
r2 r13 16 16 #include <Layout.h> 17 17 18 namespace flair 19 { 20 namespace gui 21 { 22 class LayoutPosition; 18 namespace flair { 19 namespace gui { 20 class LayoutPosition; 23 21 24 25 26 27 28 29 class GridLayout: public Layout 30 { 31 public:32 /*!33 * \brief Constructor34 *35 * Construct a QCheckBox at given position. \n36 * The GridLayout will automatically be child of position->getLayout() Layout.After calling this constructor,37 38 39 40 22 /*! \class GridLayout 23 * 24 * \brief Class displaying a QGridLayout on the ground station 25 * 26 */ 27 class GridLayout : public Layout { 28 public: 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 41 39 42 43 GridLayout(const LayoutPosition* position,std::string name);40 */ 41 GridLayout(const LayoutPosition *position, std::string name); 44 42 45 46 47 48 49 43 /*! 44 * \brief Destructor 45 * 46 */ 47 ~GridLayout(); 50 48 51 52 49 private: 50 }; 53 51 54 52 } // end namespace gui -
trunk/include/FlairCore/GroupBox.h
r2 r13 16 16 #include <Layout.h> 17 17 18 namespace flair 19 { 20 namespace gui 21 { 22 class LayoutPosition; 18 namespace flair { 19 namespace gui { 20 class LayoutPosition; 23 21 24 25 26 27 28 29 class GroupBox: public Layout 30 { 31 public:32 /*!33 * \brief Constructor34 *35 * Construct a QGroupBox at given position. \n36 * The GroupBox will automatically be child of position->getLayout() Layout.After calling this constructor,37 38 39 40 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 */ 27 class GroupBox : public Layout { 28 public: 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); 43 41 44 45 46 47 48 42 /*! 43 * \brief Destructor 44 * 45 */ 46 ~GroupBox(); 49 47 50 51 48 private: 49 }; 52 50 53 51 } // end namespace gui -
trunk/include/FlairCore/I2cPort.h
r2 r13 17 17 #include <stdint.h> 18 18 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 {} 19 namespace flair { 20 namespace 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 */ 31 class I2cPort : public Mutex { 32 public: 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) {} 44 42 45 46 47 48 49 43 /*! 44 * \brief Destructor 45 * 46 */ 47 ~I2cPort(){}; 50 48 51 52 53 54 55 56 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; 59 57 60 61 62 63 64 65 66 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; 69 67 70 71 72 73 74 75 76 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; 79 77 80 81 82 83 84 85 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; 88 86 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 }; 99 96 } // end namespace core 100 97 } // end namespace framework -
trunk/include/FlairCore/IODataElement.h
r2 r13 16 16 #include "io_data.h" 17 17 18 namespace flair { namespace core { 18 namespace flair { 19 namespace core { 19 20 20 21 class DataType; 21 22 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 */ 27 class IODataElement : public Object { 28 public: 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; } 43 40 44 virtual void CopyData(char* dst) const=0;41 virtual void CopyData(char *dst) const = 0; 45 42 46 47 48 49 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; 52 49 53 54 50 protected: 51 size_t size; 55 52 56 private: 57 const io_data* parent; 58 59 }; 53 private: 54 const io_data *parent; 55 }; 60 56 61 57 } // end namespace core -
trunk/include/FlairCore/IODevice.h
r2 r13 20 20 class FrameworkManager_impl; 21 21 22 namespace flair { namespace core { 22 namespace flair { 23 namespace core { 23 24 24 25 25 class io_data; 26 class DataType; 26 27 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 */ 44 class IODevice : public Object { 45 friend class ::IODevice_impl; 46 friend class ::Thread_impl; 47 friend class ::FrameworkManager_impl; 43 48 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); 49 public: 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); 56 63 57 58 59 60 61 64 /*! 65 * \brief Destructor 66 * 67 */ 68 virtual ~IODevice(); 62 69 63 64 65 66 67 68 69 70 71 72 73 74 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); 77 84 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); 88 96 89 90 91 92 93 94 95 96 97 98 99 100 101 102 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); 103 111 104 //TODO: these 2 method should be pure virtual105 106 112 // TODO: these 2 method should be pure virtual 113 virtual DataType const &GetInputDataType() const; 114 virtual DataType const &GetOutputDataType() const; 107 115 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); 116 protected: 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); 123 133 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; 134 private: 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; 135 146 136 class IODevice_impl*pimpl_;137 147 class IODevice_impl *pimpl_; 148 }; 138 149 139 150 } // end namespace core -
trunk/include/FlairCore/ImuData.h
r2 r13 17 17 #include <Vector3D.h> 18 18 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 }; 19 namespace flair { 20 namespace 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 */ 31 class ImuData : public io_data { 32 public: 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 186 private: 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 }; 205 218 206 219 } // end namespace core -
trunk/include/FlairCore/Label.h
r2 r13 16 16 #include <Widget.h> 17 17 18 namespace flair 19 { 20 namespace gui 21 { 18 namespace flair { 19 namespace gui { 22 20 23 21 class LayoutPosition; 24 22 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 */ 28 class Label : public Widget { 29 public: 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); 45 44 46 47 48 49 50 45 /*! 46 * \brief Destructor 47 * 48 */ 49 ~Label(); 51 50 52 53 54 55 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, ...); 58 57 59 60 char*printf_buffer;61 58 private: 59 char *printf_buffer; 60 }; 62 61 63 62 } // end namespace gui -
trunk/include/FlairCore/Layout.h
r2 r13 17 17 #include <Mutex.h> 18 18 19 namespace flair 20 { 21 namespace gui 22 { 23 class LayoutPosition; 19 namespace flair { 20 namespace gui { 21 class LayoutPosition; 24 22 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 */ 33 class Layout : public Widget { 34 friend class Box; 36 35 37 38 39 40 41 42 43 44 45 46 47 48 Layout(const Widget* parent,std::string name,std::string type);36 public: 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); 49 48 50 51 52 53 54 49 /*! 50 * \brief Destructor 51 * 52 */ 53 ~Layout(); 55 54 56 57 58 59 60 61 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; 64 63 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; 73 73 74 75 76 77 78 79 80 81 82 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; 85 85 86 87 88 89 90 91 92 93 core::Mutex*mutex;94 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 }; 95 95 96 96 } // end namespace gui -
trunk/include/FlairCore/LayoutPosition.h
r2 r13 16 16 #include <stdint.h> 17 17 18 namespace flair 19 { 20 namespace gui 21 { 22 class Layout; 18 namespace flair { 19 namespace gui { 20 class Layout; 23 21 24 25 26 27 22 /*! \class LayoutPosition 23 * 24 * \brief Class to define a position in a layout on the ground station. 25 * 28 26 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 */ 28 class LayoutPosition { 29 public: 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); 43 40 44 45 46 47 48 41 /*! 42 * \brief Destructor 43 * 44 */ 45 ~LayoutPosition(); 49 46 50 51 52 53 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; 56 53 57 58 59 60 61 62 54 /*! 55 * \brief get row 56 * 57 * \return row position 58 */ 59 int16_t Row(void) const; 63 60 64 65 66 67 68 69 61 /*! 62 * \brief get col 63 * 64 * \return col position 65 */ 66 int16_t Col(void) const; 70 67 71 72 private: 73 const Layout *layout; 74 int16_t row,col; 75 76 }; 68 private: 69 const Layout *layout; 70 int16_t row, col; 71 }; 77 72 78 73 } // end namespace gui -
trunk/include/FlairCore/Map.h
r2 r13 17 17 #include <stdint.h> 18 18 19 namespace flair 20 { 21 namespace core 22 { 23 class GeoCoordinate; 19 namespace flair { 20 namespace core { 21 class GeoCoordinate; 24 22 } 25 23 26 namespace gui 27 { 24 namespace gui { 28 25 29 26 class LayoutPosition; 30 27 31 32 33 34 35 36 class Map: public SendData 37 { 38 public:39 /*!40 * \brief Constructor41 *42 * Construct a map at given position. \n43 * The Map will automatically be child of position->getLayout() Layout. Aftercalling this constructor,44 45 46 47 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 */ 33 class Map : public SendData { 34 public: 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); 50 47 51 52 53 54 55 48 /*! 49 * \brief Destructor 50 * 51 */ 52 ~Map(); 56 53 57 58 59 60 61 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 = ""); 64 61 65 66 67 68 69 70 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; 73 70 74 75 76 77 78 79 80 71 private: 72 /*! 73 * \brief Extra Xml event 74 * 75 * Reimplemented from SendData. 76 */ 77 void ExtraXmlEvent(void); 81 78 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 }; 87 84 88 85 } // end namespace gui -
trunk/include/FlairCore/Mutex.h
r2 r13 19 19 class ConditionVariable_impl; 20 20 21 namespace flair 22 { 23 namespace core 24 { 21 namespace flair { 22 namespace core { 25 23 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 */ 29 class Mutex : public Object { 30 friend class ::ConditionVariable_impl; 34 31 35 36 37 38 39 40 41 42 43 44 Mutex(const Object *parent,std::string name="");32 public: 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 = ""); 45 42 46 47 48 49 50 43 /*! 44 * \brief Destructor 45 * 46 */ 47 ~Mutex(); 51 48 52 53 54 55 56 57 58 49 /*! 50 * \brief GetMutex 51 * 52 * Lock the mutex. 53 * 54 */ 55 void GetMutex(void) const; 59 56 60 61 62 63 64 65 66 57 /*! 58 * \brief ReleaseMutex 59 * 60 * Unlock the mutex. 61 * 62 */ 63 void ReleaseMutex(void) const; 67 64 68 69 class Mutex_impl*pimpl_;70 65 private: 66 class Mutex_impl *pimpl_; 67 }; 71 68 72 69 } // end namespace core -
trunk/include/FlairCore/Object.h
r2 r13 18 18 #include <stdarg.h> 19 19 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__) 23 23 24 24 #define TIME_INFINITE 0 … … 28 28 class Widget_impl; 29 29 30 namespace flair 31 { 32 namespace core 33 { 30 namespace flair { 31 namespace core { 34 32 35 33 class FrameworkManager; 36 34 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 }; 35 class Message { 36 public: 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 }; 48 44 49 50 51 52 53 45 /*! 46 * \brief Time definition, in ns 47 * 48 */ 49 typedef unsigned long long Time; 54 50 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 */ 58 Time GetTime(void); 61 59 62 63 64 65 66 67 68 69 60 /*! 61 * \brief Formatted print 62 * 63 * See standard printf for syntax. 64 * 65 * \param format text string to display 66 */ 67 void Printf(const char *format, ...); 70 68 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 */ 77 class Object { 78 friend class ::Widget_impl; 82 79 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=""); 80 public: 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 = ""); 100 93 101 102 103 104 105 106 107 94 /*! 95 * \brief Destructor 96 * 97 * Calling it will automatically destruct all childs. 98 * 99 */ 100 virtual ~Object(); 108 101 109 110 111 112 113 114 102 /*! 103 * \brief Name 104 * 105 * \return Object's name 106 */ 107 std::string ObjectName(void) const; 115 108 116 117 118 119 120 121 109 /*! 110 * \brief Type 111 * 112 * \return Object's type 113 */ 114 std::string ObjectType(void) const; 122 115 123 124 125 126 127 128 const Object*Parent(void) const;116 /*! 117 * \brief Parent 118 * 119 * \return Object's parent 120 */ 121 const Object *Parent(void) const; 129 122 130 131 132 133 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; 136 129 137 138 139 140 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; 143 136 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; 155 150 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; 166 162 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; 178 175 179 180 181 182 183 184 185 186 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; 189 186 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 }; 187 private: 188 class Object_impl *pimpl_; 189 void ColorPrintf(color_t, const char *function, int line, const char *format, 190 va_list *args) const; 191 }; 194 192 195 193 } // end namespace core -
trunk/include/FlairCore/OneAxisRotation.h
r2 r13 18 18 class OneAxisRotation_impl; 19 19 20 21 namespace flair 22 { 23 namespace gui 24 { 25 class LayoutPosition; 20 namespace flair { 21 namespace gui { 22 class LayoutPosition; 26 23 } 27 24 28 namespace core 29 { 30 class Vector3D; 31 class Euler; 32 class Quaternion; 33 class RotationMatrix; 25 namespace core { 26 class Vector3D; 27 class Euler; 28 class Quaternion; 29 class RotationMatrix; 34 30 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 */ 38 class OneAxisRotation : public gui::GroupBox { 39 public: 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); 54 49 55 56 57 58 59 50 /*! 51 * \brief Destructor 52 * 53 */ 54 ~OneAxisRotation(); 60 55 61 62 63 64 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; 67 62 68 69 70 71 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; 74 69 75 76 77 78 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; 81 76 82 83 84 85 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; 88 83 89 private: 90 const class OneAxisRotation_impl* pimpl_; 91 92 }; 84 private: 85 const class OneAxisRotation_impl *pimpl_; 86 }; 93 87 94 88 } // end namespace core -
trunk/include/FlairCore/Picture.h
r2 r13 17 17 #include <cxtypes.h> 18 18 19 namespace flair 20 { 21 namespace core 22 { 23 class cvimage; 19 namespace flair { 20 namespace core { 21 class cvimage; 24 22 } 25 23 26 namespace gui 27 { 24 namespace gui { 28 25 29 26 class LayoutPosition; 30 27 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 */ 33 class Picture : public SendData { 34 public: 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); 51 49 52 53 54 55 56 50 /*! 51 * \brief Destructor 52 * 53 */ 54 ~Picture(); 57 55 58 59 60 61 62 63 64 65 66 void CopyDatas(char*buf) const;56 private: 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; 67 65 68 69 70 71 72 73 66 /*! 67 * \brief Extra Xml event 68 * 69 * Reimplemented from SendData. 70 */ 71 void ExtraXmlEvent(void){}; 74 72 75 76 73 const core::cvimage *image; 74 }; 77 75 78 76 } // end namespace gui -
trunk/include/FlairCore/PushButton.h
r2 r13 16 16 #include <Widget.h> 17 17 18 namespace flair 19 { 20 namespace gui 21 { 18 namespace flair { 19 namespace gui { 22 20 23 21 class LayoutPosition; 24 22 25 26 27 28 29 30 class PushButton:public Widget 31 { 32 public:33 /*!34 * \brief Constructor35 *36 * Construct a QPushButton at given position. \n37 * The PushButton will automatically be child of position->getLayout() Layout.After calling this constructor,38 39 40 41 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 */ 28 class PushButton : public Widget { 29 public: 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); 44 42 45 46 47 48 49 43 /*! 44 * \brief Destructor 45 * 46 */ 47 ~PushButton(); 50 48 51 52 53 54 55 56 57 58 59 60 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); 61 59 62 63 64 65 66 67 68 69 60 private: 61 /*! 62 * \brief XmlEvent from ground station 63 * 64 * Reimplemented from Widget. 65 * 66 */ 67 void XmlEvent(void); 70 68 71 72 69 bool clicked; 70 }; 73 71 74 72 } // end namespace gui -
trunk/include/FlairCore/Quaternion.h
r2 r13 13 13 #define QUATERNION_H 14 14 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); 15 namespace flair { 16 namespace core { 17 class Euler; 18 class Vector3D; 19 class RotationMatrix; 20 21 /*! \class Quaternion 22 * 23 * \brief Class defining a quaternion 24 */ 25 class Quaternion { 26 public: 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 */ 158 Quaternion 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 */ 170 Quaternion 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 */ 181 Quaternion 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 */ 192 Quaternion 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 */ 204 Quaternion 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 */ 215 Quaternion operator*(Quaternion const &quaternion, float coeff); 212 216 213 217 } // end namespace core -
trunk/include/FlairCore/RTDM_I2cPort.h
r2 r13 16 16 #include <I2cPort.h> 17 17 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); 18 namespace flair { 19 namespace 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 */ 27 class RTDM_I2cPort : public I2cPort { 28 public: 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); 45 42 46 47 48 49 50 43 /*! 44 * \brief Destructor 45 * 46 */ 47 ~RTDM_I2cPort(); 51 48 52 53 54 55 56 57 58 59 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); 60 57 61 62 63 64 65 66 67 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); 70 67 71 72 73 74 75 76 77 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); 80 77 81 82 83 84 85 86 87 88 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); 89 86 90 91 92 93 94 95 96 97 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); 98 95 99 100 101 96 private: 97 int fd; 98 }; 102 99 } // end namespace core 103 100 } // end namespace flair -
trunk/include/FlairCore/RTDM_SerialPort.h
r2 r13 16 16 #include <SerialPort.h> 17 17 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 { 18 namespace flair { 19 namespace 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 */ 27 class RTDM_SerialPort : public SerialPort { 31 28 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); 29 public: 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); 44 42 45 46 47 48 49 43 /*! 44 * \brief Destructor 45 * 46 */ 47 ~RTDM_SerialPort(); 50 48 51 52 53 54 55 56 57 49 /*! 50 * \brief Set baudrate 51 * 52 * \param baudrate baudrate 53 * 54 */ 55 void SetBaudrate(int baudrate); 58 56 59 60 61 62 63 64 65 66 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); 67 65 68 69 70 71 72 73 74 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); 77 75 78 79 80 81 82 83 84 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); 87 85 88 89 90 91 92 86 /*! 87 * \brief Flush input datas 88 * 89 */ 90 void FlushInput(void); 93 91 94 95 96 92 private: 93 int fd; 94 }; 97 95 } // end namespace core 98 96 } // end namespace flair -
trunk/include/FlairCore/RangeFinderPlot.h
r2 r13 5 5 /*! 6 6 * \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 8 9 * \author Guillaume Sanahuja, Copyright Heudiasyc UMR UTC/CNRS 7253 9 10 * \date 2014/07/23 … … 17 18 #include <stdint.h> 18 19 19 namespace flair 20 { 21 namespace core 22 { 23 class cvmatrix; 24 } 20 namespace flair { 21 namespace core { 22 class cvmatrix; 23 } 25 24 } 26 25 27 namespace flair 28 { 29 namespace gui 30 { 26 namespace flair { 27 namespace gui { 31 28 32 29 class LayoutPosition; 33 30 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 */ 37 class RangeFinderPlot : public SendData { 38 public: 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); 66 65 67 68 69 70 71 66 /*! 67 * \brief Destructor 68 * 69 */ 70 ~RangeFinderPlot(); 72 71 73 74 75 76 77 78 79 80 81 void CopyDatas(char*buf) const;72 private: 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; 82 81 83 84 85 86 87 88 82 /*! 83 * \brief Extra Xml event 84 * 85 * Reimplemented from SendData. 86 */ 87 void ExtraXmlEvent(void){}; 89 88 90 const core::cvmatrix*datas;91 89 const core::cvmatrix *datas; 90 }; 92 91 93 92 } // end namespace gui -
trunk/include/FlairCore/RotationMatrix.h
r2 r13 17 17 namespace flair { 18 18 namespace core { 19 19 class Euler; 20 20 21 22 23 24 25 26 27 28 29 30 31 32 33 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(); 34 34 35 36 37 38 39 35 /*! 36 * \brief Destructor 37 * 38 */ 39 ~RotationMatrix(); 40 40 41 42 43 44 45 46 41 /*! 42 * \brief Convert to euler angles 43 * 44 * \param euler output euler angles 45 */ 46 void ToEuler(Euler &euler) const; 47 47 48 49 50 51 52 53 54 55 56 57 58 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]; 59 59 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 }; 63 63 64 64 } // end namespace core -
trunk/include/FlairCore/SendData.h
r2 r13 18 18 class SendData_impl; 19 19 20 namespace flair 21 { 22 namespace gui 23 { 24 class LayoutPosition; 20 namespace flair { 21 namespace gui { 22 class LayoutPosition; 25 23 26 27 28 29 30 31 class SendData: public Widget 32 { 33 public:34 /*!35 * \brief Constructor36 *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 */ 29 class SendData : public Widget { 30 public: 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); 39 37 40 41 42 43 44 38 /*! 39 * \brief Destructor 40 * 41 */ 42 virtual ~SendData(); 45 43 46 47 48 49 50 51 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; 54 52 55 56 57 53 size_t SendSize(void) const; 54 uint16_t SendPeriod(void) const; // in ms 55 bool IsEnabled(void) const; 58 56 59 protected: 57 protected: 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); 60 67 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; 70 76 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; 77 private: 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); 79 88 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); 90 91 91 void SetSendPeriod(uint16_t value); 92 void SetEnabled(bool value); 93 94 class SendData_impl* pimpl_; 95 }; 92 class SendData_impl *pimpl_; 93 }; 96 94 97 95 } // end namespace core -
trunk/include/FlairCore/SerialPort.h
r2 r13 17 17 #include <stdint.h> 18 18 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 {} 19 namespace flair { 20 namespace core { 21 /*! \class SerialPort 22 * 23 * \brief Base class for serial port 24 */ 25 class SerialPort : public Object { 26 public: 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) {} 40 36 41 42 43 44 45 37 /*! 38 * \brief Destructor 39 * 40 */ 41 ~SerialPort(){}; 46 42 47 48 49 50 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; 54 50 55 56 57 58 59 60 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; 63 59 64 65 66 67 68 69 70 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; 73 69 74 75 76 77 78 79 80 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; 83 79 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 }; 91 86 } // end namespace core 92 87 } // end namespace framework -
trunk/include/FlairCore/SharedMem.h
r2 r13 19 19 class SharedMem_impl; 20 20 21 namespace flair 22 { 23 namespace core 24 { 21 namespace flair { 22 namespace core { 25 23 26 27 28 29 30 31 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 */ 33 31 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); 32 class SharedMem : public Object { 33 public: 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); 47 44 48 49 50 51 52 45 /*! 46 * \brief Destructor 47 * 48 */ 49 ~SharedMem(); 53 50 54 55 56 57 58 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); 61 58 62 63 64 65 66 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; 69 66 70 71 SharedMem_impl*pimpl_;72 67 private: 68 SharedMem_impl *pimpl_; 69 }; 73 70 74 71 } // end namespace core -
trunk/include/FlairCore/Socket.h
r2 r13 20 20 class Socket_impl; 21 21 22 namespace flair 23 { 24 namespace core 25 { 22 namespace flair { 23 namespace core { 26 24 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 */ 31 class Socket : public Object { 32 public: 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); 45 45 46 47 48 49 50 51 52 53 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); 56 56 57 58 59 60 61 57 /*! 58 * \brief Destructor 59 * 60 */ 61 ~Socket(); 62 62 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); 71 72 72 73 74 75 76 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); 79 80 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); 98 100 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); 101 103 102 103 class Socket_impl*pimpl_;104 104 private: 105 class Socket_impl *pimpl_; 106 }; 105 107 106 108 } // end namespace core -
trunk/include/FlairCore/SpinBox.h
r2 r13 16 16 #include <Box.h> 17 17 18 namespace flair 19 { 20 namespace gui 21 { 18 namespace flair { 19 namespace gui { 22 20 23 21 class LayoutPosition; 24 22 25 26 27 28 29 30 class SpinBox : public Box 31 { 32 public:33 /*!34 * \brief Constructor35 *36 * Construct a QSpinBox at given position. \n37 * The QSpinBox is saturated to min and max values.38 *39 * \param position position to display the QSpinBox40 * \param name name41 * \param min minimum value42 * \param max maximum value43 * \param step step44 * \param default_value default value if not in the xml config file45 */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 */ 28 class SpinBox : public Box { 29 public: 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); /*! 47 45 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); 62 61 63 64 65 66 67 62 /*! 63 * \brief Destructor 64 * 65 */ 66 ~SpinBox(); 68 67 69 70 71 72 73 74 68 /*! 69 * \brief Value 70 * 71 * \return value 72 */ 73 int Value(void) const; 75 74 76 77 78 79 80 81 82 83 75 private: 76 /*! 77 * \brief XmlEvent from ground station 78 * 79 * Reimplemented from Widget. 80 * 81 */ 82 void XmlEvent(void); 84 83 85 86 84 int box_value; 85 }; 87 86 88 87 } // end namespace gui -
trunk/include/FlairCore/Tab.h
r2 r13 16 16 #include <Layout.h> 17 17 18 namespace flair 19 { 20 namespace gui 21 { 18 namespace flair { 19 namespace gui { 22 20 23 21 class TabWidget; 24 22 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 */ 29 class Tab : public Layout { 30 public: 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); 44 41 45 46 47 48 49 42 /*! 43 * \brief Destructor 44 * 45 */ 46 ~Tab(); 50 47 51 52 48 private: 49 }; 53 50 54 51 } // end namespace gui -
trunk/include/FlairCore/TabWidget.h
r2 r13 16 16 #include <Widget.h> 17 17 18 namespace flair 19 { 20 namespace gui 21 { 22 class LayoutPosition; 18 namespace flair { 19 namespace gui { 20 class LayoutPosition; 23 21 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 */ 29 class TabWidget : public Widget { 30 public: 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; 39 41 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); 52 56 53 54 55 56 57 57 /*! 58 * \brief Destructor 59 * 60 */ 61 ~TabWidget(); 58 62 59 60 63 private: 64 }; 61 65 62 66 } // end namespace core -
trunk/include/FlairCore/TcpSocket.h
r2 r13 16 16 #include <ConnectedSocket.h> 17 17 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 18 namespace flair { 19 namespace core { 20 /*! \class TcpSocket 21 * 22 * \brief Class encapsulating a TCP socket 23 * 24 */ 25 class TcpSocket : public ConnectedSocket { 26 public: 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 36 39 37 38 39 40 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); 41 44