Changeset 15 in flair-src for trunk/lib/FlairCore/src
- Timestamp:
- Apr 8, 2016, 3:40:57 PM (9 years ago)
- Location:
- trunk/lib/FlairCore/src
- Files:
-
- 141 edited
Legend:
- Unmodified
- Added
- Removed
-
trunk/lib/FlairCore/src/AhrsData.cpp
r2 r15 24 24 using std::string; 25 25 26 namespace flair { namespace core { 26 namespace flair { 27 namespace core { 27 28 28 29 /*! \class AhrsDataElement 29 30 */ 30 class AhrsDataElement: public IODataElement { 31 public: 32 33 AhrsDataElement(const AhrsData *inAhrsData,string name,AhrsData::PlotableData_t inPlotableData): 34 IODataElement(inAhrsData,name), 35 ahrsData(inAhrsData), 36 plotableData(inPlotableData) { 37 38 size=sizeof(float); 39 } 40 41 ~AhrsDataElement() {} 42 43 void CopyData(char* destination) const { 44 float data; 45 Vector3D angularRates; 46 Euler eulerAngles; 47 Quaternion quaternion; 48 ahrsData->GetQuaternionAndAngularRates(quaternion,angularRates); 49 quaternion.ToEuler(eulerAngles); 50 switch(plotableData) { 51 case AhrsData::Roll: 52 data=eulerAngles.roll; 53 break; 54 case AhrsData::Pitch: 55 data=eulerAngles.pitch; 56 break; 57 case AhrsData::Yaw: 58 data=eulerAngles.yaw; 59 break; 60 case AhrsData::RollDeg: 61 data=Euler::ToDegree(eulerAngles.roll); 62 break; 63 case AhrsData::PitchDeg: 64 data=Euler::ToDegree(eulerAngles.pitch); 65 break; 66 case AhrsData::YawDeg: 67 data=Euler::ToDegree(eulerAngles.yaw); 68 break; 69 case AhrsData::Q0: 70 data=quaternion.q0; 71 break; 72 case AhrsData::Q1: 73 data=quaternion.q1; 74 break; 75 case AhrsData::Q2: 76 data=quaternion.q2; 77 break; 78 case AhrsData::Q3: 79 data=quaternion.q3; 80 break; 81 case AhrsData::Wx: 82 data=angularRates.x; 83 break; 84 case AhrsData::Wy: 85 data=angularRates.y; 86 break; 87 case AhrsData::Wz: 88 data=angularRates.z; 89 break; 90 case AhrsData::WxDeg: 91 data=Euler::ToDegree(angularRates.x); 92 break; 93 case AhrsData::WyDeg: 94 data=Euler::ToDegree(angularRates.y); 95 break; 96 case AhrsData::WzDeg: 97 data=Euler::ToDegree(angularRates.z); 98 break; 99 default: 100 ahrsData->Err("data type unavailable.\n"); 101 data=0; 102 break; 103 } 104 memcpy(destination,&data,sizeof(float)); 105 } 106 107 const FloatType &GetDataType(void) const { 108 return dataType; 109 } 110 111 private: 112 const AhrsData *ahrsData; 113 AhrsData::PlotableData_t plotableData; 114 FloatType dataType; 115 116 }; 117 118 AhrsData::AhrsData(const Object *parent,std::string name,int n): io_data(parent,name,n), dataType(floatType) { 119 if(n>1) Warn("n>1 not supported\n"); 120 121 AppendLogDescription("q0",floatType); 122 AppendLogDescription("q1",floatType); 123 AppendLogDescription("q2",floatType); 124 AppendLogDescription("q3",floatType); 125 126 AppendLogDescription("wx",floatType); 127 AppendLogDescription("wy",floatType); 128 AppendLogDescription("wz",floatType); 31 class AhrsDataElement : public IODataElement { 32 public: 33 AhrsDataElement(const AhrsData *inAhrsData, string name, 34 AhrsData::PlotableData_t inPlotableData) 35 : IODataElement(inAhrsData, name), ahrsData(inAhrsData), 36 plotableData(inPlotableData) { 37 38 size = sizeof(float); 39 } 40 41 ~AhrsDataElement() {} 42 43 void CopyData(char *destination) const { 44 float data; 45 Vector3D angularRates; 46 Euler eulerAngles; 47 Quaternion quaternion; 48 ahrsData->GetQuaternionAndAngularRates(quaternion, angularRates); 49 quaternion.ToEuler(eulerAngles); 50 switch (plotableData) { 51 case AhrsData::Roll: 52 data = eulerAngles.roll; 53 break; 54 case AhrsData::Pitch: 55 data = eulerAngles.pitch; 56 break; 57 case AhrsData::Yaw: 58 data = eulerAngles.yaw; 59 break; 60 case AhrsData::RollDeg: 61 data = Euler::ToDegree(eulerAngles.roll); 62 break; 63 case AhrsData::PitchDeg: 64 data = Euler::ToDegree(eulerAngles.pitch); 65 break; 66 case AhrsData::YawDeg: 67 data = Euler::ToDegree(eulerAngles.yaw); 68 break; 69 case AhrsData::Q0: 70 data = quaternion.q0; 71 break; 72 case AhrsData::Q1: 73 data = quaternion.q1; 74 break; 75 case AhrsData::Q2: 76 data = quaternion.q2; 77 break; 78 case AhrsData::Q3: 79 data = quaternion.q3; 80 break; 81 case AhrsData::Wx: 82 data = angularRates.x; 83 break; 84 case AhrsData::Wy: 85 data = angularRates.y; 86 break; 87 case AhrsData::Wz: 88 data = angularRates.z; 89 break; 90 case AhrsData::WxDeg: 91 data = Euler::ToDegree(angularRates.x); 92 break; 93 case AhrsData::WyDeg: 94 data = Euler::ToDegree(angularRates.y); 95 break; 96 case AhrsData::WzDeg: 97 data = Euler::ToDegree(angularRates.z); 98 break; 99 default: 100 ahrsData->Err("data type unavailable.\n"); 101 data = 0; 102 break; 103 } 104 memcpy(destination, &data, sizeof(float)); 105 } 106 107 const FloatType &GetDataType(void) const { return dataType; } 108 109 private: 110 const AhrsData *ahrsData; 111 AhrsData::PlotableData_t plotableData; 112 FloatType dataType; 113 }; 114 115 AhrsData::AhrsData(const Object *parent, std::string name, int n) 116 : io_data(parent, name, n), dataType(floatType) { 117 if (n > 1) 118 Warn("n>1 not supported\n"); 119 120 AppendLogDescription("q0", floatType); 121 AppendLogDescription("q1", floatType); 122 AppendLogDescription("q2", floatType); 123 AppendLogDescription("q3", floatType); 124 125 AppendLogDescription("wx", floatType); 126 AppendLogDescription("wy", floatType); 127 AppendLogDescription("wz", floatType); 129 128 } 130 129 … … 132 131 133 132 Quaternion AhrsData::GetQuaternion(void) const { 134 135 136 out=quaternion;137 138 133 Quaternion out; 134 GetMutex(); 135 out = quaternion; 136 ReleaseMutex(); 137 return out; 139 138 } 140 139 141 140 Vector3D AhrsData::GetAngularRates(void) const { 142 Vector3D out; 143 GetMutex(); 144 out=angularRates; 145 ReleaseMutex(); 146 return out; 147 } 148 149 void AhrsData::GetQuaternionAndAngularRates(Quaternion &outQuaternion,Vector3D &outAngularRates) const { 150 GetMutex(); 151 outQuaternion=quaternion; 152 outAngularRates=angularRates; 153 ReleaseMutex(); 154 } 155 156 void AhrsData::SetQuaternionAndAngularRates(const Quaternion &inQuaternion,const Vector3D &inAngularRates) { 157 GetMutex(); 158 quaternion=inQuaternion; 159 angularRates=inAngularRates; 160 ReleaseMutex(); 141 Vector3D out; 142 GetMutex(); 143 out = angularRates; 144 ReleaseMutex(); 145 return out; 146 } 147 148 void AhrsData::GetQuaternionAndAngularRates(Quaternion &outQuaternion, 149 Vector3D &outAngularRates) const { 150 GetMutex(); 151 outQuaternion = quaternion; 152 outAngularRates = angularRates; 153 ReleaseMutex(); 154 } 155 156 void AhrsData::SetQuaternionAndAngularRates(const Quaternion &inQuaternion, 157 const Vector3D &inAngularRates) { 158 GetMutex(); 159 quaternion = inQuaternion; 160 angularRates = inAngularRates; 161 ReleaseMutex(); 161 162 } 162 163 163 164 void AhrsData::SetQuaternion(const Quaternion &inQuaternion) { 164 165 quaternion=inQuaternion;166 165 GetMutex(); 166 quaternion = inQuaternion; 167 ReleaseMutex(); 167 168 } 168 169 169 170 void AhrsData::SetAngularRates(const Vector3D &inAngularRates) { 170 171 angularRates=inAngularRates;172 173 } 174 175 IODataElement *AhrsData::Element(PlotableData_t plotableData) const {176 177 switch(plotableData) {178 179 name="Roll";180 181 182 name="Pitch";183 184 185 name="Yaw";186 187 188 name="Roll degree";189 190 191 name="Pitch degree";192 193 194 name="Yaw degree";195 196 197 name="Q0";198 199 200 name="Q1";201 202 203 name="Q2";204 205 206 name="Q3";207 208 209 name="Wx";210 211 212 name="Wy";213 214 215 name="Wz";216 217 218 name="Wx degree";219 220 221 name="Wy degree";222 223 224 name="Wz degree";225 226 227 228 229 230 return new AhrsDataElement(this,name,plotableData);171 GetMutex(); 172 angularRates = inAngularRates; 173 ReleaseMutex(); 174 } 175 176 IODataElement *AhrsData::Element(PlotableData_t plotableData) const { 177 string name; 178 switch (plotableData) { 179 case AhrsData::Roll: 180 name = "Roll"; 181 break; 182 case AhrsData::Pitch: 183 name = "Pitch"; 184 break; 185 case AhrsData::Yaw: 186 name = "Yaw"; 187 break; 188 case AhrsData::RollDeg: 189 name = "Roll degree"; 190 break; 191 case AhrsData::PitchDeg: 192 name = "Pitch degree"; 193 break; 194 case AhrsData::YawDeg: 195 name = "Yaw degree"; 196 break; 197 case AhrsData::Q0: 198 name = "Q0"; 199 break; 200 case AhrsData::Q1: 201 name = "Q1"; 202 break; 203 case AhrsData::Q2: 204 name = "Q2"; 205 break; 206 case AhrsData::Q3: 207 name = "Q3"; 208 break; 209 case AhrsData::Wx: 210 name = "Wx"; 211 break; 212 case AhrsData::Wy: 213 name = "Wy"; 214 break; 215 case AhrsData::Wz: 216 name = "Wz"; 217 break; 218 case AhrsData::WxDeg: 219 name = "Wx degree"; 220 break; 221 case AhrsData::WyDeg: 222 name = "Wy degree"; 223 break; 224 case AhrsData::WzDeg: 225 name = "Wz degree"; 226 break; 227 default: 228 Err("data type unavailable.\n"); 229 } 230 231 return new AhrsDataElement(this, name, plotableData); 231 232 } 232 233 233 234 void AhrsData::CopyDatas(char *dst) const { 234 235 Queue(&dst,&quaternion.q0,sizeof(quaternion.q0));236 Queue(&dst,&quaternion.q1,sizeof(quaternion.q1));237 Queue(&dst,&quaternion.q2,sizeof(quaternion.q2));238 Queue(&dst,&quaternion.q3,sizeof(quaternion.q3));239 240 Queue(&dst,&angularRates.x,sizeof(angularRates.x));241 Queue(&dst,&angularRates.y,sizeof(angularRates.y));242 Queue(&dst,&angularRates.z,sizeof(angularRates.z));243 244 } 245 246 void AhrsData::Queue(char **dst, const void *src,size_t size) const {247 memcpy(*dst,src,size);248 *dst+=size;235 GetMutex(); 236 Queue(&dst, &quaternion.q0, sizeof(quaternion.q0)); 237 Queue(&dst, &quaternion.q1, sizeof(quaternion.q1)); 238 Queue(&dst, &quaternion.q2, sizeof(quaternion.q2)); 239 Queue(&dst, &quaternion.q3, sizeof(quaternion.q3)); 240 241 Queue(&dst, &angularRates.x, sizeof(angularRates.x)); 242 Queue(&dst, &angularRates.y, sizeof(angularRates.y)); 243 Queue(&dst, &angularRates.z, sizeof(angularRates.z)); 244 ReleaseMutex(); 245 } 246 247 void AhrsData::Queue(char **dst, const void *src, size_t size) const { 248 memcpy(*dst, src, size); 249 *dst += size; 249 250 } 250 251 -
trunk/lib/FlairCore/src/AhrsData.h
r2 r15 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/lib/FlairCore/src/Box.cpp
r2 r15 21 21 using std::string; 22 22 23 namespace flair 24 { 25 namespace gui 26 { 23 namespace flair { 24 namespace gui { 27 25 28 Box::Box(const LayoutPosition * position,string name,string type): Widget(position->getLayout(),name,type)29 {30 value_changed=true;31 SetVolatileXmlProp("row",position->Row());32 SetVolatileXmlProp("col",position->Col());33 26 Box::Box(const LayoutPosition *position, string name, string type) 27 : Widget(position->getLayout(), name, type) { 28 value_changed = true; 29 SetVolatileXmlProp("row", position->Row()); 30 SetVolatileXmlProp("col", position->Col()); 31 delete position; 34 32 } 35 33 36 Box::~Box() 37 { 38 core::Object::ObjectName(); 34 Box::~Box() { core::Object::ObjectName(); } 35 36 bool Box::ValueChanged(void) { 37 bool ret; 38 39 GetMutex(); 40 if (value_changed == true) { 41 value_changed = false; 42 ret = true; 43 } else { 44 ret = false; 45 } 46 ReleaseMutex(); 47 48 return ret; 39 49 } 40 50 41 bool Box::ValueChanged(void) 42 { 43 bool ret; 51 void Box::SetValueChanged(void) { value_changed = true; } 44 52 45 GetMutex(); 46 if(value_changed==true) 47 { 48 value_changed=false; 49 ret=true; 50 } 51 else 52 { 53 ret=false; 54 } 55 ReleaseMutex(); 53 void Box::GetMutex(void) const { ((Layout *)Parent())->mutex->GetMutex(); } 56 54 57 return ret; 58 } 59 60 void Box::SetValueChanged(void) 61 { 62 value_changed=true; 63 } 64 65 void Box::GetMutex(void) const 66 { 67 ((Layout*)Parent())->mutex->GetMutex(); 68 } 69 70 void Box::ReleaseMutex(void) const 71 { 72 ((Layout*)Parent())->mutex->ReleaseMutex(); 55 void Box::ReleaseMutex(void) const { 56 ((Layout *)Parent())->mutex->ReleaseMutex(); 73 57 } 74 58 -
trunk/lib/FlairCore/src/Box.h
r2 r15 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/lib/FlairCore/src/CheckBox.cpp
r2 r15 19 19 using std::string; 20 20 21 namespace flair 22 { 23 namespace gui 24 { 21 namespace flair { 22 namespace gui { 25 23 26 CheckBox::CheckBox(const LayoutPosition* position,string name,bool default_value):Box(position,name,"CheckBox") 27 { 28 //update value from xml file 29 box_value=default_value; 24 CheckBox::CheckBox(const LayoutPosition *position, string name, 25 bool default_value) 26 : Box(position, name, "CheckBox") { 27 // update value from xml file 28 box_value = default_value; 30 29 31 GetPersistentXmlProp("value",box_value);32 SetPersistentXmlProp("value",Value());33 30 GetPersistentXmlProp("value", box_value); 31 SetPersistentXmlProp("value", Value()); 32 SendXml(); 34 33 } 35 34 36 CheckBox::~CheckBox() 37 { 35 CheckBox::~CheckBox() {} 38 36 37 bool CheckBox::IsChecked(void) const { 38 bool tmp; 39 40 GetMutex(); 41 tmp = box_value; 42 ReleaseMutex(); 43 44 return tmp; 39 45 } 40 46 41 bool CheckBox::IsChecked(void) const 42 { 43 bool tmp; 44 45 GetMutex(); 46 tmp=box_value; 47 ReleaseMutex(); 48 49 return tmp; 47 int CheckBox::Value(void) const { 48 if (IsChecked() == true) 49 return 1; 50 else 51 return 0; 50 52 } 51 53 52 int CheckBox::Value(void) const 53 { 54 if(IsChecked()==true) 55 return 1; 56 else 57 return 0; 58 } 59 60 void CheckBox::XmlEvent(void) 61 { 62 GetMutex(); 63 if(GetPersistentXmlProp("value",box_value)) SetValueChanged(); 64 ReleaseMutex(); 54 void CheckBox::XmlEvent(void) { 55 GetMutex(); 56 if (GetPersistentXmlProp("value", box_value)) 57 SetValueChanged(); 58 ReleaseMutex(); 65 59 } 66 60 -
trunk/lib/FlairCore/src/CheckBox.h
r2 r15 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/lib/FlairCore/src/ComboBox.cpp
r2 r15 19 19 using std::string; 20 20 21 namespace flair 22 { 23 namespace gui 24 { 21 namespace flair { 22 namespace gui { 25 23 26 ComboBox::ComboBox(const LayoutPosition * position,string name):Box(position,name,"ComboBox")27 {28 //update value from xml file29 box_value=0;30 GetPersistentXmlProp("value",box_value);31 SetPersistentXmlProp("value",box_value);24 ComboBox::ComboBox(const LayoutPosition *position, string name) 25 : Box(position, name, "ComboBox") { 26 // update value from xml file 27 box_value = 0; 28 GetPersistentXmlProp("value", box_value); 29 SetPersistentXmlProp("value", box_value); 32 30 33 31 SendXml(); 34 32 } 35 33 36 ComboBox::~ComboBox() 37 { 34 ComboBox::~ComboBox() {} 38 35 36 void ComboBox::AddItem(string name) { 37 SetVolatileXmlProp("item", name); 38 SendXml(); 39 39 } 40 40 41 void ComboBox::AddItem(string name) 42 { 43 SetVolatileXmlProp("item",name); 44 SendXml(); 41 int ComboBox::CurrentIndex(void) const { 42 int tmp; 43 44 GetMutex(); 45 tmp = box_value; 46 ReleaseMutex(); 47 48 return tmp; 45 49 } 46 50 47 int ComboBox::CurrentIndex(void) const 48 { 49 int tmp; 50 51 GetMutex(); 52 tmp=box_value; 53 ReleaseMutex(); 54 55 return tmp; 56 } 57 58 void ComboBox::XmlEvent(void) 59 { 60 GetMutex(); 61 if(GetPersistentXmlProp("value",box_value)) SetValueChanged(); 62 ReleaseMutex(); 51 void ComboBox::XmlEvent(void) { 52 GetMutex(); 53 if (GetPersistentXmlProp("value", box_value)) 54 SetValueChanged(); 55 ReleaseMutex(); 63 56 } 64 57 -
trunk/lib/FlairCore/src/ComboBox.h
r2 r15 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/lib/FlairCore/src/ConditionVariable.cpp
r2 r15 21 21 using std::string; 22 22 23 namespace flair { namespace core { 23 namespace flair { 24 namespace core { 24 25 25 ConditionVariable::ConditionVariable(const Object* parent,string name): Mutex(parent,name) { 26 pimpl_=new ConditionVariable_impl(this); 26 ConditionVariable::ConditionVariable(const Object *parent, string name) 27 : Mutex(parent, name) { 28 pimpl_ = new ConditionVariable_impl(this); 27 29 } 28 30 29 ConditionVariable::~ConditionVariable() { 30 delete pimpl_; 31 ConditionVariable::~ConditionVariable() { delete pimpl_; } 32 33 void ConditionVariable::CondWait(void) { pimpl_->CondWait(); } 34 35 bool ConditionVariable::CondWaitUntil(Time date) { 36 return pimpl_->CondWaitUntil(date); 31 37 } 32 38 33 void ConditionVariable::CondWait(void) { 34 pimpl_->CondWait(); 35 } 36 37 bool ConditionVariable::CondWaitUntil(Time date) { 38 return pimpl_->CondWaitUntil(date); 39 } 40 41 void ConditionVariable::CondSignal(void) { 42 pimpl_->CondSignal(); 43 } 39 void ConditionVariable::CondSignal(void) { pimpl_->CondSignal(); } 44 40 45 41 } // end namespace core -
trunk/lib/FlairCore/src/ConditionVariable.h
r2 r15 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/lib/FlairCore/src/ConditionVariable_impl.cpp
r2 r15 24 24 using namespace flair::core; 25 25 26 ConditionVariable_impl::ConditionVariable_impl(ConditionVariable *self) {27 this->self=self;28 26 ConditionVariable_impl::ConditionVariable_impl(ConditionVariable *self) { 27 this->self = self; 28 int status; 29 29 30 30 #ifdef __XENO__ 31 status=rt_cond_create(&m_ResumeCond,NULL);31 status = rt_cond_create(&m_ResumeCond, NULL); 32 32 #else 33 status=pthread_cond_init(&m_ResumeCond, 0);33 status = pthread_cond_init(&m_ResumeCond, 0); 34 34 #endif 35 if(status!=0) self->Err("error creating condition variable (%s)\n",strerror(-status)); 35 if (status != 0) 36 self->Err("error creating condition variable (%s)\n", strerror(-status)); 36 37 } 37 38 38 39 ConditionVariable_impl::~ConditionVariable_impl() { 39 40 int status; 40 41 41 42 #ifdef __XENO__ 42 status=rt_cond_delete(&m_ResumeCond);43 status = rt_cond_delete(&m_ResumeCond); 43 44 #else 44 status=pthread_cond_destroy(&m_ResumeCond);45 status = pthread_cond_destroy(&m_ResumeCond); 45 46 #endif 46 if(status!=0) self->Err("error destroying condition variable (%s)\n",strerror(-status)); 47 if (status != 0) 48 self->Err("error destroying condition variable (%s)\n", strerror(-status)); 47 49 } 48 50 49 51 void ConditionVariable_impl::CondWait(void) { 50 52 int status; 51 53 #ifdef __XENO__ 52 status=rt_cond_wait(&m_ResumeCond, &self->Mutex::pimpl_->mutex,TM_INFINITE); 54 status = 55 rt_cond_wait(&m_ResumeCond, &self->Mutex::pimpl_->mutex, TM_INFINITE); 53 56 #else 54 status=pthread_cond_wait(&m_ResumeCond, &self->Mutex::pimpl_->mutex);57 status = pthread_cond_wait(&m_ResumeCond, &self->Mutex::pimpl_->mutex); 55 58 #endif 56 if(status!=0) self->Err("error (%s)\n",strerror(-status)); 59 if (status != 0) 60 self->Err("error (%s)\n", strerror(-status)); 57 61 } 58 62 59 63 bool ConditionVariable_impl::CondWaitUntil(Time date) { 60 64 int status; 61 65 #ifdef __XENO__ 62 status=rt_cond_wait_until(&m_ResumeCond, &self->Mutex::pimpl_->mutex,date);66 status = rt_cond_wait_until(&m_ResumeCond, &self->Mutex::pimpl_->mutex, date); 63 67 #else 64 struct timespec restrict; 65 restrict.tv_sec=date/1000000000; 66 restrict.tv_nsec=date%1000000000; 67 status=pthread_cond_timedwait(&m_ResumeCond, &self->Mutex::pimpl_->mutex,&restrict); 68 struct timespec restrict; 69 restrict.tv_sec = date / 1000000000; 70 restrict.tv_nsec = date % 1000000000; 71 status = pthread_cond_timedwait(&m_ResumeCond, &self->Mutex::pimpl_->mutex, 72 &restrict); 68 73 #endif 69 if (status==0) return true; 70 if(status!=ETIMEDOUT) self->Err("error (%s)\n",strerror(-status)); 71 return false; 74 if (status == 0) 75 return true; 76 if (status != ETIMEDOUT) 77 self->Err("error (%s)\n", strerror(-status)); 78 return false; 72 79 } 73 80 74 81 void ConditionVariable_impl::CondSignal(void) { 75 82 int status; 76 83 #ifdef __XENO__ 77 status=rt_cond_signal(&m_ResumeCond);84 status = rt_cond_signal(&m_ResumeCond); 78 85 #else 79 status=pthread_cond_signal(&m_ResumeCond);86 status = pthread_cond_signal(&m_ResumeCond); 80 87 #endif 81 if(status!=0) self->Err("error (%s)\n",strerror(-status)); 88 if (status != 0) 89 self->Err("error (%s)\n", strerror(-status)); 82 90 } -
trunk/lib/FlairCore/src/ConnectedSocket.cpp
r2 r15 21 21 using std::string; 22 22 23 namespace flair 24 { 25 namespace core 26 { 23 namespace flair { 24 namespace core { 27 25 28 ConnectedSocket::ConnectedSocket(const Object* parent,const std::string name):Object(parent,name) {}; 26 ConnectedSocket::ConnectedSocket(const Object *parent, const std::string name) 27 : Object(parent, name){}; 29 28 30 ConnectedSocket::~ConnectedSocket() 29 ConnectedSocket::~ConnectedSocket(){}; 31 30 32 uint16_t ConnectedSocket::ReadUInt16(Time const& timeout) { 33 char buffer[sizeof(uint16_t)]; 34 size_t alreadyReceived=0; 35 Time remainingTimeout=timeout; //ms 36 do { 37 Time beforeTime=GetTime(); //ns 38 ssize_t received=RecvMessage(buffer+alreadyReceived,sizeof(uint16_t)-alreadyReceived,remainingTimeout); 39 remainingTimeout-=(GetTime()-beforeTime)/100000; 40 if ((received<0) || (remainingTimeout<0)) throw std::runtime_error("Timeout"); 41 alreadyReceived+=received; 42 } while (alreadyReceived!=sizeof(uint16_t)); 43 uint16_t *dataInNetworkEndianness=(uint16_t*)buffer; 44 uint16_t myinteger=NetworkToHost16(*dataInNetworkEndianness); 45 return myinteger; 31 uint16_t ConnectedSocket::ReadUInt16(Time const &timeout) { 32 char buffer[sizeof(uint16_t)]; 33 size_t alreadyReceived = 0; 34 Time remainingTimeout = timeout; // ms 35 do { 36 Time beforeTime = GetTime(); // ns 37 ssize_t received = 38 RecvMessage(buffer + alreadyReceived, 39 sizeof(uint16_t) - alreadyReceived, remainingTimeout); 40 remainingTimeout -= (GetTime() - beforeTime) / 100000; 41 if ((received < 0) || (remainingTimeout < 0)) 42 throw std::runtime_error("Timeout"); 43 alreadyReceived += received; 44 } while (alreadyReceived != sizeof(uint16_t)); 45 uint16_t *dataInNetworkEndianness = (uint16_t *)buffer; 46 uint16_t myinteger = NetworkToHost16(*dataInNetworkEndianness); 47 return myinteger; 46 48 } 47 49 48 void ConnectedSocket::WriteUInt16(uint16_t const& data,Time const& timeout) { 49 uint16_t dataInNetworkEndianness=HostToNetwork16(data); 50 char *buffer=(char *)&dataInNetworkEndianness; 51 size_t alreadySent=0; 52 Time remainingTimeout=timeout; //ms 53 do { 54 Time beforeTime=GetTime(); //ns 55 ssize_t sent=SendMessage(buffer+alreadySent,sizeof(uint16_t)-alreadySent,remainingTimeout); 56 remainingTimeout-=(GetTime()-beforeTime)/100000; 57 if ((sent<0) || (remainingTimeout<0)) throw std::runtime_error("Timeout"); 58 alreadySent+=sent; 59 } while (alreadySent!=sizeof(uint16_t)); 50 void ConnectedSocket::WriteUInt16(uint16_t const &data, Time const &timeout) { 51 uint16_t dataInNetworkEndianness = HostToNetwork16(data); 52 char *buffer = (char *)&dataInNetworkEndianness; 53 size_t alreadySent = 0; 54 Time remainingTimeout = timeout; // ms 55 do { 56 Time beforeTime = GetTime(); // ns 57 ssize_t sent = SendMessage( 58 buffer + alreadySent, sizeof(uint16_t) - alreadySent, remainingTimeout); 59 remainingTimeout -= (GetTime() - beforeTime) / 100000; 60 if ((sent < 0) || (remainingTimeout < 0)) 61 throw std::runtime_error("Timeout"); 62 alreadySent += sent; 63 } while (alreadySent != sizeof(uint16_t)); 60 64 } 61 65 62 uint32_t ConnectedSocket::ReadUInt32(Time const& timeout) { 63 char buffer[sizeof(uint32_t)]; 64 size_t alreadyReceived=0; 65 Time remainingTimeout=timeout; //ms 66 do { 67 Time beforeTime=GetTime(); //ns 68 ssize_t received=RecvMessage(buffer+alreadyReceived,sizeof(uint32_t)-alreadyReceived,remainingTimeout); 69 remainingTimeout-=(GetTime()-beforeTime)/100000; 70 if ((received<0) || (remainingTimeout<0)) throw std::runtime_error("Timeout"); 71 alreadyReceived+=received; 72 } while (alreadyReceived!=sizeof(uint32_t)); 73 uint32_t *dataInNetworkEndianness=(uint32_t*)buffer; 74 uint32_t myinteger=NetworkToHost32(*dataInNetworkEndianness); 75 return myinteger; 66 uint32_t ConnectedSocket::ReadUInt32(Time const &timeout) { 67 char buffer[sizeof(uint32_t)]; 68 size_t alreadyReceived = 0; 69 Time remainingTimeout = timeout; // ms 70 do { 71 Time beforeTime = GetTime(); // ns 72 ssize_t received = 73 RecvMessage(buffer + alreadyReceived, 74 sizeof(uint32_t) - alreadyReceived, remainingTimeout); 75 remainingTimeout -= (GetTime() - beforeTime) / 100000; 76 if ((received < 0) || (remainingTimeout < 0)) 77 throw std::runtime_error("Timeout"); 78 alreadyReceived += received; 79 } while (alreadyReceived != sizeof(uint32_t)); 80 uint32_t *dataInNetworkEndianness = (uint32_t *)buffer; 81 uint32_t myinteger = NetworkToHost32(*dataInNetworkEndianness); 82 return myinteger; 76 83 } 77 84 78 void ConnectedSocket::WriteUInt32(uint32_t const& data,Time const& timeout) { 79 uint32_t dataInNetworkEndianness=HostToNetwork32(data); 80 char *buffer=(char *)&dataInNetworkEndianness; 81 size_t alreadySent=0; 82 Time remainingTimeout=timeout; //ms 83 do { 84 Time beforeTime=GetTime(); //ns 85 ssize_t sent=SendMessage(buffer+alreadySent,sizeof(uint32_t)-alreadySent,remainingTimeout); 86 remainingTimeout-=(GetTime()-beforeTime)/100000; 87 if ((sent<0) || (remainingTimeout<0)) throw std::runtime_error("Timeout"); 88 alreadySent+=sent; 89 } while (alreadySent!=sizeof(uint32_t)); 85 void ConnectedSocket::WriteUInt32(uint32_t const &data, Time const &timeout) { 86 uint32_t dataInNetworkEndianness = HostToNetwork32(data); 87 char *buffer = (char *)&dataInNetworkEndianness; 88 size_t alreadySent = 0; 89 Time remainingTimeout = timeout; // ms 90 do { 91 Time beforeTime = GetTime(); // ns 92 ssize_t sent = SendMessage( 93 buffer + alreadySent, sizeof(uint32_t) - alreadySent, remainingTimeout); 94 remainingTimeout -= (GetTime() - beforeTime) / 100000; 95 if ((sent < 0) || (remainingTimeout < 0)) 96 throw std::runtime_error("Timeout"); 97 alreadySent += sent; 98 } while (alreadySent != sizeof(uint32_t)); 90 99 } 91 100 92 101 string ConnectedSocket::ReadString(const size_t &stringSize, Time timeout) { 93 char buffer[stringSize+1]; 94 size_t alreadyReceived=0; 95 Time remainingTimeout=timeout; //ms 96 do { 97 Time beforeTime=GetTime(); //ns 98 ssize_t received=RecvMessage(buffer+alreadyReceived,stringSize-alreadyReceived,remainingTimeout); 99 remainingTimeout-=(GetTime()-beforeTime)/100000; 100 if ((received<0) || (remainingTimeout<0)) throw std::runtime_error("Timeout"); 101 alreadyReceived+=received; 102 } while (alreadyReceived!=stringSize); 103 buffer[stringSize]='\0'; 102 char buffer[stringSize + 1]; 103 size_t alreadyReceived = 0; 104 Time remainingTimeout = timeout; // ms 105 do { 106 Time beforeTime = GetTime(); // ns 107 ssize_t received = 108 RecvMessage(buffer + alreadyReceived, stringSize - alreadyReceived, 109 remainingTimeout); 110 remainingTimeout -= (GetTime() - beforeTime) / 100000; 111 if ((received < 0) || (remainingTimeout < 0)) 112 throw std::runtime_error("Timeout"); 113 alreadyReceived += received; 114 } while (alreadyReceived != stringSize); 115 buffer[stringSize] = '\0'; 104 116 105 string mystring=buffer;106 117 string mystring = buffer; 118 return mystring; 107 119 } 108 120 -
trunk/lib/FlairCore/src/ConnectedSocket.h
r2 r15 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/lib/FlairCore/src/DataPlot.cpp
r2 r15 24 24 using std::string; 25 25 26 namespace flair 27 { 28 namespace gui 29 { 26 namespace flair { 27 namespace gui { 30 28 31 29 using namespace core; 32 30 33 void RGBFromColor(DataPlot::Color_t color,uint8_t &r,uint8_t &g,uint8_t &b) 34 { 35 switch(color) 36 { 37 case DataPlot::Red: 38 r=255; 39 g=0; 40 b=0; 41 break; 42 case DataPlot::Blue: 43 r=0; 44 g=0; 45 b=255; 46 break; 47 case DataPlot::Green: 48 r=0; 49 g=255; 50 b=0; 51 break; 52 case DataPlot::Yellow: 53 r=255; 54 g=255; 55 b=0; 56 break; 57 case DataPlot::Black: 58 r=0; 59 g=0; 60 b=0; 61 break; 62 case DataPlot::White: 63 r=255; 64 g=255; 65 b=255; 66 break; 67 } 31 void RGBFromColor(DataPlot::Color_t color, uint8_t &r, uint8_t &g, uint8_t &b) { 32 switch (color) { 33 case DataPlot::Red: 34 r = 255; 35 g = 0; 36 b = 0; 37 break; 38 case DataPlot::Blue: 39 r = 0; 40 g = 0; 41 b = 255; 42 break; 43 case DataPlot::Green: 44 r = 0; 45 g = 255; 46 b = 0; 47 break; 48 case DataPlot::Yellow: 49 r = 255; 50 g = 255; 51 b = 0; 52 break; 53 case DataPlot::Black: 54 r = 0; 55 g = 0; 56 b = 0; 57 break; 58 case DataPlot::White: 59 r = 255; 60 g = 255; 61 b = 255; 62 break; 63 } 68 64 } 69 65 70 DataPlot::DataPlot(const LayoutPosition * position,string name,string type):SendData(position,name,type)71 {72 pimpl_=new DataPlot_impl();66 DataPlot::DataPlot(const LayoutPosition *position, string name, string type) 67 : SendData(position, name, type) { 68 pimpl_ = new DataPlot_impl(); 73 69 } 74 70 75 DataPlot::~DataPlot() 76 { 77 delete pimpl_; 71 DataPlot::~DataPlot() { delete pimpl_; } 72 73 void DataPlot::AddDataToSend(const IODataElement *element) { 74 pimpl_->tosend.push_back(element); 75 76 SetSendSize(SendSize() + element->Size()); 78 77 } 79 78 80 void DataPlot::AddDataToSend(const IODataElement *element) 81 { 82 pimpl_->tosend.push_back(element); 79 void DataPlot::CopyDatas(char *buf) const { 80 int buf_size = 0; 83 81 84 SetSendSize(SendSize()+element->Size()); 85 } 86 87 void DataPlot::CopyDatas(char* buf) const { 88 int buf_size=0; 89 90 for(size_t i=0;i<pimpl_->tosend.size();i++) { 91 pimpl_->tosend[i]->CopyData(buf+buf_size); 92 buf_size+=pimpl_->tosend[i]->Size(); 93 } 82 for (size_t i = 0; i < pimpl_->tosend.size(); i++) { 83 pimpl_->tosend[i]->CopyData(buf + buf_size); 84 buf_size += pimpl_->tosend[i]->Size(); 85 } 94 86 } 95 87 -
trunk/lib/FlairCore/src/DataPlot.h
r2 r15 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/lib/FlairCore/src/DataPlot1D.cpp
r2 r15 23 23 using std::string; 24 24 25 namespace flair 26 { 27 namespace gui 28 { 25 namespace flair { 26 namespace gui { 29 27 30 28 using namespace core; 31 29 32 DataPlot1D::DataPlot1D(const LayoutPosition* position,string name,float ymin,float ymax):DataPlot(position,name,"DataPlot1D") 33 { 34 SetVolatileXmlProp("min",ymin); 35 SetVolatileXmlProp("max",ymax); 36 SendXml(); 30 DataPlot1D::DataPlot1D(const LayoutPosition *position, string name, float ymin, 31 float ymax) 32 : DataPlot(position, name, "DataPlot1D") { 33 SetVolatileXmlProp("min", ymin); 34 SetVolatileXmlProp("max", ymax); 35 SendXml(); 37 36 } 38 37 39 DataPlot1D::~DataPlot1D() { 38 DataPlot1D::~DataPlot1D() {} 39 40 void DataPlot1D::AddCurve(const core::IODataElement *element, uint8_t r, 41 uint8_t g, uint8_t b, string curve_name) { 42 if (curve_name != "") { 43 SetVolatileXmlProp("curve", curve_name); 44 } else { 45 SetVolatileXmlProp("curve", element->Parent()->ObjectName() + "\\" + 46 element->ObjectName()); 47 } 48 SetVolatileXmlProp("type", element->GetDataType().GetDescription()); 49 SetVolatileXmlProp("r", r); 50 SetVolatileXmlProp("g", g); 51 SetVolatileXmlProp("b", b); 52 53 SendXml(); 54 55 // save data information 56 AddDataToSend(element); 40 57 } 41 58 42 void DataPlot1D::AddCurve(const core::IODataElement* element,uint8_t r,uint8_t g,uint8_t b,string curve_name) 43 { 44 if(curve_name!="") 45 { 46 SetVolatileXmlProp("curve",curve_name); 47 } 48 else 49 { 50 SetVolatileXmlProp("curve",element->Parent()->ObjectName() + "\\" +element->ObjectName()); 51 } 52 SetVolatileXmlProp("type",element->GetDataType().GetDescription()); 53 SetVolatileXmlProp("r",r); 54 SetVolatileXmlProp("g",g); 55 SetVolatileXmlProp("b",b); 56 57 SendXml(); 58 59 //save data information 60 AddDataToSend(element); 61 } 62 63 void DataPlot1D::AddCurve(const core::IODataElement* element,Color_t color,string curve_name) { 64 uint8_t r,g,b; 65 RGBFromColor(color,r,g,b); 66 AddCurve(element,r,g,b,curve_name); 59 void DataPlot1D::AddCurve(const core::IODataElement *element, Color_t color, 60 string curve_name) { 61 uint8_t r, g, b; 62 RGBFromColor(color, r, g, b); 63 AddCurve(element, r, g, b, curve_name); 67 64 } 68 65 -
trunk/lib/FlairCore/src/DataPlot1D.h
r2 r15 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/lib/FlairCore/src/DataPlot2D.cpp
r2 r15 23 23 using std::string; 24 24 25 namespace flair { namespace gui { 25 namespace flair { 26 namespace gui { 26 27 27 DataPlot2D::DataPlot2D(const LayoutPosition* position,string name,string x_name,float xmin,float xmax,string y_name,float ymin,float ymax):DataPlot(position,name,"DataPlot2D") { 28 SetVolatileXmlProp("xmin",xmin); 29 SetVolatileXmlProp("xmax",xmax); 30 SetVolatileXmlProp("ymin",ymin); 31 SetVolatileXmlProp("ymax",ymax); 32 SetVolatileXmlProp("x_name",x_name); 33 SetVolatileXmlProp("y_name",y_name); 34 SendXml(); 28 DataPlot2D::DataPlot2D(const LayoutPosition *position, string name, 29 string x_name, float xmin, float xmax, string y_name, 30 float ymin, float ymax) 31 : DataPlot(position, name, "DataPlot2D") { 32 SetVolatileXmlProp("xmin", xmin); 33 SetVolatileXmlProp("xmax", xmax); 34 SetVolatileXmlProp("ymin", ymin); 35 SetVolatileXmlProp("ymax", ymax); 36 SetVolatileXmlProp("x_name", x_name); 37 SetVolatileXmlProp("y_name", y_name); 38 SendXml(); 35 39 } 36 40 37 41 DataPlot2D::~DataPlot2D() {} 38 42 39 void DataPlot2D::AddCurve(const core::IODataElement* x_element,const core::IODataElement* y_element,Color_t color,string curve_name) { 40 uint8_t r,g,b; 41 RGBFromColor(color,r,g,b); 42 AddCurve(x_element,y_element,r,g,b,curve_name); 43 void DataPlot2D::AddCurve(const core::IODataElement *x_element, 44 const core::IODataElement *y_element, Color_t color, 45 string curve_name) { 46 uint8_t r, g, b; 47 RGBFromColor(color, r, g, b); 48 AddCurve(x_element, y_element, r, g, b, curve_name); 43 49 } 44 50 45 void DataPlot2D::AddCurve(const core::IODataElement* x_element,const core::IODataElement* y_element,uint8_t r,uint8_t g,uint8_t b,string curve_name) { 46 if(typeid(x_element->GetDataType())!=typeid(y_element->GetDataType())) { 47 Err("x_element type is different from y_element type (%i-%i)\n",x_element->GetDataType().GetDescription().c_str(),y_element->GetDataType().GetDescription().c_str()); 48 //gerer erreur 49 return; 50 } 51 void DataPlot2D::AddCurve(const core::IODataElement *x_element, 52 const core::IODataElement *y_element, uint8_t r, 53 uint8_t g, uint8_t b, string curve_name) { 54 if (typeid(x_element->GetDataType()) != typeid(y_element->GetDataType())) { 55 Err("x_element type is different from y_element type (%i-%i)\n", 56 x_element->GetDataType().GetDescription().c_str(), 57 y_element->GetDataType().GetDescription().c_str()); 58 // gerer erreur 59 return; 60 } 51 61 52 if(curve_name!="") { 53 SetVolatileXmlProp("curve",curve_name); 54 } else { 55 SetVolatileXmlProp("curve",x_element->Parent()->ObjectName() + "\\" +x_element->ObjectName()+ "\\" +y_element->ObjectName()); 56 } 57 SetVolatileXmlProp("type",x_element->GetDataType().GetDescription()); 58 SetVolatileXmlProp("r",r); 59 SetVolatileXmlProp("g",g); 60 SetVolatileXmlProp("b",b); 62 if (curve_name != "") { 63 SetVolatileXmlProp("curve", curve_name); 64 } else { 65 SetVolatileXmlProp("curve", x_element->Parent()->ObjectName() + "\\" + 66 x_element->ObjectName() + "\\" + 67 y_element->ObjectName()); 68 } 69 SetVolatileXmlProp("type", x_element->GetDataType().GetDescription()); 70 SetVolatileXmlProp("r", r); 71 SetVolatileXmlProp("g", g); 72 SetVolatileXmlProp("b", b); 61 73 62 74 SendXml(); 63 75 64 //save data information65 66 76 // save data information 77 AddDataToSend(x_element); 78 AddDataToSend(y_element); 67 79 } 68 80 -
trunk/lib/FlairCore/src/DataPlot2D.h
r2 r15 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/lib/FlairCore/src/DataPlot_impl.cpp
r2 r15 18 18 #include "DataPlot_impl.h" 19 19 20 DataPlot_impl::DataPlot_impl() 21 { 22 } 20 DataPlot_impl::DataPlot_impl() {} 23 21 24 DataPlot_impl::~DataPlot_impl() 25 { 26 } 22 DataPlot_impl::~DataPlot_impl() {} -
trunk/lib/FlairCore/src/DoubleSpinBox.cpp
r2 r15 20 20 using std::string; 21 21 22 namespace flair 23 { 24 namespace gui 25 { 22 namespace flair { 23 namespace gui { 26 24 27 DoubleSpinBox::DoubleSpinBox(const LayoutPosition* position,string name,double min,double max,double step,int decimals,double default_value):Box(position,name,"DoubleSpinBox") 28 { 29 //update value from xml file 30 if(default_value<min) default_value=min; 31 if(default_value>max) default_value=max; 32 box_value=default_value; 25 DoubleSpinBox::DoubleSpinBox(const LayoutPosition *position, string name, 26 double min, double max, double step, int decimals, 27 double default_value) 28 : Box(position, name, "DoubleSpinBox") { 29 // update value from xml file 30 if (default_value < min) 31 default_value = min; 32 if (default_value > max) 33 default_value = max; 34 box_value = default_value; 33 35 34 SetVolatileXmlProp("min",min);35 SetVolatileXmlProp("max",max);36 SetVolatileXmlProp("step",step);37 SetVolatileXmlProp("decimals",decimals);38 GetPersistentXmlProp("value",box_value);39 SetPersistentXmlProp("value",box_value);36 SetVolatileXmlProp("min", min); 37 SetVolatileXmlProp("max", max); 38 SetVolatileXmlProp("step", step); 39 SetVolatileXmlProp("decimals", decimals); 40 GetPersistentXmlProp("value", box_value); 41 SetPersistentXmlProp("value", box_value); 40 42 41 43 SendXml(); 42 44 } 43 45 44 DoubleSpinBox::DoubleSpinBox(const LayoutPosition* position,string name,string suffix,double min,double max,double step,int decimals,double default_value):Box(position,name,"DoubleSpinBox") 45 { 46 //update value from xml file 47 if(default_value<min) default_value=min; 48 if(default_value>max) default_value=max; 49 box_value=default_value; 46 DoubleSpinBox::DoubleSpinBox(const LayoutPosition *position, string name, 47 string suffix, double min, double max, double step, 48 int decimals, double default_value) 49 : Box(position, name, "DoubleSpinBox") { 50 // update value from xml file 51 if (default_value < min) 52 default_value = min; 53 if (default_value > max) 54 default_value = max; 55 box_value = default_value; 50 56 51 SetVolatileXmlProp("suffix",suffix);52 SetVolatileXmlProp("min",min);53 SetVolatileXmlProp("max",max);54 SetVolatileXmlProp("step",step);55 SetVolatileXmlProp("decimals",decimals);56 GetPersistentXmlProp("value",box_value);57 SetPersistentXmlProp("value",box_value);57 SetVolatileXmlProp("suffix", suffix); 58 SetVolatileXmlProp("min", min); 59 SetVolatileXmlProp("max", max); 60 SetVolatileXmlProp("step", step); 61 SetVolatileXmlProp("decimals", decimals); 62 GetPersistentXmlProp("value", box_value); 63 SetPersistentXmlProp("value", box_value); 58 64 59 65 SendXml(); 60 66 } 61 67 62 DoubleSpinBox::~DoubleSpinBox() 63 { 68 DoubleSpinBox::~DoubleSpinBox() {} 64 69 70 double DoubleSpinBox::Value(void) const { 71 double tmp; 72 73 GetMutex(); 74 tmp = box_value; 75 ReleaseMutex(); 76 77 return tmp; 65 78 } 66 79 67 double DoubleSpinBox::Value(void) const 68 { 69 double tmp; 70 71 GetMutex(); 72 tmp=box_value; 73 ReleaseMutex(); 74 75 return tmp; 76 } 77 78 void DoubleSpinBox::XmlEvent(void) 79 { 80 GetMutex(); 81 if(GetPersistentXmlProp("value",box_value)) SetValueChanged(); 82 ReleaseMutex(); 80 void DoubleSpinBox::XmlEvent(void) { 81 GetMutex(); 82 if (GetPersistentXmlProp("value", box_value)) 83 SetValueChanged(); 84 ReleaseMutex(); 83 85 } 84 86 -
trunk/lib/FlairCore/src/DoubleSpinBox.h
r2 r15 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/lib/FlairCore/src/Euler.cpp
r2 r15 23 23 #define PI_D ((double)3.14159265358979323846) 24 24 25 namespace flair 26 { 27 namespace core 28 { 25 namespace flair { 26 namespace core { 29 27 30 Euler::Euler(float inRoll, float inPitch,float inYaw): roll(inRoll), pitch(inPitch),yaw(inYaw) {31 }28 Euler::Euler(float inRoll, float inPitch, float inYaw) 29 : roll(inRoll), pitch(inPitch), yaw(inYaw) {} 32 30 33 Euler::~Euler() { 31 Euler::~Euler() {} 34 32 35 } 36 37 Euler& Euler::operator=(const Euler &euler) { 38 roll=euler.roll; 39 pitch=euler.pitch; 40 yaw=euler.yaw; 41 return (*this); 33 Euler &Euler::operator=(const Euler &euler) { 34 roll = euler.roll; 35 pitch = euler.pitch; 36 yaw = euler.yaw; 37 return (*this); 42 38 } 43 39 /* … … 85 81 */ 86 82 void Euler::ToQuaternion(Quaternion &quaternion) const { 87 quaternion.q0=cos(yaw/2)*cos(pitch/2)*cos(roll/2)88 +sin(yaw/2)*sin(pitch/2)*sin(roll/2);83 quaternion.q0 = cos(yaw / 2) * cos(pitch / 2) * cos(roll / 2) + 84 sin(yaw / 2) * sin(pitch / 2) * sin(roll / 2); 89 85 90 quaternion.q1=cos(yaw/2)*cos(pitch/2)*sin(roll/2)91 -sin(yaw/2)*sin(pitch/2)*cos(roll/2);86 quaternion.q1 = cos(yaw / 2) * cos(pitch / 2) * sin(roll / 2) - 87 sin(yaw / 2) * sin(pitch / 2) * cos(roll / 2); 92 88 93 quaternion.q2=cos(yaw/2)*sin(pitch/2)*cos(roll/2)94 +sin(yaw/2)*cos(pitch/2)*sin(roll/2);89 quaternion.q2 = cos(yaw / 2) * sin(pitch / 2) * cos(roll / 2) + 90 sin(yaw / 2) * cos(pitch / 2) * sin(roll / 2); 95 91 96 quaternion.q3=sin(yaw/2)*cos(pitch/2)*cos(roll/2)97 -cos(yaw/2)*sin(pitch/2)*sin(roll/2);92 quaternion.q3 = sin(yaw / 2) * cos(pitch / 2) * cos(roll / 2) - 93 cos(yaw / 2) * sin(pitch / 2) * sin(roll / 2); 98 94 } 99 95 100 96 Quaternion Euler::ToQuaternion(void) const { 101 102 103 97 Quaternion quaternion; 98 ToQuaternion(quaternion); 99 return quaternion; 104 100 } 105 101 106 float Euler::ToDegree(float radianValue) { 107 return radianValue*180.0f/PI; 108 } 102 float Euler::ToDegree(float radianValue) { return radianValue * 180.0f / PI; } 109 103 110 float Euler::ToRadian(float degreeValue) { 111 return degreeValue/180.0f*PI; 112 } 104 float Euler::ToRadian(float degreeValue) { return degreeValue / 180.0f * PI; } 113 105 114 106 float Euler::YawDistanceFrom(float angle) const { 115 float rot1,rot2; 116 if(angle > yaw ) { 117 rot1=angle-yaw; 118 rot2=2*PI-angle+yaw; 119 } else { 120 rot1=2*PI+angle-yaw; 121 rot2=yaw-angle; 122 } 123 if(rot2<rot1) rot1=-rot2; 124 rot1=-rot1;//pour avoir rot1=yaw-angle 107 float rot1, rot2; 108 if (angle > yaw) { 109 rot1 = angle - yaw; 110 rot2 = 2 * PI - angle + yaw; 111 } else { 112 rot1 = 2 * PI + angle - yaw; 113 rot2 = yaw - angle; 114 } 115 if (rot2 < rot1) 116 rot1 = -rot2; 117 rot1 = -rot1; // pour avoir rot1=yaw-angle 125 118 126 119 return rot1; 127 120 } 128 121 -
trunk/lib/FlairCore/src/Euler.h
r2 r15 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/lib/FlairCore/src/FrameworkManager.cpp
r2 r15 26 26 using namespace flair::gui; 27 27 28 namespace 29 { 30 flair::core::FrameworkManager* frameworkmanager=NULL; 28 namespace { 29 flair::core::FrameworkManager *frameworkmanager = NULL; 31 30 } 32 31 32 namespace flair { 33 namespace core { 33 34 34 namespace flair 35 { 36 namespace core 37 { 35 FrameworkManager *getFrameworkManager(void) { return frameworkmanager; } 38 36 37 bool IsBigEndian(void) { 38 union { 39 uint32_t i; 40 char c[4]; 41 } bint = {0x01020304}; 39 42 40 FrameworkManager* getFrameworkManager(void) { 41 return frameworkmanager; 43 if (bint.c[0] == 1) { 44 return true; 45 } else { 46 return false; 47 } 42 48 } 43 49 44 bool IsBigEndian(void) { 45 union { 46 uint32_t i; 47 char c[4]; 48 } bint = {0x01020304}; 50 FrameworkManager::FrameworkManager(string name) 51 : Object(NULL, name, XML_ROOT_TYPE) { 52 if (frameworkmanager != NULL) { 53 Err("FrameworkManager should be instanced only one time\n"); 54 return; 55 } 49 56 50 if(bint.c[0] == 1) { 51 return true; 52 } else { 53 return false; 54 } 55 } 56 57 FrameworkManager::FrameworkManager(string name): Object(NULL,name,XML_ROOT_TYPE) 58 { 59 if(frameworkmanager!=NULL) { 60 Err("FrameworkManager should be instanced only one time\n"); 61 return; 62 } 63 64 Printf(SVN_REV); 65 frameworkmanager=this; 66 pimpl_=new FrameworkManager_impl(this,name); 57 Printf(SVN_REV); 58 frameworkmanager = this; 59 pimpl_ = new FrameworkManager_impl(this, name); 67 60 } 68 61 69 62 FrameworkManager::~FrameworkManager() { 70 //Printf("destruction FrameworkManager\n");63 // Printf("destruction FrameworkManager\n"); 71 64 72 //stop ui_com thread (which sends datas for graphs), we do not need it as graphs will be destroyed 73 if(getUiCom()!=NULL) { 74 getUiCom()->SafeStop(); 75 getUiCom()->Join(); 65 // stop ui_com thread (which sends datas for graphs), we do not need it as 66 // graphs will be destroyed 67 if (getUiCom() != NULL) { 68 getUiCom()->SafeStop(); 69 getUiCom()->Join(); 70 } 71 72 // we start by deleting threads (except pimpl which must be deleted at last) 73 // (before deleting objects that could be used by the threads) 74 // Printf("delete Threads\n"); 75 for (vector<const Object *>::iterator it = Childs()->begin(); 76 it < Childs()->end(); it++) { 77 // Printf("child %i %s 78 // %s\n",Childs()->size(),(*it)->ObjectName().c_str(),(*it)->ObjectType().c_str()); 79 if ((*it)->ObjectType() == "Thread") { 80 if (*it != pimpl_) { 81 // Printf("del\n"); 82 delete (Thread *)(*it); 83 // Childs() vector has been modified, we start from beginning again 84 // it will be incremented by the loop, so in fact we start again at 85 // begin()+1 86 // it is not a problem since begin is pimpl 87 it = Childs()->begin(); 88 // Printf("del ok\n"); 89 } 76 90 } 91 } 77 92 78 //we start by deleting threads (except pimpl which must be deleted at last) 79 // (before deleting objects that could be used by the threads) 80 //Printf("delete Threads\n"); 81 for(vector<const Object*>::iterator it=Childs()->begin() ; it < Childs()->end(); it++ ) { 82 //Printf("child %i %s %s\n",Childs()->size(),(*it)->ObjectName().c_str(),(*it)->ObjectType().c_str()); 83 if((*it)->ObjectType()=="Thread") { 84 if(*it!=pimpl_) { 85 //Printf("del\n"); 86 delete (Thread*)(*it); 87 //Childs() vector has been modified, we start from beginning again 88 //it will be incremented by the loop, so in fact we start again at begin()+1 89 //it is not a problem since begin is pimpl 90 it=Childs()->begin(); 91 //Printf("del ok\n"); 92 } 93 } 93 // next we delete IODevice 94 // (before deleting objects that could be used by the IODevice) 95 // Printf("delete IODevices\n"); 96 for (vector<const Object *>::iterator it = Childs()->begin(); 97 it < Childs()->end(); it++) { 98 // Printf("child %i %s 99 // %s\n",Childs()->size(),(*it)->ObjectName().c_str(),(*it)->ObjectType().c_str()); 100 if ((*it)->ObjectType() == "IODevice") { 101 // Printf("del\n"); 102 delete (IODevice *)*it; 103 // Printf("del ok\n"); 104 // Childs() vector has been modified, we start from beginning again 105 // it will be incremented by the loop, so in fact we start again at 106 // begin()+1 107 // it is not a problem since begin is pimpl (not an IODevice) 108 it = Childs()->begin(); 109 // Printf("del ok\n"); 94 110 } 111 } 95 112 96 //next we delete IODevice 97 // (before deleting objects that could be used by the IODevice) 98 //Printf("delete IODevices\n"); 99 for(vector<const Object*>::iterator it=Childs()->begin() ; it < Childs()->end(); it++ ) { 100 //Printf("child %i %s %s\n",Childs()->size(),(*it)->ObjectName().c_str(),(*it)->ObjectType().c_str()); 101 if((*it)->ObjectType()=="IODevice") { 102 //Printf("del\n"); 103 delete (IODevice*)*it; 104 //Printf("del ok\n"); 105 //Childs() vector has been modified, we start from beginning again 106 //it will be incremented by the loop, so in fact we start again at begin()+1 107 //it is not a problem since begin is pimpl (not an IODevice) 108 it=Childs()->begin(); 109 //Printf("del ok\n"); 110 } 111 } 113 // Printf("delete childs\n"); 114 // on efface les enfants en commencant par la fin 115 // le ui_com puis FrameworkManager_impl est détruit en dernier 116 // permet de garder l'uicom pour notifer des destructions 117 while (Childs()->size() != 0) { 118 // Printf("child %i %s 119 // %s\n",Childs()->size(),Childs()->back()->ObjectName().c_str(),Childs()->back()->ObjectType().c_str()); 120 if (Childs()->back() != NULL) 121 delete Childs()->back(); 122 } 112 123 113 //Printf("delete childs\n"); 114 //on efface les enfants en commencant par la fin 115 //le ui_com puis FrameworkManager_impl est détruit en dernier 116 //permet de garder l'uicom pour notifer des destructions 117 while(Childs()->size()!=0) { 118 //Printf("child %i %s %s\n",Childs()->size(),Childs()->back()->ObjectName().c_str(),Childs()->back()->ObjectType().c_str()); 119 if(Childs()->back()!=NULL) delete Childs()->back(); 120 } 124 // childs.clear(); 121 125 122 //childs.clear(); 123 124 //Printf("destruction FrameworkManager ok\n"); 126 // Printf("destruction FrameworkManager ok\n"); 125 127 } 126 128 127 void FrameworkManager::SetupConnection(string address,uint16_t port,size_t rcv_buf_size) { 128 pimpl_->SetupConnection(address,port,rcv_buf_size); 129 void FrameworkManager::SetupConnection(string address, uint16_t port, 130 size_t rcv_buf_size) { 131 pimpl_->SetupConnection(address, port, rcv_buf_size); 129 132 } 130 133 131 134 void FrameworkManager::SetupUserInterface(string xml_file) { 132 135 pimpl_->SetupUserInterface(xml_file); 133 136 } 134 137 135 gui::TabWidget *FrameworkManager::GetTabWidget(void) const {136 138 gui::TabWidget *FrameworkManager::GetTabWidget(void) const { 139 return pimpl_->tabwidget; 137 140 } 138 141 139 142 void FrameworkManager::UpdateSendData(const SendData *obj) { 140 if(getUiCom()!=NULL) getUiCom()->UpdateSendData(obj); 143 if (getUiCom() != NULL) 144 getUiCom()->UpdateSendData(obj); 141 145 } 142 146 143 147 void FrameworkManager::BlockCom(void) { 144 if(getUiCom()!=NULL) getUiCom()->Block(); 148 if (getUiCom() != NULL) 149 getUiCom()->Block(); 145 150 } 146 151 147 152 void FrameworkManager::UnBlockCom(void) { 148 if(getUiCom()!=NULL) getUiCom()->UnBlock(); 153 if (getUiCom() != NULL) 154 getUiCom()->UnBlock(); 149 155 } 150 156 151 157 bool FrameworkManager::ConnectionLost(void) const { 152 if(getUiCom()!=NULL) {153 return (getUiCom()->ConnectionLost()| pimpl_->connection_lost);154 155 156 158 if (getUiCom() != NULL) { 159 return (getUiCom()->ConnectionLost() | pimpl_->connection_lost); 160 } else { 161 return false; 162 } 157 163 } 158 164 159 165 void FrameworkManager::SetupLogger(string log_path) { 160 166 pimpl_->SetupLogger(log_path); 161 167 } 162 168 163 169 void FrameworkManager::AddDeviceToLog(IODevice *device) { 164 170 pimpl_->AddDeviceToLog(device); 165 171 } 166 172 167 void FrameworkManager::StartLog(void) { 168 pimpl_->StartLog(); 169 } 173 void FrameworkManager::StartLog(void) { pimpl_->StartLog(); } 170 174 171 void FrameworkManager::StopLog(void) { 172 pimpl_->StopLog(); 173 } 175 void FrameworkManager::StopLog(void) { pimpl_->StopLog(); } 174 176 175 bool FrameworkManager::IsLogging(void) const { 176 return pimpl_->is_logging; 177 } 177 bool FrameworkManager::IsLogging(void) const { return pimpl_->is_logging; } 178 178 179 179 void FrameworkManager::DisableErrorsDisplay(bool value) { 180 pimpl_->disable_errors=value;180 pimpl_->disable_errors = value; 181 181 } 182 182 183 183 bool FrameworkManager::IsDisplayingErrors(void) const { 184 184 return !(pimpl_->disable_errors); 185 185 } 186 186 -
trunk/lib/FlairCore/src/FrameworkManager.h
r2 r15 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/lib/FlairCore/src/FrameworkManager_impl.cpp
r2 r15 43 43 using namespace flair::gui; 44 44 45 ui_com * FrameworkManager_impl::com=NULL;46 FrameworkManager_impl * FrameworkManager_impl::_this=NULL;45 ui_com *FrameworkManager_impl::com = NULL; 46 FrameworkManager_impl *FrameworkManager_impl::_this = NULL; 47 47 48 48 namespace { … … 50 50 51 51 #ifdef SIGDEBUG 52 static const char *reason_str[] = { 53 "undefined", 54 "received signal", 55 "invoked syscall", 56 "triggered fault", 57 "affected by priority inversion", 58 "missing mlockall", 59 "runaway thread", 60 }; 61 62 void warn_upon_switch(int sig, siginfo_t *si, void *context) { 63 unsigned int reason = si->si_value.sival_int; 64 void *bt[32]; 65 int nentries; 52 static const char *reason_str[] = { 53 "undefined", "received signal", "invoked syscall", "triggered fault", 54 "affected by priority inversion", "missing mlockall", "runaway thread", 55 }; 56 57 void warn_upon_switch(int sig, siginfo_t *si, void *context) { 58 unsigned int reason = si->si_value.sival_int; 59 void *bt[32]; 60 int nentries; 66 61 #ifdef SIGDEBUG_WATCHDOG 67 68 69 #endif 70 71 nentries = backtrace(bt,sizeof(bt) / sizeof(bt[0]));72 backtrace_symbols_fd(bt,nentries,fileno(stdout));73 74 #else //SIGDEBUG75 76 77 78 79 80 81 nentries = backtrace(bt,sizeof(bt) / sizeof(bt[0]));82 backtrace_symbols_fd(bt,nentries,fileno(stdout));83 84 #endif // SIGDEBUG62 printf("\nSIGDEBUG received, reason %d: %s\n", reason, 63 reason <= SIGDEBUG_WATCHDOG ? reason_str[reason] : "<unknown>"); 64 #endif 65 // Dump a backtrace of the frame which caused the switch to secondary mode: 66 nentries = backtrace(bt, sizeof(bt) / sizeof(bt[0])); 67 backtrace_symbols_fd(bt, nentries, fileno(stdout)); 68 } 69 #else // SIGDEBUG 70 void warn_upon_switch(int sig __attribute__((unused))) { 71 void *bt[32]; 72 int nentries; 73 74 /* Dump a backtrace of the frame which caused the switch to 75 secondary mode: */ 76 nentries = backtrace(bt, sizeof(bt) / sizeof(bt[0])); 77 backtrace_symbols_fd(bt, nentries, fileno(stdout)); 78 } 79 #endif // SIGDEBUG 85 80 #endif //__XENO__ 86 void seg_fault(int sig __attribute__((unused))) { 87 void *bt[32]; 88 int nentries; 89 90 printf("Segmentation fault:\n"); 91 /* Dump a backtrace of the frame which caused the segfault: */ 92 nentries = backtrace(bt,sizeof(bt) / sizeof(bt[0])); 93 backtrace_symbols_fd(bt,nentries,fileno(stdout)); 94 95 exit(1); 96 } 97 } 98 99 FrameworkManager_impl::FrameworkManager_impl(FrameworkManager *self,string name): Thread(self,"FrameworkManager",FRAMEWORK_TASK_PRIORITY) { 100 this->self=self; 101 is_logging=false; 102 logger_defined=false; 103 disable_errors=false; 104 ui_defined=false; 105 rcv_buf=NULL; 106 _this=this; 107 108 // Avoids memory swapping for this program 109 mlockall(MCL_CURRENT|MCL_FUTURE); 110 struct sigaction sa; 111 112 //catch segfault 113 signal(SIGSEGV, seg_fault); 114 115 //catch primary->secondary switch 81 void seg_fault(int sig __attribute__((unused))) { 82 void *bt[32]; 83 int nentries; 84 85 printf("Segmentation fault:\n"); 86 /* Dump a backtrace of the frame which caused the segfault: */ 87 nentries = backtrace(bt, sizeof(bt) / sizeof(bt[0])); 88 backtrace_symbols_fd(bt, nentries, fileno(stdout)); 89 90 exit(1); 91 } 92 } 93 94 FrameworkManager_impl::FrameworkManager_impl(FrameworkManager *self, 95 string name) 96 : Thread(self, "FrameworkManager", FRAMEWORK_TASK_PRIORITY) { 97 this->self = self; 98 is_logging = false; 99 logger_defined = false; 100 disable_errors = false; 101 ui_defined = false; 102 rcv_buf = NULL; 103 _this = this; 104 105 // Avoids memory swapping for this program 106 mlockall(MCL_CURRENT | MCL_FUTURE); 107 struct sigaction sa; 108 109 // catch segfault 110 signal(SIGSEGV, seg_fault); 111 112 // catch primary->secondary switch 116 113 #ifdef __XENO__ 117 114 #ifdef SIGDEBUG 118 119 120 121 122 #else 123 124 #endif 125 126 string task_name="Framework_"+name;127 int status=rt_task_shadow(NULL,task_name.c_str(),10,0);128 if(status!=0) {129 self->Err("rt_task_shadow error (%s)\n",strerror(-status));130 115 sigemptyset(&sa.sa_mask); 116 sa.sa_sigaction = warn_upon_switch; 117 sa.sa_flags = SA_SIGINFO; 118 sigaction(SIGDEBUG, &sa, NULL); 119 #else 120 signal(SIGXCPU, warn_upon_switch); 121 #endif 122 123 string task_name = "Framework_" + name; 124 int status = rt_task_shadow(NULL, task_name.c_str(), 10, 0); 125 if (status != 0) { 126 self->Err("rt_task_shadow error (%s)\n", strerror(-status)); 127 } 131 128 132 129 #endif //__XENO__ … … 134 131 135 132 void FrameworkManager_impl::ConnectionLost(void) { 136 137 138 connection_lost=true;133 Err("connection lost\n"); 134 gcs_watchdog->SafeStop(); 135 connection_lost = true; 139 136 } 140 137 141 138 FrameworkManager_impl::~FrameworkManager_impl() { 142 //Printf("destruction FrameworkManager_impl\n"); 143 int status; 144 145 SafeStop(); 146 Join(); 147 148 if(rcv_buf!=NULL) free(rcv_buf); 149 150 if(logger_defined==true) { 151 continuer=false; 152 (void)pthread_join(log_th,NULL); 153 154 status=DeletePipe(&cmd_pipe); 155 if(status!=0) { 156 Err("Error deleting pipe (%s)\n",strerror(-status)); 139 // Printf("destruction FrameworkManager_impl\n"); 140 int status; 141 142 SafeStop(); 143 Join(); 144 145 if (rcv_buf != NULL) 146 free(rcv_buf); 147 148 if (logger_defined == true) { 149 continuer = false; 150 (void)pthread_join(log_th, NULL); 151 152 status = DeletePipe(&cmd_pipe); 153 if (status != 0) { 154 Err("Error deleting pipe (%s)\n", strerror(-status)); 155 } 156 status = DeletePipe(&data_pipe); 157 if (status != 0) { 158 Err("Error deleting pipe (%s)\n", strerror(-status)); 159 } 160 161 #ifdef __XENO__ 162 status = rt_heap_delete(&log_heap); 163 if (status != 0) { 164 Err("rt_heap_delete error (%s)\n", strerror(-status)); 165 } 166 #endif 167 168 logs.clear(); 169 } 170 171 if (file_doc != NULL) 172 xmlFreeDoc(file_doc); 173 174 if (ui_defined) 175 delete top_layout; 176 177 if (com != NULL) { 178 delete com; 179 status = UDT::close(com_sock); 180 if (status != 0) 181 printf("Error udt::close %s", UDT::getlasterror().getErrorMessage()); 182 183 status = UDT::close(file_sock); 184 if (status != 0) 185 printf("Error udt::close %s", UDT::getlasterror().getErrorMessage()); 186 187 SleepMS(200); // a revoir, sinon UDT::cleanup bloque en RT 188 UDT::cleanup(); 189 } 190 191 // Printf("destruction FrameworkManager_impl ok\n"); 192 } 193 194 void FrameworkManager_impl::SetupConnection(string address, uint16_t port, 195 size_t rcv_buf_size) { 196 UDT::startup(); 197 this->rcv_buf_size = rcv_buf_size; 198 199 // socket file_socket, doit être créé en premier, cf station sol 200 Printf("Connecting to %s:%i\n", address.c_str(), port); 201 file_sock = GetSocket(address, port); 202 com_sock = GetSocket(address, port); 203 204 // receive buffer allocation 205 rcv_buf = (char *)malloc(rcv_buf_size); 206 if (rcv_buf == NULL) { 207 Err("receive buffer malloc error\n"); 208 } 209 210 com = new ui_com(this, com_sock); 211 212 // file managment 213 bool blocking = true; 214 UDT::setsockopt(file_sock, 0, UDT_SNDSYN, &blocking, sizeof(bool)); 215 UDT::setsockopt(file_sock, 0, UDT_RCVSYN, &blocking, sizeof(bool)); 216 217 // configure timeout of blocking receive, short timeout to have priority on 218 // the other socket (see run method) 219 int timeout = 1; // ms 220 UDT::setsockopt(file_sock, 0, UDT_RCVTIMEO, &timeout, sizeof(int)); 221 222 timeout = 100; // ms 223 UDT::setsockopt(com_sock, 0, UDT_RCVTIMEO, &timeout, sizeof(int)); 224 225 Start(); 226 227 // watchdog for connection with ground station 228 connection_lost = false; 229 gcs_watchdog = new Watchdog( 230 this, std::bind(&FrameworkManager_impl::ConnectionLost, this), 231 (Time)1000000000); 232 gcs_watchdog->Start(); 233 } 234 235 void FrameworkManager_impl::SetupUserInterface(string xml_file) { 236 ui_defined = true; 237 this->xml_file = xml_file; 238 239 // top_layout=new Layout(NULL,XML_ROOT_ELEMENT,XML_ROOT_TYPE); 240 top_layout = new Layout(NULL, self->ObjectName(), XML_ROOT_TYPE); 241 242 // xml setup of the main widget 243 if (xml_file != "") { 244 xmlNodePtr *file_node = &(((Widget *)(top_layout))->pimpl_->file_node); 245 file_doc = xmlParseFile(xml_file.c_str()); 246 if (file_doc == NULL) { 247 self->Warn("XML document not parsed successfully. Creating a new one.\n"); 248 file_doc = xmlNewDoc((xmlChar *)"1.0"); 249 *file_node = xmlNewNode(NULL, (xmlChar *)XML_ROOT_TYPE); 250 xmlSetProp(*file_node, (xmlChar *)"name", 251 (xmlChar *)ObjectName().c_str()); 252 xmlDocSetRootElement(file_doc, *file_node); 253 // PrintXml(); 254 } else { 255 *file_node = xmlDocGetRootElement(file_doc); 256 if (xmlStrcmp((*file_node)->name, (xmlChar *)XML_ROOT_TYPE)) { 257 self->Warn("%s, no match found in xml file\n", XML_ROOT_TYPE); 258 *file_node = xmlNewNode(NULL, (xmlChar *)XML_ROOT_TYPE); 259 xmlSetProp(*file_node, (xmlChar *)"name", 260 (xmlChar *)ObjectName().c_str()); 261 xmlDocSetRootElement(file_doc, *file_node); 262 } 263 } 264 } else { 265 self->Err("xml file not defined\n"); 266 } 267 268 // gui 269 tabwidget = 270 new TabWidget(top_layout->At(0, 0), XML_MAIN_TABWIDGET, TabWidget::North); 271 save_button = 272 new PushButton(top_layout->At(1, 0), 273 "save config on target (" + self->ObjectName() + ")"); 274 // load_button=new PushButton(top_layout->At(1,1),"load config on target (" + 275 // self->ObjectName() + ")"); 276 } 277 278 // in case of RT, this thread switches to secondary mode when calling 279 // com->Receive 280 // it switches back to RT in ProcessXML when mutex are locked 281 void FrameworkManager_impl::Run(void) { 282 while (!ToBeStopped()) { 283 ssize_t bytesRead; 284 285 bytesRead = com->Receive(rcv_buf, rcv_buf_size); 286 287 if (bytesRead == (ssize_t)rcv_buf_size) 288 Err("FrameworkManager max receive size, augmenter le buffer size!\n"); 289 290 if (bytesRead > 0) { 291 // printf("recu %ld, trame %x\n",bytesRead,(uint8_t)rcv_buf[0]); 292 // rcv_buf[bytesRead-1]=0;//pour affichage 293 // printf("%s\n",rcv_buf); 294 295 switch ((uint8_t)rcv_buf[0]) { 296 case XML_HEADER: { 297 xmlDoc *doc; 298 rcv_buf[bytesRead] = 0; 299 300 doc = xmlReadMemory(rcv_buf, (int)bytesRead, "include.xml", 301 "ISO-8859-1", 0); 302 xmlNode *cur_node = NULL; 303 304 for (cur_node = xmlDocGetRootElement(doc); cur_node; 305 cur_node = cur_node->next) { 306 if (cur_node->type == XML_ELEMENT_NODE) { 307 if (!xmlStrcmp(cur_node->name, (xmlChar *)XML_ROOT_TYPE)) { 308 #ifdef __XENO__ 309 WarnUponSwitches( 310 true); // ProcessXML should not switch to secondary mode 311 #endif 312 top_layout->Widget::pimpl_->ProcessXML(cur_node->children); 313 #ifdef __XENO__ 314 WarnUponSwitches(false); // other parts of this thread can switch 315 // to secondary mode 316 #endif 317 break; 318 } 319 } 157 320 } 158 status=DeletePipe(&data_pipe); 159 if(status!=0) { 160 Err("Error deleting pipe (%s)\n",strerror(-status)); 321 322 xmlFreeDoc(doc); 323 324 if (save_button->Clicked()) 325 SaveXml(); 326 327 SaveXmlChange(rcv_buf); 328 329 break; 330 } 331 case WATCHDOG_HEADER: { 332 gcs_watchdog->Touch(); 333 break; 334 } 335 default: 336 Err("unknown id: %x\n", (uint8_t)rcv_buf[0]); 337 break; 338 } 339 } else { 340 if (com->ConnectionLost()) 341 SleepMS(10); // avoid infinite loop in this case 342 } 343 } 344 } 345 346 void FrameworkManager_impl::SaveXml(void) { 347 if (ui_defined) 348 xmlSaveFormatFile(xml_file.c_str(), file_doc, 1); 349 } 350 351 void FrameworkManager_impl::SaveXmlChange(char *buf) { 352 if (is_logging == true) { 353 FILE *xml_change; 354 char filename[256]; 355 Time time = GetTime(); 356 357 sprintf(filename, "%s/changes_at_%lld.xml", log_path.c_str(), time); 358 359 xml_change = fopen(filename, "a"); 360 fprintf(xml_change, "%s", buf); 361 fclose(xml_change); 362 363 sprintf(filename, "changes_at_%lld.xml", time); 364 xml_changes.push_back(filename); 365 } 366 } 367 368 void FrameworkManager_impl::SendFile(string path, string name) { 369 char *buf, *more_buf; 370 int size; 371 filebuf *pbuf; 372 ssize_t nb_write; 373 string filename = path + "/" + name; 374 375 // open the file 376 fstream ifs(filename.c_str(), ios::in | ios::binary); 377 ifs.seekg(0, ios::end); 378 size = ifs.tellg(); 379 ifs.seekg(0, ios::beg); 380 pbuf = ifs.rdbuf(); 381 382 if (size <= 0) { 383 Err("error opening file %s\n", filename.c_str()); 384 return; 385 } 386 387 buf = (char *)malloc(sizeof(uint8_t) + sizeof(int) + name.size()); 388 if (buf == NULL) { 389 Err("malloc error, not sending file\n"); 390 return; 391 } 392 393 if (IsBigEndian()) { 394 buf[0] = FILE_INFO_BIG_ENDIAN; 395 } else { 396 buf[0] = FILE_INFO_LITTLE_ENDIAN; 397 } 398 399 memcpy(buf + 1, &size, sizeof(int)); 400 memcpy(buf + 1 + sizeof(int), name.c_str(), name.size()); 401 Printf("sending %s, size: %i\n", filename.c_str(), size); 402 // send file information 403 UDT::sendmsg(file_sock, buf, sizeof(uint8_t) + sizeof(int) + name.size(), -1, 404 true); 405 406 more_buf = (char *)realloc((void *)buf, size); 407 if (more_buf == NULL) { 408 Err("realloc error, not sending file\n"); 409 free(buf); 410 return; 411 } else { 412 buf = more_buf; 413 } 414 415 pbuf->sgetn(buf, size); 416 // send the file 417 nb_write = UDT::sendmsg(file_sock, buf, size, -1, true); 418 419 if (nb_write < 0) { 420 Err("UDT::sendmsg error (%s)\n", UDT::getlasterror().getErrorMessage()); 421 } else if (nb_write != size) { 422 Err("UDT::sendmsg error, sent %ld/%i\n", nb_write, size); 423 } 424 425 ifs.close(); 426 free(buf); 427 } 428 429 void FrameworkManager_impl::FinishSending() { 430 char rm_cmd[256]; 431 432 // send orignal xml 433 SendFile(log_path, "setup.xml"); 434 sprintf(rm_cmd, "rm %s/setup.xml", log_path.c_str()); 435 system(rm_cmd); 436 437 // send xml changes 438 for (size_t i = 0; i < xml_changes.size(); i++) { 439 // Printf("%s\n",xml_changes.at(i).c_str()); 440 SendFile(log_path, xml_changes.at(i).c_str()); 441 sprintf(rm_cmd, "rm %s/%s", log_path.c_str(), xml_changes.at(i).c_str()); 442 system(rm_cmd); 443 } 444 xml_changes.clear(); 445 446 // end notify 447 char buf = END; 448 int nb_write = UDT::sendmsg(file_sock, &buf, 1, -1, true); 449 450 if (nb_write < 0) { 451 Err("UDT::sendmsg error (%s)\n", UDT::getlasterror().getErrorMessage()); 452 } else if (nb_write != 1) { 453 Err("UDT::sendmsg error, sent %i/%i\n", nb_write, 1); 454 } 455 } 456 457 UDTSOCKET FrameworkManager_impl::GetSocket(string address, uint16_t port) { 458 while (1) { 459 UDTSOCKET new_fd; 460 new_fd = UDT::socket(AF_INET, SOCK_DGRAM, 0); 461 if (new_fd == UDT::INVALID_SOCK) { 462 Err("socket error: %s\n", UDT::getlasterror().getErrorMessage()); 463 return 0; 464 } 465 466 sockaddr_in serv_addr; 467 serv_addr.sin_family = AF_INET; 468 serv_addr.sin_port = htons(short(port)); 469 470 if (inet_pton(AF_INET, address.c_str(), &serv_addr.sin_addr) <= 0) { 471 Err("incorrect network address\n"); 472 return 0; 473 } 474 475 memset(&(serv_addr.sin_zero), '\0', 8); 476 477 if (UDT::ERROR == 478 UDT::connect(new_fd, (sockaddr *)&serv_addr, sizeof(serv_addr))) { 479 // Printf("connect error: %s 480 // %i\n",UDT::getlasterror().getErrorMessage(),UDT::getlasterror().getErrorCode()); 481 UDT::close(new_fd); 482 if (UDT::getlasterror().getErrorCode() != 1001 && 483 UDT::getlasterror().getErrorCode() != 1002) { 484 Err("connect error: %s\n", UDT::getlasterror().getErrorMessage()); 485 return 0; 486 } 487 } else { 488 // printf("connected to 489 // %s:%i\n",inet_ntoa(serv_addr.sin_addr),serv_addr.sin_port); 490 return new_fd; 491 } 492 } 493 } 494 495 #ifdef __XENO__ 496 int FrameworkManager_impl::CreatePipe(RT_PIPE *fd, string name) { 497 name = self->ObjectName() + "-" + name; 498 // xenomai limitation 499 if (name.size() > 31) 500 self->Err("rt_pipe_create error (%s is too long)\n", name.c_str()); 501 // start log writter 502 #ifdef RT_PIPE_SIZE 503 return rt_pipe_create(fd, name.c_str(), P_MINOR_AUTO, RT_PIPE_SIZE); 504 #else 505 return rt_pipe_create(fd, name.c_str(), P_MINOR_AUTO, 0); 506 #endif 507 } 508 #else 509 int FrameworkManager_impl::CreatePipe(int (*fd)[2], string name) { 510 // if(pipe2(fd[0],O_NONBLOCK) == -1) 511 if (pipe(fd[0]) == -1) { 512 return errno; 513 } else { 514 int attr = fcntl((*fd)[0], F_GETFL, 0); 515 if (attr == -1) { 516 return errno; 517 } 518 if (fcntl((*fd)[0], F_SETFL, attr | O_NONBLOCK) == -1) { 519 return errno; 520 } 521 attr = fcntl((*fd)[1], F_GETFL, 0); 522 if (attr == -1) { 523 return errno; 524 } 525 if (fcntl((*fd)[1], F_SETFL, attr | O_NONBLOCK) == -1) { 526 return errno; 527 } 528 529 return 0; 530 } 531 } 532 #endif 533 534 #ifdef __XENO__ 535 int FrameworkManager_impl::DeletePipe(RT_PIPE *fd) { 536 return rt_pipe_delete(fd); 537 } 538 #else 539 int FrameworkManager_impl::DeletePipe(int (*fd)[2]) { 540 int status1 = close((*fd)[0]); 541 int status2 = close((*fd)[1]); 542 if (status1 == 0 && status2 == 0) 543 return 0; 544 if (status1 != 0) 545 return status1; 546 if (status2 != 0) 547 return status2; 548 } 549 #endif 550 551 void FrameworkManager_impl::SetupLogger(string log_path) { 552 if (logger_defined == true) { 553 Warn("SetupLogger() was already called.\n"); 554 return; 555 } 556 557 this->log_path = log_path; 558 559 int status = CreatePipe(&cmd_pipe, "log_cmd"); 560 if (status != 0) { 561 Err("Error creating pipe (%s)\n", strerror(-status)); 562 return; 563 } 564 565 status = CreatePipe(&data_pipe, "log_data"); 566 if (status != 0) { 567 Err("Error creating pipe (%s)\n", strerror(-status)); 568 return; 569 } 570 571 #ifdef __XENO__ 572 string tmp_name; 573 tmp_name = self->ObjectName() + "-log_heap"; 574 status = rt_heap_create(&log_heap, tmp_name.c_str(), LOG_HEAP, H_FIFO); 575 if (status != 0) { 576 Err("rt_heap_create error (%s)\n", strerror(-status)); 577 return; 578 } 579 #endif //__XENO__ 580 581 continuer = true; 582 583 #ifdef NRT_STACK_SIZE 584 // Initialize thread creation attributes 585 pthread_attr_t attr; 586 if (pthread_attr_init(&attr) != 0) { 587 Err("pthread_attr_init error\n"); 588 return; 589 } 590 591 if (pthread_attr_setstacksize(&attr, NRT_STACK_SIZE) != 0) { 592 Err("pthread_attr_setstacksize error\n"); 593 return; 594 } 595 596 if (pthread_create(&log_th, &attr, write_log_user, (void *)this) < 0) 597 #else 598 if (pthread_create(&log_th, NULL, write_log_user, (void *)this) < 0) 599 #endif 600 { 601 Err("pthread_create error\n"); 602 return; 603 } 604 #ifdef NRT_STACK_SIZE 605 if (pthread_attr_destroy(&attr) != 0) { 606 Err("pthread_attr_destroy error\n"); 607 return; 608 } 609 #endif 610 611 logger_defined = true; 612 } 613 614 void FrameworkManager_impl::AddDeviceToLog(IODevice *device) { 615 if (logger_defined == false) { 616 Err("SetupLogger() was not called, not starting log\n"); 617 return; 618 } 619 620 if (is_logging == false) { 621 if (device->pimpl_->SetToBeLogged()) { 622 log_desc_t tmp; 623 tmp.device = device; 624 logs.push_back(tmp); 625 } else { 626 Warn("not adding it twice\n"); 627 } 628 } else { 629 Err("impossible while logging\n"); 630 } 631 } 632 633 void FrameworkManager_impl::StartLog(void) { 634 if (logger_defined == false) { 635 Err("SetupLogger() was not called, not starting log\n"); 636 return; 637 } 638 639 ssize_t written; 640 size_t nb_err = 0; 641 642 if (logs.size() == 0) { 643 Warn("Not starting log: nothing to log!\n"); 644 return; 645 } 646 647 if (is_logging == false) { 648 for (size_t i = 0; i < logs.size(); i++) { 649 650 logs.at(i).running = true; 651 logs.at(i).dbtFile = NULL; 652 logs.at(i).size = logs.at(i).device->pimpl_->LogSize(); 653 #ifdef __XENO__ 654 written = 655 rt_pipe_write(&cmd_pipe, &logs.at(i), sizeof(log_desc_t), P_NORMAL); 656 #else 657 written = write(cmd_pipe[1], &logs.at(i), sizeof(log_desc_t)); 658 #endif 659 660 if (written < 0) { 661 Err("write pipe error (%s)\n", strerror(-written)); 662 nb_err++; 663 logs.at(i).running = false; 664 } else if (written != sizeof(log_desc_t)) { 665 Err("write pipe error %ld/%ld\n", written, sizeof(log_desc_t)); 666 nb_err++; 667 logs.at(i).running = false; 668 } 669 } 670 671 if (nb_err != logs.size()) 672 is_logging = true; 673 } else { 674 Warn("Already logging\n"); 675 } 676 } 677 678 void FrameworkManager_impl::StopLog(void) { 679 ssize_t written; 680 681 if (is_logging == true) { 682 for (size_t i = 0; i < logs.size(); i++) { 683 logs.at(i).running = false; 684 } 685 // send only one running false condition, user thread will stop and send all 686 #ifdef __XENO__ 687 written = 688 rt_pipe_write(&cmd_pipe, &logs.at(0), sizeof(log_desc_t), P_NORMAL); 689 #else 690 written = write(cmd_pipe[1], &logs.at(0), sizeof(log_desc_t)); 691 #endif 692 693 if (written < 0) { 694 Err("write pipe error (%s)\n", strerror(-written)); 695 return; 696 } else if (written != sizeof(log_desc_t)) { 697 Err("write pipe error %ld/%ld\n", written, sizeof(log_desc_t)); 698 return; 699 } 700 701 is_logging = false; 702 } else { 703 Warn("Not logging\n"); 704 } 705 } 706 707 char *FrameworkManager_impl::GetBuffer(size_t sz) { 708 // Printf("alloc %i\n",sz); 709 #ifdef __XENO__ 710 void *ptr; 711 int status = rt_heap_alloc(&log_heap, sz, TM_NONBLOCK, &ptr); 712 if (status != 0) { 713 Err("rt_heap_alloc error (%s)\n", strerror(-status)); 714 ptr = NULL; 715 } 716 return (char *)ptr; 717 #else 718 return (char *)malloc(sz); 719 #endif 720 } 721 722 void FrameworkManager_impl::ReleaseBuffer(char *buf) { 723 #ifdef __XENO__ 724 int status = rt_heap_free(&log_heap, buf); 725 726 if (status != 0) { 727 Err("rt_heap_free error (%s)\n", strerror(-status)); 728 } 729 #else 730 free(buf); 731 #endif 732 } 733 734 void FrameworkManager_impl::WriteLog(const char *buf, size_t size) { 735 ssize_t written; 736 737 #ifdef __XENO__ 738 written = rt_pipe_write(&data_pipe, buf, size, P_NORMAL); 739 #else 740 written = write(data_pipe[1], buf, size); 741 #endif 742 743 if (written < 0) { 744 Err("erreur write pipe (%s)\n", strerror(-written)); 745 } else if (written != (ssize_t)size) { 746 Err("erreur write pipe %ld/%ld\n", written, size); 747 } 748 } 749 750 void *FrameworkManager_impl::write_log_user(void *arg) { 751 int cmd_pipe = -1; 752 int data_pipe = -1; 753 string filename; 754 fd_set set; 755 struct timeval timeout; 756 FrameworkManager_impl *caller = (FrameworkManager_impl *)arg; 757 int rv; 758 759 vector<log_desc_t> logs; 760 761 #ifdef __XENO__ 762 filename = NRT_PIPE_PATH + caller->self->ObjectName() + "-log_cmd"; 763 while (cmd_pipe < 0) { 764 cmd_pipe = open(filename.c_str(), O_RDWR); 765 if (cmd_pipe < 0 && errno != ENOENT) 766 caller->self->Err("open rt_pipe error: %s %i\n", filename.c_str(), errno); 767 usleep(1000); 768 } 769 filename = NRT_PIPE_PATH + caller->self->ObjectName() + "-log_data"; 770 while (data_pipe < 0) { 771 data_pipe = open(filename.c_str(), O_RDWR); 772 if (data_pipe < 0 && errno != ENOENT) 773 caller->self->Err("open rt_pipe error: %s %i\n", filename.c_str(), errno); 774 usleep(1000); 775 } 776 #else 777 cmd_pipe = caller->cmd_pipe[0]; 778 data_pipe = caller->data_pipe[0]; 779 #endif 780 781 while (caller->continuer == true) { 782 FD_ZERO(&set); 783 FD_SET(cmd_pipe, &set); 784 FD_SET(data_pipe, &set); 785 786 timeout.tv_sec = 0; 787 timeout.tv_usec = SELECT_TIMEOUT_MS * 1000; 788 rv = select(FD_SETSIZE, &set, NULL, NULL, &timeout); 789 790 if (rv == -1) { 791 caller->Err("select error\n"); // an error accured 792 } else if (rv == 0) { 793 // printf("timeout write_log_user %s\n",caller->ObjectName().c_str()); // 794 // a timeout occured 795 } else { 796 if (FD_ISSET(cmd_pipe, &set)) { 797 log_desc_t tmp; 798 read(cmd_pipe, &tmp, sizeof(log_desc_t)); 799 800 if (tmp.running == true) // start logging 801 { 802 filename = 803 caller->log_path + "/" + caller->FileName(tmp.device) + ".dbt"; 804 printf("Creating log file %s (log size %i)\n", filename.c_str(), 805 (int)tmp.size); 806 tmp.dbtFile = inithdFile((char *)filename.c_str(), UAV, tmp.size); 807 logs.push_back(tmp); 808 809 if (logs.size() == 1) { 810 filename = caller->log_path + "/setup.xml"; 811 xmlSaveFile(filename.c_str(), caller->file_doc); 812 } 813 } else // stop logging 814 { 815 for (size_t i = 0; i < logs.size(); i++) { 816 if (logs.at(i).dbtFile != NULL) { 817 close_hdfile(logs.at(i).dbtFile); 818 819 filename = caller->FileName(logs.at(i).device) + ".dbt"; 820 caller->SendFile(caller->log_path, filename); 821 822 fstream txt_file; 823 filename = caller->FileName(logs.at(i).device) + ".txt"; 824 txt_file.open((caller->log_path + "/" + filename).c_str(), 825 fstream::out); 826 txt_file << "1: time (us)\n2: time (ns)\n"; 827 int index = 3; 828 logs.at(i).device->pimpl_->WriteLogsDescriptors(txt_file, &index); 829 txt_file.close(); 830 831 caller->SendFile(caller->log_path, filename); 832 } 833 } 834 // a revoir celui ci est le xml enregistré et pas forcement l'actuel 835 // if(caller->xml_file!="") caller->SendFile(caller->xml_file); 836 caller->FinishSending(); 837 838 logs.clear(); 161 839 } 162 163 #ifdef __XENO__ 164 status=rt_heap_delete(&log_heap); 165 if(status!=0) { 166 Err("rt_heap_delete error (%s)\n",strerror(-status)); 840 } 841 842 if (FD_ISSET(data_pipe, &set)) { 843 log_header_t header; 844 read(data_pipe, &header, sizeof(log_header_t)); 845 846 for (size_t i = 0; i < logs.size(); i++) { 847 if (logs.at(i).device == header.device) { 848 char *buf = (char *)malloc(header.size); 849 read(data_pipe, buf, header.size); 850 // printf("%s \n",header.device->ObjectName().c_str()); 851 // for(int i=0;i<header.size;i++) printf("%x ",buf[i]); 852 // printf("\n"); 853 if (logs.at(i).size == header.size) { 854 if (logs.at(i).dbtFile != NULL) { 855 write_hdfile( 856 logs.at(i).dbtFile, buf, (road_time_t)(header.time / 1000), 857 (road_timerange_t)(header.time % 1000), header.size); 858 } else { 859 printf("err\n"); 860 } 861 } else { 862 caller->self->Err("%s log size is not correct %i/%i\n", 863 header.device->ObjectName().c_str(), 864 header.size, logs.at(i).size); 865 } 866 free(buf); 867 } 167 868 } 168 #endif 169 170 logs.clear(); 171 } 172 173 if(file_doc!=NULL) xmlFreeDoc(file_doc); 174 175 if(ui_defined) delete top_layout; 176 177 if(com!=NULL) { 178 delete com; 179 status=UDT::close(com_sock); 180 if(status!=0) printf("Error udt::close %s",UDT::getlasterror().getErrorMessage()); 181 182 status=UDT::close(file_sock); 183 if(status!=0) printf("Error udt::close %s",UDT::getlasterror().getErrorMessage()); 184 185 SleepMS(200);//a revoir, sinon UDT::cleanup bloque en RT 186 UDT::cleanup(); 187 } 188 189 //Printf("destruction FrameworkManager_impl ok\n"); 190 } 191 192 193 void FrameworkManager_impl::SetupConnection(string address,uint16_t port,size_t rcv_buf_size) { 194 UDT::startup(); 195 this->rcv_buf_size=rcv_buf_size; 196 197 //socket file_socket, doit être créé en premier, cf station sol 198 Printf("Connecting to %s:%i\n",address.c_str(),port); 199 file_sock=GetSocket(address,port); 200 com_sock=GetSocket(address,port); 201 202 //receive buffer allocation 203 rcv_buf=(char*)malloc(rcv_buf_size); 204 if(rcv_buf==NULL) { 205 Err("receive buffer malloc error\n"); 206 } 207 208 com=new ui_com(this,com_sock); 209 210 //file managment 211 bool blocking = true; 212 UDT::setsockopt(file_sock, 0, UDT_SNDSYN, &blocking, sizeof(bool)); 213 UDT::setsockopt(file_sock, 0, UDT_RCVSYN, &blocking, sizeof(bool)); 214 215 //configure timeout of blocking receive, short timeout to have priority on the other socket (see run method) 216 int timeout=1;//ms 217 UDT::setsockopt(file_sock, 0, UDT_RCVTIMEO, &timeout, sizeof(int)); 218 219 timeout=100;//ms 220 UDT::setsockopt(com_sock, 0, UDT_RCVTIMEO, &timeout, sizeof(int)); 221 222 Start(); 223 224 //watchdog for connection with ground station 225 connection_lost=false; 226 gcs_watchdog=new Watchdog(this,std::bind(&FrameworkManager_impl::ConnectionLost,this),(Time)1000000000); 227 gcs_watchdog->Start(); 228 } 229 230 void FrameworkManager_impl::SetupUserInterface(string xml_file) { 231 ui_defined=true; 232 this->xml_file=xml_file; 233 234 //top_layout=new Layout(NULL,XML_ROOT_ELEMENT,XML_ROOT_TYPE); 235 top_layout=new Layout(NULL,self->ObjectName(),XML_ROOT_TYPE); 236 237 //xml setup of the main widget 238 if(xml_file!="") { 239 xmlNodePtr* file_node=&(((Widget*)(top_layout))->pimpl_->file_node); 240 file_doc = xmlParseFile(xml_file.c_str()); 241 if (file_doc == NULL ) { 242 self->Warn("XML document not parsed successfully. Creating a new one.\n"); 243 file_doc = xmlNewDoc((xmlChar*)"1.0"); 244 *file_node=xmlNewNode(NULL, (xmlChar*)XML_ROOT_TYPE); 245 xmlSetProp(*file_node,(xmlChar*)"name",(xmlChar*)ObjectName().c_str()); 246 xmlDocSetRootElement(file_doc, *file_node); 247 //PrintXml(); 248 } else { 249 *file_node=xmlDocGetRootElement(file_doc); 250 if(xmlStrcmp((*file_node)->name,(xmlChar*)XML_ROOT_TYPE)) { 251 self->Warn("%s, no match found in xml file\n",XML_ROOT_TYPE); 252 *file_node=xmlNewNode(NULL, (xmlChar*)XML_ROOT_TYPE); 253 xmlSetProp(*file_node,(xmlChar*)"name",(xmlChar*)ObjectName().c_str()); 254 xmlDocSetRootElement(file_doc, *file_node); 255 } 256 } 257 } else { 258 self->Err("xml file not defined\n"); 259 } 260 261 //gui 262 tabwidget=new TabWidget(top_layout->At(0,0),XML_MAIN_TABWIDGET,TabWidget::North); 263 save_button=new PushButton(top_layout->At(1,0),"save config on target (" + self->ObjectName() + ")"); 264 //load_button=new PushButton(top_layout->At(1,1),"load config on target (" + self->ObjectName() + ")"); 265 } 266 267 //in case of RT, this thread switches to secondary mode when calling com->Receive 268 //it switches back to RT in ProcessXML when mutex are locked 269 void FrameworkManager_impl::Run(void) 270 { 271 while(!ToBeStopped()) 272 { 273 ssize_t bytesRead; 274 275 bytesRead=com->Receive(rcv_buf,rcv_buf_size); 276 277 if(bytesRead==(ssize_t)rcv_buf_size) Err("FrameworkManager max receive size, augmenter le buffer size!\n"); 278 279 if(bytesRead>0) 280 { 281 //printf("recu %ld, trame %x\n",bytesRead,(uint8_t)rcv_buf[0]); 282 //rcv_buf[bytesRead-1]=0;//pour affichage 283 //printf("%s\n",rcv_buf); 284 285 switch((uint8_t)rcv_buf[0]) 286 { 287 case XML_HEADER: 288 { 289 xmlDoc *doc; 290 rcv_buf[bytesRead]=0; 291 292 doc = xmlReadMemory(rcv_buf, (int)bytesRead, "include.xml", "ISO-8859-1", 0); 293 xmlNode *cur_node = NULL; 294 295 for (cur_node = xmlDocGetRootElement(doc); cur_node; cur_node = cur_node->next) 296 { 297 if (cur_node->type == XML_ELEMENT_NODE) 298 { 299 if(!xmlStrcmp(cur_node->name,(xmlChar*)XML_ROOT_TYPE) ) 300 { 301 #ifdef __XENO__ 302 WarnUponSwitches(true);//ProcessXML should not switch to secondary mode 303 #endif 304 top_layout->Widget::pimpl_->ProcessXML(cur_node->children); 305 #ifdef __XENO__ 306 WarnUponSwitches(false);//other parts of this thread can switch to secondary mode 307 #endif 308 break; 309 } 310 } 311 } 312 313 xmlFreeDoc(doc); 314 315 if(save_button->Clicked()) SaveXml(); 316 317 SaveXmlChange(rcv_buf); 318 319 break; 320 } 321 case WATCHDOG_HEADER: { 322 gcs_watchdog->Touch(); 323 break; 324 } 325 default: 326 Err("unknown id: %x\n",(uint8_t)rcv_buf[0]); 327 break; 328 } 329 } else { 330 if(com->ConnectionLost()) SleepMS(10);//avoid infinite loop in this case 331 } 332 } 333 } 334 335 void FrameworkManager_impl::SaveXml(void) 336 { 337 if(ui_defined) xmlSaveFormatFile(xml_file.c_str(),file_doc,1); 338 } 339 340 void FrameworkManager_impl::SaveXmlChange(char* buf) 341 { 342 if(is_logging==true) 343 { 344 FILE *xml_change; 345 char filename[256]; 346 Time time=GetTime(); 347 348 sprintf(filename,"%s/changes_at_%lld.xml",log_path.c_str(),time); 349 350 xml_change=fopen(filename,"a"); 351 fprintf(xml_change,"%s",buf); 352 fclose(xml_change); 353 354 sprintf(filename,"changes_at_%lld.xml",time); 355 xml_changes.push_back(filename); 356 } 357 } 358 359 void FrameworkManager_impl::SendFile(string path,string name) 360 { 361 char *buf,*more_buf; 362 int size; 363 filebuf *pbuf; 364 ssize_t nb_write; 365 string filename=path+ "/" +name; 366 367 // open the file 368 fstream ifs(filename.c_str(), ios::in | ios::binary); 369 ifs.seekg(0, ios::end); 370 size = ifs.tellg(); 371 ifs.seekg(0, ios::beg); 372 pbuf=ifs.rdbuf(); 373 374 if(size<=0) 375 { 376 Err("error opening file %s\n",filename.c_str()); 377 return; 378 } 379 380 buf=(char*)malloc(sizeof(uint8_t)+sizeof(int)+name.size()); 381 if(buf==NULL) 382 { 383 Err("malloc error, not sending file\n"); 384 return; 385 } 386 387 if(IsBigEndian()) 388 { 389 buf[0]=FILE_INFO_BIG_ENDIAN; 390 } 391 else 392 { 393 buf[0]=FILE_INFO_LITTLE_ENDIAN; 394 } 395 396 memcpy(buf+1,&size,sizeof(int)); 397 memcpy(buf+1+sizeof(int),name.c_str(),name.size()); 398 Printf("sending %s, size: %i\n",filename.c_str(),size); 399 // send file information 400 UDT::sendmsg(file_sock, buf, sizeof(uint8_t)+sizeof(int)+name.size(), -1,true); 401 402 more_buf=(char*)realloc((void*)buf,size); 403 if(more_buf==NULL) 404 { 405 Err("realloc error, not sending file\n"); 406 free(buf); 407 return; 408 } 409 else 410 { 411 buf=more_buf; 412 } 413 414 pbuf->sgetn (buf,size); 415 // send the file 416 nb_write=UDT::sendmsg(file_sock, buf, size,-1,true); 417 418 if(nb_write<0) 419 { 420 Err("UDT::sendmsg error (%s)\n",UDT::getlasterror().getErrorMessage()); 421 } 422 else if (nb_write != size) 423 { 424 Err("UDT::sendmsg error, sent %ld/%i\n",nb_write,size); 425 } 426 427 ifs.close(); 428 free(buf); 429 } 430 431 void FrameworkManager_impl::FinishSending() 432 { 433 char rm_cmd[256]; 434 435 //send orignal xml 436 SendFile(log_path,"setup.xml"); 437 sprintf(rm_cmd,"rm %s/setup.xml",log_path.c_str()); 438 system(rm_cmd); 439 440 //send xml changes 441 for(size_t i=0;i<xml_changes.size();i++) 442 { 443 //Printf("%s\n",xml_changes.at(i).c_str()); 444 SendFile(log_path,xml_changes.at(i).c_str()); 445 sprintf(rm_cmd,"rm %s/%s",log_path.c_str(),xml_changes.at(i).c_str()); 446 system(rm_cmd); 447 } 448 xml_changes.clear(); 449 450 //end notify 451 char buf=END; 452 int nb_write=UDT::sendmsg(file_sock, &buf, 1,-1,true); 453 454 if(nb_write<0) 455 { 456 Err("UDT::sendmsg error (%s)\n",UDT::getlasterror().getErrorMessage()); 457 } 458 else if (nb_write != 1) 459 { 460 Err("UDT::sendmsg error, sent %i/%i\n",nb_write,1); 461 } 462 } 463 464 UDTSOCKET FrameworkManager_impl::GetSocket(string address,uint16_t port) { 465 while(1) { 466 UDTSOCKET new_fd; 467 new_fd = UDT::socket(AF_INET, SOCK_DGRAM, 0); 468 if(new_fd==UDT::INVALID_SOCK) { 469 Err("socket error: %s\n",UDT::getlasterror().getErrorMessage()); 470 return 0; 471 } 472 473 sockaddr_in serv_addr; 474 serv_addr.sin_family = AF_INET; 475 serv_addr.sin_port = htons(short(port)); 476 477 if (inet_pton(AF_INET,address.c_str(), &serv_addr.sin_addr) <= 0) { 478 Err("incorrect network address\n"); 479 return 0; 480 } 481 482 memset(&(serv_addr.sin_zero), '\0', 8); 483 484 if (UDT::ERROR == UDT::connect(new_fd, (sockaddr*)&serv_addr, sizeof(serv_addr))) { 485 //Printf("connect error: %s %i\n",UDT::getlasterror().getErrorMessage(),UDT::getlasterror().getErrorCode()); 486 UDT::close(new_fd); 487 if(UDT::getlasterror().getErrorCode()!=1001 && UDT::getlasterror().getErrorCode()!=1002) { 488 Err("connect error: %s\n",UDT::getlasterror().getErrorMessage()); 489 return 0; 490 } 491 } else { 492 //printf("connected to %s:%i\n",inet_ntoa(serv_addr.sin_addr),serv_addr.sin_port); 493 return new_fd; 494 } 495 } 496 } 497 498 #ifdef __XENO__ 499 int FrameworkManager_impl::CreatePipe(RT_PIPE* fd,string name) 500 { 501 name=self->ObjectName()+ "-" + name; 502 //xenomai limitation 503 if(name.size()>31) self->Err("rt_pipe_create error (%s is too long)\n",name.c_str()); 504 //start log writter 505 #ifdef RT_PIPE_SIZE 506 return rt_pipe_create(fd, name.c_str(), P_MINOR_AUTO,RT_PIPE_SIZE); 507 #else 508 return rt_pipe_create(fd, name.c_str(), P_MINOR_AUTO,0); 509 #endif 510 } 511 #else 512 int FrameworkManager_impl::CreatePipe(int (*fd)[2],string name) 513 { 514 //if(pipe2(fd[0],O_NONBLOCK) == -1) 515 if(pipe(fd[0]) == -1) 516 { 517 return errno; 518 } 519 else 520 { 521 int attr=fcntl((*fd)[0], F_GETFL,0); 522 if(attr == -1) 523 { 524 return errno; 525 } 526 if(fcntl((*fd)[0], F_SETFL, attr|O_NONBLOCK)== -1) 527 { 528 return errno; 529 } 530 attr=fcntl((*fd)[1], F_GETFL,0); 531 if(attr == -1) 532 { 533 return errno; 534 } 535 if(fcntl((*fd)[1], F_SETFL, attr|O_NONBLOCK)== -1) 536 { 537 return errno; 538 } 539 540 return 0; 541 } 542 } 543 #endif 544 545 #ifdef __XENO__ 546 int FrameworkManager_impl::DeletePipe(RT_PIPE* fd) 547 { 548 return rt_pipe_delete(fd); 549 } 550 #else 551 int FrameworkManager_impl::DeletePipe(int (*fd)[2]) 552 { 553 int status1=close((*fd)[0]); 554 int status2=close((*fd)[1]); 555 if(status1==0 && status2==0) return 0; 556 if(status1!=0) return status1; 557 if(status2!=0) return status2; 558 } 559 #endif 560 561 void FrameworkManager_impl::SetupLogger(string log_path) { 562 if(logger_defined==true) { 563 Warn("SetupLogger() was already called.\n"); 564 return; 565 } 566 567 this->log_path=log_path; 568 569 int status=CreatePipe(&cmd_pipe,"log_cmd"); 570 if(status!=0) { 571 Err("Error creating pipe (%s)\n",strerror(-status)); 572 return; 573 } 574 575 status=CreatePipe(&data_pipe,"log_data"); 576 if(status!=0) { 577 Err("Error creating pipe (%s)\n",strerror(-status)); 578 return; 579 } 580 581 #ifdef __XENO__ 582 string tmp_name; 583 tmp_name=self->ObjectName() + "-log_heap"; 584 status=rt_heap_create(&log_heap,tmp_name.c_str(),LOG_HEAP,H_FIFO); 585 if(status!=0) { 586 Err("rt_heap_create error (%s)\n",strerror(-status)); 587 return; 588 } 589 #endif //__XENO__ 590 591 continuer=true; 592 593 #ifdef NRT_STACK_SIZE 594 // Initialize thread creation attributes 595 pthread_attr_t attr; 596 if(pthread_attr_init(&attr) != 0) { 597 Err("pthread_attr_init error\n"); 598 return; 599 } 600 601 if(pthread_attr_setstacksize(&attr, NRT_STACK_SIZE) != 0) { 602 Err("pthread_attr_setstacksize error\n"); 603 return; 604 } 605 606 if(pthread_create(&log_th, &attr, write_log_user, (void*)this) < 0) 607 #else 608 if(pthread_create(&log_th, NULL, write_log_user, (void*)this) < 0) 609 #endif 610 { 611 Err("pthread_create error\n"); 612 return; 613 } 614 #ifdef NRT_STACK_SIZE 615 if(pthread_attr_destroy(&attr) != 0) { 616 Err("pthread_attr_destroy error\n"); 617 return; 618 } 619 #endif 620 621 logger_defined=true; 622 } 623 624 void FrameworkManager_impl::AddDeviceToLog(IODevice *device) 625 { 626 if(logger_defined==false) 627 { 628 Err("SetupLogger() was not called, not starting log\n"); 629 return; 630 } 631 632 if(is_logging==false) 633 { 634 if(device->pimpl_->SetToBeLogged()) { 635 log_desc_t tmp; 636 tmp.device=device; 637 logs.push_back(tmp); 638 } else { 639 Warn("not adding it twice\n"); 640 } 641 } 642 else 643 { 644 Err("impossible while logging\n"); 645 } 646 } 647 648 void FrameworkManager_impl::StartLog(void) 649 { 650 if(logger_defined==false) 651 { 652 Err("SetupLogger() was not called, not starting log\n"); 653 return; 654 } 655 656 ssize_t written; 657 size_t nb_err=0; 658 659 if(logs.size()==0) 660 { 661 Warn("Not starting log: nothing to log!\n"); 662 return; 663 } 664 665 if(is_logging==false) 666 { 667 for(size_t i=0;i<logs.size();i++) 668 { 669 670 logs.at(i).running=true; 671 logs.at(i).dbtFile=NULL; 672 logs.at(i).size=logs.at(i).device->pimpl_->LogSize(); 673 #ifdef __XENO__ 674 written=rt_pipe_write(&cmd_pipe,&logs.at(i),sizeof(log_desc_t),P_NORMAL); 675 #else 676 written=write(cmd_pipe[1],&logs.at(i),sizeof(log_desc_t)); 677 #endif 678 679 if(written<0) 680 { 681 Err("write pipe error (%s)\n",strerror(-written)); 682 nb_err++; 683 logs.at(i).running=false; 684 } 685 else if (written != sizeof(log_desc_t)) 686 { 687 Err("write pipe error %ld/%ld\n",written,sizeof(log_desc_t)); 688 nb_err++; 689 logs.at(i).running=false; 690 } 691 } 692 693 if(nb_err!=logs.size()) is_logging=true; 694 } 695 else 696 { 697 Warn("Already logging\n"); 698 } 699 } 700 701 void FrameworkManager_impl::StopLog(void) 702 { 703 ssize_t written; 704 705 if(is_logging==true) 706 { 707 for(size_t i=0;i<logs.size();i++) 708 { 709 logs.at(i).running=false; 710 } 711 //send only one running false condition, user thread will stop and send all 712 #ifdef __XENO__ 713 written=rt_pipe_write(&cmd_pipe,&logs.at(0),sizeof(log_desc_t),P_NORMAL); 714 #else 715 written=write(cmd_pipe[1],&logs.at(0),sizeof(log_desc_t)); 716 #endif 717 718 if(written<0) 719 { 720 Err("write pipe error (%s)\n",strerror(-written)); 721 return; 722 } 723 else if (written != sizeof(log_desc_t)) 724 { 725 Err("write pipe error %ld/%ld\n",written,sizeof(log_desc_t)); 726 return; 727 } 728 729 is_logging=false; 730 } 731 else 732 { 733 Warn("Not logging\n"); 734 } 735 } 736 737 char* FrameworkManager_impl::GetBuffer(size_t sz) 738 { 739 //Printf("alloc %i\n",sz); 740 #ifdef __XENO__ 741 void *ptr; 742 int status=rt_heap_alloc(&log_heap,sz,TM_NONBLOCK ,&ptr); 743 if(status!=0) 744 { 745 Err("rt_heap_alloc error (%s)\n",strerror(-status)); 746 ptr=NULL; 747 } 748 return (char*)ptr; 749 #else 750 return (char*)malloc(sz); 751 #endif 752 } 753 754 void FrameworkManager_impl::ReleaseBuffer(char* buf) 755 { 756 #ifdef __XENO__ 757 int status=rt_heap_free(&log_heap,buf); 758 759 if(status!=0) 760 { 761 Err("rt_heap_free error (%s)\n",strerror(-status)); 762 } 763 #else 764 free(buf); 765 #endif 766 } 767 768 void FrameworkManager_impl::WriteLog(const char* buf,size_t size) 769 { 770 ssize_t written; 771 772 #ifdef __XENO__ 773 written=rt_pipe_write(&data_pipe,buf,size,P_NORMAL); 774 #else 775 written=write(data_pipe[1],buf,size); 776 #endif 777 778 if(written<0) 779 { 780 Err("erreur write pipe (%s)\n",strerror(-written)); 781 } 782 else if (written != (ssize_t)size) 783 { 784 Err("erreur write pipe %ld/%ld\n",written,size); 785 } 786 } 787 788 void* FrameworkManager_impl::write_log_user(void * arg) 789 { 790 int cmd_pipe=-1; 791 int data_pipe=-1; 792 string filename; 793 fd_set set; 794 struct timeval timeout; 795 FrameworkManager_impl *caller = (FrameworkManager_impl*)arg; 796 int rv; 797 798 vector<log_desc_t> logs; 799 800 #ifdef __XENO__ 801 filename=NRT_PIPE_PATH+ caller->self->ObjectName() + "-log_cmd"; 802 while(cmd_pipe<0) 803 { 804 cmd_pipe = open(filename.c_str(), O_RDWR); 805 if (cmd_pipe < 0 && errno!=ENOENT) caller->self->Err("open rt_pipe error: %s %i\n",filename.c_str(),errno); 806 usleep(1000); 807 } 808 filename=NRT_PIPE_PATH+ caller->self->ObjectName() + "-log_data"; 809 while(data_pipe<0) 810 { 811 data_pipe = open(filename.c_str(), O_RDWR); 812 if (data_pipe < 0 && errno!=ENOENT) caller->self->Err("open rt_pipe error: %s %i\n",filename.c_str(),errno); 813 usleep(1000); 814 } 815 #else 816 cmd_pipe=caller->cmd_pipe[0]; 817 data_pipe=caller->data_pipe[0]; 818 #endif 819 820 while(caller->continuer==true) 821 { 822 FD_ZERO(&set); 823 FD_SET(cmd_pipe, &set); 824 FD_SET(data_pipe, &set); 825 826 timeout.tv_sec = 0; 827 timeout.tv_usec = SELECT_TIMEOUT_MS*1000; 828 rv = select(FD_SETSIZE, &set, NULL, NULL, &timeout); 829 830 if(rv == -1) 831 { 832 caller->Err("select error\n"); // an error accured 833 } 834 else if(rv == 0) 835 { 836 //printf("timeout write_log_user %s\n",caller->ObjectName().c_str()); // a timeout occured 837 } 838 else 839 { 840 if(FD_ISSET(cmd_pipe, &set)) 841 { 842 log_desc_t tmp; 843 read(cmd_pipe,&tmp,sizeof(log_desc_t)); 844 845 if(tmp.running==true)//start logging 846 { 847 filename= caller->log_path + "/" +caller->FileName(tmp.device)+ ".dbt"; 848 printf("Creating log file %s (log size %i)\n",filename.c_str(), (int)tmp.size); 849 tmp.dbtFile = inithdFile((char*)filename.c_str(),UAV,tmp.size); 850 logs.push_back(tmp); 851 852 if(logs.size()==1) 853 { 854 filename= caller->log_path + "/setup.xml"; 855 xmlSaveFile(filename.c_str(),caller->file_doc); 856 } 857 } 858 else//stop logging 859 { 860 for(size_t i=0;i<logs.size();i++) 861 { 862 if(logs.at(i).dbtFile!=NULL) 863 { 864 close_hdfile(logs.at(i).dbtFile); 865 866 filename= caller->FileName(logs.at(i).device)+ ".dbt"; 867 caller->SendFile(caller->log_path,filename); 868 869 fstream txt_file; 870 filename= caller->FileName(logs.at(i).device)+ ".txt"; 871 txt_file.open((caller->log_path+"/"+filename).c_str(),fstream::out); 872 txt_file << "1: time (us)\n2: time (ns)\n"; 873 int index=3; 874 logs.at(i).device->pimpl_->WriteLogsDescriptors(txt_file,&index); 875 txt_file.close(); 876 877 caller->SendFile(caller->log_path,filename); 878 } 879 } 880 //a revoir celui ci est le xml enregistré et pas forcement l'actuel 881 //if(caller->xml_file!="") caller->SendFile(caller->xml_file); 882 caller->FinishSending(); 883 884 logs.clear(); 885 } 886 } 887 888 if(FD_ISSET(data_pipe, &set)) 889 { 890 log_header_t header; 891 read(data_pipe,&header,sizeof(log_header_t)); 892 893 for(size_t i=0;i<logs.size();i++) 894 { 895 if(logs.at(i).device==header.device) 896 { 897 char* buf=(char*)malloc(header.size); 898 read(data_pipe,buf,header.size); 899 //printf("%s \n",header.device->ObjectName().c_str()); 900 //for(int i=0;i<header.size;i++) printf("%x ",buf[i]); 901 //printf("\n"); 902 if(logs.at(i).size==header.size) 903 { 904 if(logs.at(i).dbtFile!=NULL) 905 { 906 write_hdfile(logs.at(i).dbtFile,buf,(road_time_t)(header.time/1000),(road_timerange_t)(header.time%1000),header.size); 907 } 908 else 909 { 910 printf("err\n"); 911 } 912 } 913 else 914 { 915 caller->self->Err("%s log size is not correct %i/%i\n",header.device->ObjectName().c_str(),header.size,logs.at(i).size); 916 } 917 free(buf); 918 } 919 } 920 } 921 } 922 } 923 924 #ifdef __XENO__ 925 close(cmd_pipe); 926 close(data_pipe); 927 #endif 928 929 pthread_exit(0); 930 931 } 932 933 string FrameworkManager_impl::FileName(IODevice* device) 934 { 935 return getFrameworkManager()->ObjectName() + "_"+device->ObjectName(); 936 } 937 938 void FrameworkManager_impl::PrintXml(void) const 939 { 940 xmlChar *xmlbuff; 941 int buffersize; 942 xmlDocDumpFormatMemory(file_doc, &xmlbuff, &buffersize, 1); 943 Printf("xml:\n%s\n",xmlbuff); 944 xmlFree(xmlbuff); 945 } 869 } 870 } 871 } 872 873 #ifdef __XENO__ 874 close(cmd_pipe); 875 close(data_pipe); 876 #endif 877 878 pthread_exit(0); 879 } 880 881 string FrameworkManager_impl::FileName(IODevice *device) { 882 return getFrameworkManager()->ObjectName() + "_" + device->ObjectName(); 883 } 884 885 void FrameworkManager_impl::PrintXml(void) const { 886 xmlChar *xmlbuff; 887 int buffersize; 888 xmlDocDumpFormatMemory(file_doc, &xmlbuff, &buffersize, 1); 889 Printf("xml:\n%s\n", xmlbuff); 890 xmlFree(xmlbuff); 891 } -
trunk/lib/FlairCore/src/GeoCoordinate.cpp
r2 r15 20 20 using std::string; 21 21 22 namespace flair 23 { 24 namespace core 25 { 22 namespace flair { 23 namespace core { 26 24 27 GeoCoordinate::GeoCoordinate(const Object* parent,string name,const GeoCoordinate *point,int n): io_data(parent,name,n) 28 { 29 if(n>1) Warn("n>1 not supported\n"); 30 CopyFrom(point); 25 GeoCoordinate::GeoCoordinate(const Object *parent, string name, 26 const GeoCoordinate *point, int n) 27 : io_data(parent, name, n) { 28 if (n > 1) 29 Warn("n>1 not supported\n"); 30 CopyFrom(point); 31 31 } 32 32 33 GeoCoordinate::GeoCoordinate(const Object* parent,string name,double latitude,double longitude,double altitude,int n): io_data(parent,name,n) 34 { 35 this->latitude=latitude; 36 this->longitude=longitude; 37 this->altitude=altitude; 33 GeoCoordinate::GeoCoordinate(const Object *parent, string name, double latitude, 34 double longitude, double altitude, int n) 35 : io_data(parent, name, n) { 36 this->latitude = latitude; 37 this->longitude = longitude; 38 this->altitude = altitude; 38 39 } 39 40 40 GeoCoordinate::~GeoCoordinate() 41 { 41 GeoCoordinate::~GeoCoordinate() {} 42 42 43 void GeoCoordinate::CopyFrom(const GeoCoordinate *point) { 44 double latitude, longitude, altitude; 45 point->GetCoordinates(&latitude, &longitude, &altitude); 46 GetMutex(); 47 this->latitude = latitude; 48 this->longitude = longitude; 49 this->altitude = altitude; 50 ReleaseMutex(); 43 51 } 44 52 45 void GeoCoordinate::CopyFrom(const GeoCoordinate *point) 46 { 47 double latitude,longitude,altitude; 48 point->GetCoordinates(&latitude,&longitude,&altitude); 49 GetMutex(); 50 this->latitude=latitude; 51 this->longitude=longitude; 52 this->altitude=altitude; 53 ReleaseMutex(); 53 void GeoCoordinate::SetCoordinates(double latitude, double longitude, 54 double altitude) { 55 GetMutex(); 56 this->latitude = latitude; 57 this->longitude = longitude; 58 this->altitude = altitude; 59 ReleaseMutex(); 54 60 } 55 61 56 void GeoCoordinate:: SetCoordinates(double latitude,double longitude,double altitude)57 {58 59 this->latitude=latitude;60 this->longitude=longitude;61 this->altitude=altitude;62 62 void GeoCoordinate::GetCoordinates(double *latitude, double *longitude, 63 double *altitude) const { 64 GetMutex(); 65 *latitude = this->latitude; 66 *longitude = this->longitude; 67 *altitude = this->altitude; 68 ReleaseMutex(); 63 69 } 64 70 65 void GeoCoordinate::GetCoordinates(double *latitude,double *longitude,double *altitude) const 66 { 67 GetMutex(); 68 *latitude=this->latitude; 69 *longitude=this->longitude; 70 *altitude=this->altitude; 71 ReleaseMutex(); 72 } 73 74 void GeoCoordinate::CopyDatas(char* ptr) const 75 { 76 Warn("a ecrire"); 77 } 71 void GeoCoordinate::CopyDatas(char *ptr) const { Warn("a ecrire"); } 78 72 79 73 } // end namespace core -
trunk/lib/FlairCore/src/GeoCoordinate.h
r2 r15 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/lib/FlairCore/src/GridLayout.cpp
r2 r15 20 20 using std::string; 21 21 22 namespace flair 23 { 24 namespace gui 25 { 22 namespace flair { 23 namespace gui { 26 24 27 GridLayout::GridLayout(const LayoutPosition * position,string name): Layout(position->getLayout(),name,"GridLayout")28 {29 SetVolatileXmlProp("row",position->Row());30 SetVolatileXmlProp("col",position->Col());31 25 GridLayout::GridLayout(const LayoutPosition *position, string name) 26 : Layout(position->getLayout(), name, "GridLayout") { 27 SetVolatileXmlProp("row", position->Row()); 28 SetVolatileXmlProp("col", position->Col()); 29 SendXml(); 32 30 33 31 delete position; 34 32 } 35 33 36 GridLayout::~GridLayout() 37 { 38 39 } 34 GridLayout::~GridLayout() {} 40 35 41 36 } // end namespace gui -
trunk/lib/FlairCore/src/GridLayout.h
r2 r15 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/lib/FlairCore/src/GroupBox.cpp
r2 r15 20 20 using std::string; 21 21 22 namespace flair 23 { 24 namespace gui 25 { 22 namespace flair { 23 namespace gui { 26 24 27 GroupBox::GroupBox(const LayoutPosition * position,string name): Layout(position->getLayout(),name,"GroupBox")28 {29 SetVolatileXmlProp("row",position->Row());30 SetVolatileXmlProp("col",position->Col());31 25 GroupBox::GroupBox(const LayoutPosition *position, string name) 26 : Layout(position->getLayout(), name, "GroupBox") { 27 SetVolatileXmlProp("row", position->Row()); 28 SetVolatileXmlProp("col", position->Col()); 29 SendXml(); 32 30 33 31 delete position; 34 32 } 35 33 36 GroupBox::~GroupBox() 37 { 38 39 } 34 GroupBox::~GroupBox() {} 40 35 41 36 } // end namespace gui -
trunk/lib/FlairCore/src/GroupBox.h
r2 r15 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/lib/FlairCore/src/I2cPort.h
r2 r15 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/lib/FlairCore/src/IODataElement.h
r2 r15 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/lib/FlairCore/src/IODevice.cpp
r2 r15 24 24 using std::string; 25 25 26 namespace flair 27 { 28 namespace core 29 { 26 namespace flair { 27 namespace core { 30 28 31 IODevice::IODevice(const Object * parent,string name): Object(parent,name,"IODevice")32 {33 pimpl_=new IODevice_impl(this);29 IODevice::IODevice(const Object *parent, string name) 30 : Object(parent, name, "IODevice") { 31 pimpl_ = new IODevice_impl(this); 34 32 } 35 33 36 IODevice::~IODevice() 37 { 38 delete pimpl_; 34 IODevice::~IODevice() { delete pimpl_; } 35 36 void IODevice::AddDeviceToLog(const IODevice *device) { 37 pimpl_->AddDeviceToLog(device); 39 38 } 40 39 41 void IODevice::AddDeviceToLog(const IODevice* device) 42 { 43 pimpl_->AddDeviceToLog(device); 40 void IODevice::OutputToShMem(bool enabled) { pimpl_->OutputToShMem(enabled); } 41 42 void IODevice::ProcessUpdate(io_data *data) { 43 if (data != NULL) 44 data->pimpl_->SetConsistent(true); 45 46 for (size_t i = 0; i < TypeChilds()->size(); i++) { 47 ((IODevice *)TypeChilds()->at(i))->UpdateFrom(data); 48 } 49 50 if (data != NULL) { 51 if (getFrameworkManager()->IsLogging() == true) 52 pimpl_->WriteLog(data->DataTime()); 53 54 data->pimpl_->Circle(); 55 } 56 57 pimpl_->WriteToShMem(); 58 59 pimpl_->ResumeThread(); 44 60 } 45 61 46 void IODevice::OutputToShMem(bool enabled) { 47 pimpl_->OutputToShMem(enabled); 48 } 62 void IODevice::AddDataToLog(const io_data *data) { pimpl_->AddDataToLog(data); } 49 63 50 void IODevice::ProcessUpdate(io_data* data) 51 { 52 if(data!=NULL) data->pimpl_->SetConsistent(true); 64 DataType const &IODevice::GetInputDataType() const { return dummyType; } 53 65 54 for(size_t i=0;i<TypeChilds()->size();i++) 55 { 56 ((IODevice*)TypeChilds()->at(i))->UpdateFrom(data); 57 } 58 59 if(data!=NULL) 60 { 61 if(getFrameworkManager()->IsLogging()==true) pimpl_->WriteLog(data->DataTime()); 62 63 data->pimpl_->Circle(); 64 } 65 66 pimpl_->WriteToShMem(); 67 68 pimpl_->ResumeThread(); 69 } 70 71 void IODevice::AddDataToLog(const io_data* data) 72 { 73 pimpl_->AddDataToLog(data); 74 } 75 76 DataType const &IODevice::GetInputDataType() const { 77 return dummyType; 78 } 79 80 DataType const &IODevice::GetOutputDataType() const { 81 return dummyType; 82 } 66 DataType const &IODevice::GetOutputDataType() const { return dummyType; } 83 67 84 68 } // end namespace core -
trunk/lib/FlairCore/src/IODevice.h
r2 r15 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/lib/FlairCore/src/IODevice_impl.cpp
r2 r15 31 31 using namespace flair::core; 32 32 33 IODevice_impl::IODevice_impl(const IODevice *self) {34 this->self=self;35 thread_to_wake=NULL;36 wake_mutex= new Mutex(self);37 framework_impl=::getFrameworkManagerImpl();38 framework=getFrameworkManager();39 tobelogged=false;40 outputtoshm=false;33 IODevice_impl::IODevice_impl(const IODevice *self) { 34 this->self = self; 35 thread_to_wake = NULL; 36 wake_mutex = new Mutex(self); 37 framework_impl = ::getFrameworkManagerImpl(); 38 framework = getFrameworkManager(); 39 tobelogged = false; 40 outputtoshm = false; 41 41 } 42 42 … … 44 44 45 45 void IODevice_impl::OutputToShMem(bool enabled) { 46 if(framework->IsLogging()) { 47 self->Err("impossible while logging\n"); 46 if (framework->IsLogging()) { 47 self->Err("impossible while logging\n"); 48 } else { 49 if (LogSize() == 0) { 50 self->Warn("log size is null, not enabling output to shared memory."); 51 return; 52 } 53 54 if (enabled) { 55 string dev_name = 56 getFrameworkManager()->ObjectName() + "-" + self->ObjectName(); 57 shmem = new SharedMem(self, dev_name.c_str(), LogSize()); 58 outputtoshm = true; 59 60 Printf("Created %s shared memory for object %s; size: %i\n", 61 dev_name.c_str(), self->ObjectName().c_str(), LogSize()); 62 PrintLogsDescriptors(); 48 63 } else { 49 if(LogSize()==0) { 50 self->Warn("log size is null, not enabling output to shared memory."); 51 return; 52 } 53 54 if(enabled) { 55 string dev_name=getFrameworkManager()->ObjectName()+ "-" + self->ObjectName(); 56 shmem=new SharedMem(self,dev_name.c_str(),LogSize()); 57 outputtoshm=true; 58 59 Printf("Created %s shared memory for object %s; size: %i\n",dev_name.c_str(),self->ObjectName().c_str(),LogSize()); 60 PrintLogsDescriptors(); 61 } else { 62 outputtoshm=false; 63 delete shmem; 64 } 64 outputtoshm = false; 65 delete shmem; 65 66 } 67 } 66 68 } 67 69 68 70 void IODevice_impl::PrintLogsDescriptors(void) { 69 //own logs 70 for(size_t i=0;i<datasToLog.size();i++) datasToLog.at(i)->pimpl_->PrintLogDescriptor(); 71 //childs logs 72 for(size_t i=0;i<self->TypeChilds()->size();i++) ((IODevice*)self->TypeChilds()->at(i))->pimpl_->PrintLogsDescriptors(); 73 //manually added logs 74 for(size_t i=0;i<devicesToLog.size();i++) devicesToLog.at(i)->pimpl_->PrintLogsDescriptors(); 71 // own logs 72 for (size_t i = 0; i < datasToLog.size(); i++) 73 datasToLog.at(i)->pimpl_->PrintLogDescriptor(); 74 // childs logs 75 for (size_t i = 0; i < self->TypeChilds()->size(); i++) 76 ((IODevice *)self->TypeChilds()->at(i))->pimpl_->PrintLogsDescriptors(); 77 // manually added logs 78 for (size_t i = 0; i < devicesToLog.size(); i++) 79 devicesToLog.at(i)->pimpl_->PrintLogsDescriptors(); 75 80 } 76 81 77 82 void IODevice_impl::WriteToShMem(void) { 78 if(outputtoshm) { 79 size_t size=LogSize(); 80 81 char* buf=framework_impl->GetBuffer(size); 82 char* buf_orig=buf; 83 if(buf==NULL) { 84 self->Err("err GetBuffer\n"); 85 return; 86 } 87 88 AppendLog(&buf); 89 90 shmem->Write(buf_orig,size); 91 framework_impl->ReleaseBuffer(buf_orig); 83 if (outputtoshm) { 84 size_t size = LogSize(); 85 86 char *buf = framework_impl->GetBuffer(size); 87 char *buf_orig = buf; 88 if (buf == NULL) { 89 self->Err("err GetBuffer\n"); 90 return; 92 91 } 93 } 94 95 void IODevice_impl::AddDeviceToLog(const IODevice* device) { 96 if(framework->IsLogging()) { 97 self->Err("impossible while logging\n"); 98 } else { 99 devicesToLog.push_back(device); 100 } 92 93 AppendLog(&buf); 94 95 shmem->Write(buf_orig, size); 96 framework_impl->ReleaseBuffer(buf_orig); 97 } 98 } 99 100 void IODevice_impl::AddDeviceToLog(const IODevice *device) { 101 if (framework->IsLogging()) { 102 self->Err("impossible while logging\n"); 103 } else { 104 devicesToLog.push_back(device); 105 } 101 106 } 102 107 103 108 bool IODevice_impl::SetToBeLogged(void) { 104 if(!tobelogged) { 105 tobelogged=true; 106 return true; 107 } else { 108 self->Warn("already added to log\n"); 109 return false; 110 } 111 } 112 113 void IODevice_impl::WriteLogsDescriptors(fstream& desc_file,int *index) { 114 //own descriptor 115 for(size_t i=0;i<datasToLog.size();i++) datasToLog.at(i)->pimpl_->WriteLogDescriptor(desc_file,index); 116 //childs descriptors 117 for(size_t i=0;i<self->TypeChilds()->size();i++) ((IODevice*)self->TypeChilds()->at(i))->pimpl_->WriteLogsDescriptors(desc_file,index); 118 //manually added logs 119 for(size_t i=0;i<devicesToLog.size();i++) devicesToLog.at(i)->pimpl_->WriteLogsDescriptors(desc_file,index); 109 if (!tobelogged) { 110 tobelogged = true; 111 return true; 112 } else { 113 self->Warn("already added to log\n"); 114 return false; 115 } 116 } 117 118 void IODevice_impl::WriteLogsDescriptors(fstream &desc_file, int *index) { 119 // own descriptor 120 for (size_t i = 0; i < datasToLog.size(); i++) 121 datasToLog.at(i)->pimpl_->WriteLogDescriptor(desc_file, index); 122 // childs descriptors 123 for (size_t i = 0; i < self->TypeChilds()->size(); i++) 124 ((IODevice *)self->TypeChilds()->at(i)) 125 ->pimpl_->WriteLogsDescriptors(desc_file, index); 126 // manually added logs 127 for (size_t i = 0; i < devicesToLog.size(); i++) 128 devicesToLog.at(i)->pimpl_->WriteLogsDescriptors(desc_file, index); 120 129 } 121 130 122 131 void IODevice_impl::ResumeThread(void) { 123 124 if(thread_to_wake!=NULL) {125 126 thread_to_wake=NULL;127 128 129 } 130 131 void IODevice_impl::AddDataToLog(const io_data *data) {132 if(framework->IsLogging()) {133 134 135 136 132 wake_mutex->GetMutex(); 133 if (thread_to_wake != NULL) { 134 thread_to_wake->Resume(); 135 thread_to_wake = NULL; 136 } 137 wake_mutex->ReleaseMutex(); 138 } 139 140 void IODevice_impl::AddDataToLog(const io_data *data) { 141 if (framework->IsLogging()) { 142 self->Err("impossible while logging\n"); 143 } else { 144 datasToLog.push_back(data); 145 } 137 146 } 138 147 139 148 size_t IODevice_impl::LogSize() const { 140 size_t value=0;141 142 for(size_t i=0;i<datasToLog.size();i++) {143 value+=datasToLog.at(i)->GetDataType().GetSize();144 145 146 //childs logs147 for(size_t i=0;i<self->TypeChilds()->size();i++) {148 value+=((IODevice*)self->TypeChilds()->at(i))->pimpl_->LogSize();149 150 //manually added logs151 for(size_t i=0;i<devicesToLog.size();i++) {152 value+=devicesToLog.at(i)->pimpl_->LogSize();153 154 155 149 size_t value = 0; 150 151 for (size_t i = 0; i < datasToLog.size(); i++) { 152 value += datasToLog.at(i)->GetDataType().GetSize(); 153 } 154 155 // childs logs 156 for (size_t i = 0; i < self->TypeChilds()->size(); i++) { 157 value += ((IODevice *)self->TypeChilds()->at(i))->pimpl_->LogSize(); 158 } 159 // manually added logs 160 for (size_t i = 0; i < devicesToLog.size(); i++) { 161 value += devicesToLog.at(i)->pimpl_->LogSize(); 162 } 163 164 return value; 156 165 } 157 166 158 167 void IODevice_impl::WriteLog(Time time) { 159 if(tobelogged==false) return; 160 161 size_t size=LogSize(); 162 163 char* buf=framework_impl->GetBuffer(sizeof(FrameworkManager_impl::log_header_t)+size); 164 char* buf_orig=buf; 165 if(buf==NULL) { 166 self->Err("err GetBuffer\n"); 167 return; 168 } 169 170 FrameworkManager_impl::log_header_t header; 171 header.device=self; 172 header.size=size; 173 header.time=time; 174 175 memcpy(buf,&header,sizeof(FrameworkManager_impl::log_header_t)); 176 buf+=sizeof(FrameworkManager_impl::log_header_t); 177 AppendLog(&buf); 178 179 framework_impl->WriteLog(buf_orig,sizeof(FrameworkManager_impl::log_header_t)+size); 180 framework_impl->ReleaseBuffer(buf_orig); 181 } 182 183 void IODevice_impl::AppendLog(char** ptr) 184 { 185 //Printf("AppendLog %s %x\n",self->ObjectName().c_str(),*ptr); 186 187 //copy state to buf 188 for(size_t i=0;i<datasToLog.size();i++) { 189 //printf("copy\n"); 190 datasToLog.at(i)->CopyDatas(*ptr); 191 (*ptr)+=datasToLog.at(i)->GetDataType().GetSize(); 192 } 193 194 //copy linked states to buf 195 for(size_t i=0;i<self->TypeChilds()->size();i++) { 196 ((IODevice*)self->TypeChilds()->at(i))->pimpl_->AppendLog(ptr); 197 } 198 //copy manually added logs to buf 199 for(size_t i=0;i<devicesToLog.size();i++) { 200 devicesToLog.at(i)->pimpl_->AppendLog(ptr); 201 //devices.at(i)->DataToLog()->CopyDatas(*ptr); 202 //(*ptr)+=devices.at(i)->DataToLog()->Size(); 203 } 204 //Printf("AppendLog %s ok\n",self->ObjectName().c_str()); 205 } 206 207 int IODevice_impl::SetToWake(const Thread* thread) { 208 int status=0; 209 210 wake_mutex->GetMutex(); 211 if(thread_to_wake==NULL) { 212 thread_to_wake=(Thread*)thread; 213 } else { 214 status=-1; 215 } 216 wake_mutex->ReleaseMutex(); 217 218 return status; 219 } 168 if (tobelogged == false) 169 return; 170 171 size_t size = LogSize(); 172 173 char *buf = framework_impl->GetBuffer( 174 sizeof(FrameworkManager_impl::log_header_t) + size); 175 char *buf_orig = buf; 176 if (buf == NULL) { 177 self->Err("err GetBuffer\n"); 178 return; 179 } 180 181 FrameworkManager_impl::log_header_t header; 182 header.device = self; 183 header.size = size; 184 header.time = time; 185 186 memcpy(buf, &header, sizeof(FrameworkManager_impl::log_header_t)); 187 buf += sizeof(FrameworkManager_impl::log_header_t); 188 AppendLog(&buf); 189 190 framework_impl->WriteLog(buf_orig, 191 sizeof(FrameworkManager_impl::log_header_t) + size); 192 framework_impl->ReleaseBuffer(buf_orig); 193 } 194 195 void IODevice_impl::AppendLog(char **ptr) { 196 // Printf("AppendLog %s %x\n",self->ObjectName().c_str(),*ptr); 197 198 // copy state to buf 199 for (size_t i = 0; i < datasToLog.size(); i++) { 200 // printf("copy\n"); 201 datasToLog.at(i)->CopyDatas(*ptr); 202 (*ptr) += datasToLog.at(i)->GetDataType().GetSize(); 203 } 204 205 // copy linked states to buf 206 for (size_t i = 0; i < self->TypeChilds()->size(); i++) { 207 ((IODevice *)self->TypeChilds()->at(i))->pimpl_->AppendLog(ptr); 208 } 209 // copy manually added logs to buf 210 for (size_t i = 0; i < devicesToLog.size(); i++) { 211 devicesToLog.at(i)->pimpl_->AppendLog(ptr); 212 // devices.at(i)->DataToLog()->CopyDatas(*ptr); 213 //(*ptr)+=devices.at(i)->DataToLog()->Size(); 214 } 215 // Printf("AppendLog %s ok\n",self->ObjectName().c_str()); 216 } 217 218 int IODevice_impl::SetToWake(const Thread *thread) { 219 int status = 0; 220 221 wake_mutex->GetMutex(); 222 if (thread_to_wake == NULL) { 223 thread_to_wake = (Thread *)thread; 224 } else { 225 status = -1; 226 } 227 wake_mutex->ReleaseMutex(); 228 229 return status; 230 } -
trunk/lib/FlairCore/src/ImuData.cpp
r2 r15 24 24 using std::string; 25 25 26 namespace flair { namespace core { 26 namespace flair { 27 namespace core { 27 28 28 29 /*! \class ImuDataElement 29 30 */ 30 class ImuDataElement: public IODataElement { 31 public: 32 33 ImuDataElement(const ImuData *inImudata,string name,ImuData::PlotableData_t inPlotableData):IODataElement(inImudata,name) { 34 imudata=inImudata; 35 plotableData=inPlotableData; 36 37 size=4; 38 } 39 40 ~ImuDataElement() {} 41 42 void CopyData(char* dst) const { 43 float data; 44 Vector3D rawAcc=imudata->GetRawAcc(); 45 Vector3D rawMag=imudata->GetRawMag(); 46 Vector3D rawGyr=imudata->GetRawGyr(); 47 switch(plotableData) { 48 case ImuData::RawAx: 49 data=rawAcc.x; 50 break; 51 case ImuData::RawAy: 52 data=rawAcc.y; 53 break; 54 case ImuData::RawAz: 55 data=rawAcc.z; 56 break; 57 case ImuData::RawGx: 58 data=rawGyr.x; 59 break; 60 case ImuData::RawGy: 61 data=rawGyr.y; 62 break; 63 case ImuData::RawGz: 64 data=rawGyr.z; 65 break; 66 case ImuData::RawGxDeg: 67 data=Euler::ToDegree(rawGyr.x); 68 break; 69 case ImuData::RawGyDeg: 70 data=Euler::ToDegree(rawGyr.y); 71 break; 72 case ImuData::RawGzDeg: 73 data=Euler::ToDegree(rawGyr.z); 74 break; 75 case ImuData::RawMx: 76 data=rawMag.x; 77 break; 78 case ImuData::RawMy: 79 data=rawMag.y; 80 break; 81 case ImuData::RawMz: 82 data=rawMag.z; 83 break; 84 default: 85 imudata->Err("data type unavailable.\n"); 86 data=0; 87 break; 88 } 89 90 memcpy(dst,&data,sizeof(float)); 91 } 92 93 FloatType const &GetDataType(void) const { 94 return dataType; 95 } 96 97 private: 98 const ImuData *imudata; 99 ImuData::PlotableData_t plotableData; 100 FloatType dataType; 101 102 }; 103 104 ImuData::ImuData(const Object* parent,std::string name,int n): io_data(parent,name,n),dataType(floatType) { 105 if(n>1) Warn("n>1 not supported\n"); 106 107 AppendLogDescription("raw_ax",floatType); 108 AppendLogDescription("raw_ay",floatType); 109 AppendLogDescription("raw_az",floatType); 110 111 AppendLogDescription("raw_gx",floatType); 112 AppendLogDescription("raw_gy",floatType); 113 AppendLogDescription("raw_gz",floatType); 114 115 AppendLogDescription("raw_mx",floatType); 116 AppendLogDescription("raw_my",floatType); 117 AppendLogDescription("raw_mz",floatType); 118 31 class ImuDataElement : public IODataElement { 32 public: 33 ImuDataElement(const ImuData *inImudata, string name, 34 ImuData::PlotableData_t inPlotableData) 35 : IODataElement(inImudata, name) { 36 imudata = inImudata; 37 plotableData = inPlotableData; 38 39 size = 4; 40 } 41 42 ~ImuDataElement() {} 43 44 void CopyData(char *dst) const { 45 float data; 46 Vector3D rawAcc = imudata->GetRawAcc(); 47 Vector3D rawMag = imudata->GetRawMag(); 48 Vector3D rawGyr = imudata->GetRawGyr(); 49 switch (plotableData) { 50 case ImuData::RawAx: 51 data = rawAcc.x; 52 break; 53 case ImuData::RawAy: 54 data = rawAcc.y; 55 break; 56 case ImuData::RawAz: 57 data = rawAcc.z; 58 break; 59 case ImuData::RawGx: 60 data = rawGyr.x; 61 break; 62 case ImuData::RawGy: 63 data = rawGyr.y; 64 break; 65 case ImuData::RawGz: 66 data = rawGyr.z; 67 break; 68 case ImuData::RawGxDeg: 69 data = Euler::ToDegree(rawGyr.x); 70 break; 71 case ImuData::RawGyDeg: 72 data = Euler::ToDegree(rawGyr.y); 73 break; 74 case ImuData::RawGzDeg: 75 data = Euler::ToDegree(rawGyr.z); 76 break; 77 case ImuData::RawMx: 78 data = rawMag.x; 79 break; 80 case ImuData::RawMy: 81 data = rawMag.y; 82 break; 83 case ImuData::RawMz: 84 data = rawMag.z; 85 break; 86 default: 87 imudata->Err("data type unavailable.\n"); 88 data = 0; 89 break; 90 } 91 92 memcpy(dst, &data, sizeof(float)); 93 } 94 95 FloatType const &GetDataType(void) const { return dataType; } 96 97 private: 98 const ImuData *imudata; 99 ImuData::PlotableData_t plotableData; 100 FloatType dataType; 101 }; 102 103 ImuData::ImuData(const Object *parent, std::string name, int n) 104 : io_data(parent, name, n), dataType(floatType) { 105 if (n > 1) 106 Warn("n>1 not supported\n"); 107 108 AppendLogDescription("raw_ax", floatType); 109 AppendLogDescription("raw_ay", floatType); 110 AppendLogDescription("raw_az", floatType); 111 112 AppendLogDescription("raw_gx", floatType); 113 AppendLogDescription("raw_gy", floatType); 114 AppendLogDescription("raw_gz", floatType); 115 116 AppendLogDescription("raw_mx", floatType); 117 AppendLogDescription("raw_my", floatType); 118 AppendLogDescription("raw_mz", floatType); 119 119 } 120 120 121 121 ImuData::~ImuData() {} 122 122 123 124 123 Vector3D ImuData::GetRawAcc(void) const { 125 126 127 out=rawAcc;128 129 124 Vector3D out; 125 GetMutex(); 126 out = rawAcc; 127 ReleaseMutex(); 128 return out; 130 129 } 131 130 132 131 Vector3D ImuData::GetRawMag(void) const { 133 134 135 out=rawMag;136 137 132 Vector3D out; 133 GetMutex(); 134 out = rawMag; 135 ReleaseMutex(); 136 return out; 138 137 } 139 138 140 139 Vector3D ImuData::GetRawGyr(void) const { 141 Vector3D out; 142 GetMutex(); 143 out=rawGyr; 144 ReleaseMutex(); 145 return out; 146 } 147 148 void ImuData::GetRawAccMagAndGyr(Vector3D &inRawAcc,Vector3D &inRawMag,Vector3D &inRawGyr) const { 149 GetMutex(); 150 inRawAcc=rawAcc; 151 inRawMag=rawMag; 152 inRawGyr=rawGyr; 153 ReleaseMutex(); 140 Vector3D out; 141 GetMutex(); 142 out = rawGyr; 143 ReleaseMutex(); 144 return out; 145 } 146 147 void ImuData::GetRawAccMagAndGyr(Vector3D &inRawAcc, Vector3D &inRawMag, 148 Vector3D &inRawGyr) const { 149 GetMutex(); 150 inRawAcc = rawAcc; 151 inRawMag = rawMag; 152 inRawGyr = rawGyr; 153 ReleaseMutex(); 154 154 } 155 155 156 156 void ImuData::SetRawAcc(const Vector3D &inRawAcc) { 157 158 rawAcc=inRawAcc;159 157 GetMutex(); 158 rawAcc = inRawAcc; 159 ReleaseMutex(); 160 160 } 161 161 162 162 void ImuData::SetRawMag(const Vector3D &inRawMag) { 163 164 rawMag=inRawMag;165 163 GetMutex(); 164 rawMag = inRawMag; 165 ReleaseMutex(); 166 166 } 167 167 168 168 void ImuData::SetRawGyr(const Vector3D &inRawGyr) { 169 GetMutex(); 170 rawGyr=inRawGyr; 171 ReleaseMutex(); 172 } 173 174 void ImuData::SetRawAccMagAndGyr(const Vector3D &inRawAcc,const Vector3D &inRawMag,const Vector3D &inRawGyr) { 175 GetMutex(); 176 rawAcc=inRawAcc; 177 rawMag=inRawMag; 178 rawGyr=inRawGyr; 179 ReleaseMutex(); 180 } 181 182 IODataElement* ImuData::Element(PlotableData_t data_type) const { 183 string name; 184 switch(data_type) { 185 case ImuData::RawAx: 186 name="RawAx"; 187 break; 188 case ImuData::RawAy: 189 name="RawAy"; 190 break; 191 case ImuData::RawAz: 192 name="RawAz"; 193 break; 194 case ImuData::RawGx: 195 name="RawGx"; 196 break; 197 case ImuData::RawGy: 198 name="RawGy"; 199 break; 200 case ImuData::RawGz: 201 name="RawGz"; 202 break; 203 case ImuData::RawGxDeg: 204 name="RawGx degree"; 205 break; 206 case ImuData::RawGyDeg: 207 name="RawGy degree"; 208 break; 209 case ImuData::RawGzDeg: 210 name="RawGz degree"; 211 break; 212 case ImuData::RawMx: 213 name="RawMx"; 214 break; 215 case ImuData::RawMy: 216 name="RawMy"; 217 break; 218 case ImuData::RawMz: 219 name="RawMz"; 220 break; 221 } 222 223 return new ImuDataElement(this,name,data_type); 224 } 225 226 void ImuData::CopyDatas(char* dst) const { 227 GetMutex(); 228 229 Queue(&dst,&rawAcc.x,sizeof(rawAcc.x)); 230 Queue(&dst,&rawAcc.y,sizeof(rawAcc.y)); 231 Queue(&dst,&rawAcc.z,sizeof(rawAcc.z)); 232 233 Queue(&dst,&rawGyr.x,sizeof(rawGyr.x)); 234 Queue(&dst,&rawGyr.y,sizeof(rawGyr.y)); 235 Queue(&dst,&rawGyr.z,sizeof(rawGyr.z)); 236 237 Queue(&dst,&rawMag.x,sizeof(rawMag.x)); 238 Queue(&dst,&rawMag.y,sizeof(rawMag.y)); 239 Queue(&dst,&rawMag.z,sizeof(rawMag.z)); 240 241 ReleaseMutex(); 242 } 243 244 void ImuData::Queue(char** dst,const void *src,size_t size) const { 245 memcpy(*dst,src,size); 246 *dst+=size; 169 GetMutex(); 170 rawGyr = inRawGyr; 171 ReleaseMutex(); 172 } 173 174 void ImuData::SetRawAccMagAndGyr(const Vector3D &inRawAcc, 175 const Vector3D &inRawMag, 176 const Vector3D &inRawGyr) { 177 GetMutex(); 178 rawAcc = inRawAcc; 179 rawMag = inRawMag; 180 rawGyr = inRawGyr; 181 ReleaseMutex(); 182 } 183 184 IODataElement *ImuData::Element(PlotableData_t data_type) const { 185 string name; 186 switch (data_type) { 187 case ImuData::RawAx: 188 name = "RawAx"; 189 break; 190 case ImuData::RawAy: 191 name = "RawAy"; 192 break; 193 case ImuData::RawAz: 194 name = "RawAz"; 195 break; 196 case ImuData::RawGx: 197 name = "RawGx"; 198 break; 199 case ImuData::RawGy: 200 name = "RawGy"; 201 break; 202 case ImuData::RawGz: 203 name = "RawGz"; 204 break; 205 case ImuData::RawGxDeg: 206 name = "RawGx degree"; 207 break; 208 case ImuData::RawGyDeg: 209 name = "RawGy degree"; 210 break; 211 case ImuData::RawGzDeg: 212 name = "RawGz degree"; 213 break; 214 case ImuData::RawMx: 215 name = "RawMx"; 216 break; 217 case ImuData::RawMy: 218 name = "RawMy"; 219 break; 220 case ImuData::RawMz: 221 name = "RawMz"; 222 break; 223 } 224 225 return new ImuDataElement(this, name, data_type); 226 } 227 228 void ImuData::CopyDatas(char *dst) const { 229 GetMutex(); 230 231 Queue(&dst, &rawAcc.x, sizeof(rawAcc.x)); 232 Queue(&dst, &rawAcc.y, sizeof(rawAcc.y)); 233 Queue(&dst, &rawAcc.z, sizeof(rawAcc.z)); 234 235 Queue(&dst, &rawGyr.x, sizeof(rawGyr.x)); 236 Queue(&dst, &rawGyr.y, sizeof(rawGyr.y)); 237 Queue(&dst, &rawGyr.z, sizeof(rawGyr.z)); 238 239 Queue(&dst, &rawMag.x, sizeof(rawMag.x)); 240 Queue(&dst, &rawMag.y, sizeof(rawMag.y)); 241 Queue(&dst, &rawMag.z, sizeof(rawMag.z)); 242 243 ReleaseMutex(); 244 } 245 246 void ImuData::Queue(char **dst, const void *src, size_t size) const { 247 memcpy(*dst, src, size); 248 *dst += size; 247 249 } 248 250 -
trunk/lib/FlairCore/src/ImuData.h
r2 r15 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/lib/FlairCore/src/Label.cpp
r2 r15 22 22 using std::string; 23 23 24 namespace flair 25 { 26 namespace gui 27 { 24 namespace flair { 25 namespace gui { 28 26 29 Label::Label(const LayoutPosition * position,string name,size_t buf_size): Widget(position->getLayout(),name,"Label")30 {31 SetVolatileXmlProp("row",position->Row());32 SetVolatileXmlProp("col",position->Col());27 Label::Label(const LayoutPosition *position, string name, size_t buf_size) 28 : Widget(position->getLayout(), name, "Label") { 29 SetVolatileXmlProp("row", position->Row()); 30 SetVolatileXmlProp("col", position->Col()); 33 31 34 32 SendXml(); 35 33 36 printf_buffer=(char*)malloc(buf_size); 37 if(printf_buffer==NULL) Err("erreur malloc\n"); 34 printf_buffer = (char *)malloc(buf_size); 35 if (printf_buffer == NULL) 36 Err("erreur malloc\n"); 38 37 39 38 delete position; 40 39 } 41 40 42 Label::~Label() 43 { 44 if(printf_buffer!=NULL)free(printf_buffer);45 printf_buffer=NULL;41 Label::~Label() { 42 if (printf_buffer != NULL) 43 free(printf_buffer); 44 printf_buffer = NULL; 46 45 } 47 46 47 void Label::SetText(const char *format, ...) { 48 int n; 48 49 49 void Label::SetText(const char * format, ...) 50 { 51 int n; 50 va_list args; 51 va_start(args, format); 52 n = vsprintf(printf_buffer, format, args); 53 va_end(args); 54 if (n <= 0) 55 return; 52 56 53 va_list args; 54 va_start (args, format); 55 n = vsprintf(printf_buffer,format, args); 56 va_end (args); 57 if (n<=0) return; 58 59 SetVolatileXmlProp("value",printf_buffer); 60 SendXml(); 61 57 SetVolatileXmlProp("value", printf_buffer); 58 SendXml(); 62 59 } 63 60 -
trunk/lib/FlairCore/src/Label.h
r2 r15 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/lib/FlairCore/src/Layout.cpp
r2 r15 21 21 using std::string; 22 22 23 namespace flair 24 { 25 namespace gui 26 { 23 namespace flair { 24 namespace gui { 27 25 28 Layout::Layout(const Widget * parent,string name,string type): Widget(parent,name,type)29 {30 mutex=new core::Mutex(this,name);26 Layout::Layout(const Widget *parent, string name, string type) 27 : Widget(parent, name, type) { 28 mutex = new core::Mutex(this, name); 31 29 } 32 30 33 Layout::~Layout() 34 { 31 Layout::~Layout() {} 35 32 33 LayoutPosition *Layout::LastRowLastCol(void) const { 34 return new LayoutPosition(this, -1, 0); 36 35 } 37 36 38 LayoutPosition* Layout::LastRowLastCol(void) const 39 { 40 return new LayoutPosition(this,-1,0); 37 LayoutPosition *Layout::NewRow(void) const { 38 return new LayoutPosition(this, -1, -1); 41 39 } 42 40 43 LayoutPosition* Layout::NewRow(void) const 44 { 45 return new LayoutPosition(this,-1,-1); 46 } 47 48 LayoutPosition* Layout::At(uint16_t row,uint16_t col) const 49 { 50 return new LayoutPosition(this,row,col); 41 LayoutPosition *Layout::At(uint16_t row, uint16_t col) const { 42 return new LayoutPosition(this, row, col); 51 43 } 52 44 -
trunk/lib/FlairCore/src/Layout.h
r2 r15 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/lib/FlairCore/src/LayoutPosition.cpp
r2 r15 17 17 #include "LayoutPosition.h" 18 18 19 namespace flair { 20 namespace gui { 19 21 20 namespace flair 21 { 22 namespace gui 23 { 24 25 LayoutPosition::LayoutPosition(const Layout* layout,int16_t row,int16_t col) 26 { 27 this->layout=layout; 28 this->row=row; 29 this->col=col; 22 LayoutPosition::LayoutPosition(const Layout *layout, int16_t row, int16_t col) { 23 this->layout = layout; 24 this->row = row; 25 this->col = col; 30 26 } 31 27 32 LayoutPosition::~LayoutPosition() 33 { 28 LayoutPosition::~LayoutPosition() {} 34 29 35 }30 const Layout *LayoutPosition::getLayout(void) const { return layout; } 36 31 37 const Layout* LayoutPosition::getLayout(void) const 38 { 39 return layout; 40 } 32 int16_t LayoutPosition::Row(void) const { return row; } 41 33 42 int16_t LayoutPosition::Row(void) const 43 { 44 return row; 45 } 46 47 int16_t LayoutPosition::Col(void) const 48 { 49 return col; 50 } 34 int16_t LayoutPosition::Col(void) const { return col; } 51 35 52 36 } // end namespace gui -
trunk/lib/FlairCore/src/LayoutPosition.h
r2 r15 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/lib/FlairCore/src/Map.cpp
r2 r15 27 27 using std::ostringstream; 28 28 29 namespace flair 30 { 31 namespace gui 32 { 29 namespace flair { 30 namespace gui { 33 31 34 32 using namespace core; 35 33 36 Map::Map(const LayoutPosition* position,string name):SendData(position,name,"Map",1000) { 37 size_t i=0; 38 while(1) { 39 double latitude,longitude; 40 double altitude=0; 41 ostringstream lat_prop,long_prop,alt_prop; 42 lat_prop << "lat" << i; 43 long_prop << "long" << i; 44 alt_prop << "alt" << i; 45 if(GetPersistentXmlProp(lat_prop.str(),latitude) && GetPersistentXmlProp(long_prop.str(),longitude)) { 46 SetVolatileXmlProp(lat_prop.str(),latitude); 47 SetVolatileXmlProp(long_prop.str(),longitude); 48 if(GetPersistentXmlProp(alt_prop.str(),altitude)) SetVolatileXmlProp(alt_prop.str(),altitude); 49 GeoCoordinate *checkpoint=new GeoCoordinate(this,"checkpoint",latitude,longitude,altitude); 50 checkpoints.push_back(checkpoint); 51 } else { 52 break; 53 } 54 i++; 34 Map::Map(const LayoutPosition *position, string name) 35 : SendData(position, name, "Map", 1000) { 36 size_t i = 0; 37 while (1) { 38 double latitude, longitude; 39 double altitude = 0; 40 ostringstream lat_prop, long_prop, alt_prop; 41 lat_prop << "lat" << i; 42 long_prop << "long" << i; 43 alt_prop << "alt" << i; 44 if (GetPersistentXmlProp(lat_prop.str(), latitude) && 45 GetPersistentXmlProp(long_prop.str(), longitude)) { 46 SetVolatileXmlProp(lat_prop.str(), latitude); 47 SetVolatileXmlProp(long_prop.str(), longitude); 48 if (GetPersistentXmlProp(alt_prop.str(), altitude)) 49 SetVolatileXmlProp(alt_prop.str(), altitude); 50 GeoCoordinate *checkpoint = 51 new GeoCoordinate(this, "checkpoint", latitude, longitude, altitude); 52 checkpoints.push_back(checkpoint); 53 } else { 54 break; 55 55 } 56 for(size_t i=0;i<checkpoints.size();i++) { 57 double latitude,longitude,altitude; 58 checkpoints.at(i)->GetCoordinates(&latitude,&longitude,&altitude); 59 //printf("%i %f %f\n",i,latitude,longitude); 60 } 56 i++; 57 } 58 for (size_t i = 0; i < checkpoints.size(); i++) { 59 double latitude, longitude, altitude; 60 checkpoints.at(i)->GetCoordinates(&latitude, &longitude, &altitude); 61 // printf("%i %f %f\n",i,latitude,longitude); 62 } 61 63 62 63 /*64 //update value from xml file65 XmlEvent(XmlFileNode());66 if(checkpoints_node.size()!=0) SendXml();//pour les checkpoints64 SendXml(); 65 /* 66 //update value from xml file 67 XmlEvent(XmlFileNode()); 68 if(checkpoints_node.size()!=0) SendXml();//pour les checkpoints 67 69 68 //on enleve les checkpoints du xml69 for(size_t i=0;i<checkpoints_node.size();i++)70 {71 xmlUnlinkNode(checkpoints_node.at(i));72 xmlFreeNode(checkpoints_node.at(i));73 }*/70 //on enleve les checkpoints du xml 71 for(size_t i=0;i<checkpoints_node.size();i++) 72 { 73 xmlUnlinkNode(checkpoints_node.at(i)); 74 xmlFreeNode(checkpoints_node.at(i)); 75 }*/ 74 76 } 75 77 76 Map::~Map() { 77 78 } 78 Map::~Map() {} 79 79 80 80 void Map::ExtraXmlEvent(void) { 81 81 82 //attention pas rt safe (creation checkpoint) 83 size_t i=0; 84 while(1) { 85 //printf("test %i\n",i); 86 double latitude,longitude; 87 double altitude=0; 88 ostringstream lat_prop,long_prop,alt_prop; 89 lat_prop << "lat" << i; 90 long_prop << "long" << i; 91 alt_prop << "alt" << i; 92 if(GetPersistentXmlProp(lat_prop.str(),latitude) && GetPersistentXmlProp(long_prop.str(),longitude)) { 93 GetPersistentXmlProp(alt_prop.str(),altitude); 94 if(i>=checkpoints.size()) { 95 GeoCoordinate *checkpoint=new GeoCoordinate(this,"checkpoint",latitude,longitude,altitude); 96 checkpoints.push_back(checkpoint); 97 //printf("add %i\n",i); 98 } else { 99 checkpoints.at(i)->SetCoordinates(latitude,longitude,altitude); 100 } 101 } else { 102 if(i==checkpoints.size()) break; 103 } 104 i++; 82 // attention pas rt safe (creation checkpoint) 83 size_t i = 0; 84 while (1) { 85 // printf("test %i\n",i); 86 double latitude, longitude; 87 double altitude = 0; 88 ostringstream lat_prop, long_prop, alt_prop; 89 lat_prop << "lat" << i; 90 long_prop << "long" << i; 91 alt_prop << "alt" << i; 92 if (GetPersistentXmlProp(lat_prop.str(), latitude) && 93 GetPersistentXmlProp(long_prop.str(), longitude)) { 94 GetPersistentXmlProp(alt_prop.str(), altitude); 95 if (i >= checkpoints.size()) { 96 GeoCoordinate *checkpoint = new GeoCoordinate( 97 this, "checkpoint", latitude, longitude, altitude); 98 checkpoints.push_back(checkpoint); 99 // printf("add %i\n",i); 100 } else { 101 checkpoints.at(i)->SetCoordinates(latitude, longitude, altitude); 102 } 103 } else { 104 if (i == checkpoints.size()) 105 break; 105 106 } 107 i++; 108 } 106 109 107 for(size_t i=0;i<checkpoints.size();i++) {108 double latitude,longitude,altitude;109 checkpoints.at(i)->GetCoordinates(&latitude,&longitude,&altitude);110 //printf("%i %f %f\n",i,latitude,longitude);111 110 for (size_t i = 0; i < checkpoints.size(); i++) { 111 double latitude, longitude, altitude; 112 checkpoints.at(i)->GetCoordinates(&latitude, &longitude, &altitude); 113 // printf("%i %f %f\n",i,latitude,longitude); 114 } 112 115 } 113 116 114 void Map::AddPoint(const GeoCoordinate * point,string name) {115 SetVolatileXmlProp("point",name);116 117 void Map::AddPoint(const GeoCoordinate *point, string name) { 118 SetVolatileXmlProp("point", name); 119 SendXml(); 117 120 118 119 SetSendSize(to_draw.size()*3*sizeof(double));//lat,long,alt121 to_draw.push_back(point); 122 SetSendSize(to_draw.size() * 3 * sizeof(double)); // lat,long,alt 120 123 } 121 124 122 void Map::CopyDatas(char* buf) const { 123 for(size_t i=0;i<to_draw.size();i++) { 124 double latitude,longitude,altitude; 125 to_draw.at(i)->GetCoordinates(&latitude,&longitude,&altitude); 126 memcpy(buf+i*3*sizeof(double),&latitude,sizeof(double)); 127 memcpy(buf+sizeof(double)+i*3*sizeof(double),&longitude,sizeof(double)); 128 memcpy(buf+2*sizeof(double)+i*3*sizeof(double),&altitude,sizeof(double)); 129 } 125 void Map::CopyDatas(char *buf) const { 126 for (size_t i = 0; i < to_draw.size(); i++) { 127 double latitude, longitude, altitude; 128 to_draw.at(i)->GetCoordinates(&latitude, &longitude, &altitude); 129 memcpy(buf + i * 3 * sizeof(double), &latitude, sizeof(double)); 130 memcpy(buf + sizeof(double) + i * 3 * sizeof(double), &longitude, 131 sizeof(double)); 132 memcpy(buf + 2 * sizeof(double) + i * 3 * sizeof(double), &altitude, 133 sizeof(double)); 134 } 130 135 } 131 136 -
trunk/lib/FlairCore/src/Map.h
r2 r15 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/lib/FlairCore/src/Mutex.cpp
r2 r15 21 21 using std::string; 22 22 23 namespace flair 24 { 25 namespace core 26 { 23 namespace flair { 24 namespace core { 27 25 28 Mutex::Mutex(const Object *parent, string name): Object(parent, name,"mutex")29 {30 pimpl_=new Mutex_impl(this);26 Mutex::Mutex(const Object *parent, string name) 27 : Object(parent, name, "mutex") { 28 pimpl_ = new Mutex_impl(this); 31 29 } 32 30 33 Mutex::~Mutex() 34 { 35 delete pimpl_; 36 } 31 Mutex::~Mutex() { delete pimpl_; } 37 32 38 void Mutex::GetMutex(void) const 39 { 40 pimpl_->GetMutex(); 41 } 33 void Mutex::GetMutex(void) const { pimpl_->GetMutex(); } 42 34 43 void Mutex::ReleaseMutex(void) const 44 { 45 pimpl_->ReleaseMutex(); 46 } 35 void Mutex::ReleaseMutex(void) const { pimpl_->ReleaseMutex(); } 47 36 48 37 /* -
trunk/lib/FlairCore/src/Mutex.h
r2 r15 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/lib/FlairCore/src/Mutex_impl.cpp
r2 r15 23 23 using namespace flair::core; 24 24 25 Mutex_impl::Mutex_impl(Mutex *self) 26 { 27 this->self=self; 25 Mutex_impl::Mutex_impl(Mutex *self) { 26 this->self = self; 28 27 #ifdef __XENO__ 29 int status=rt_mutex_create(&mutex,NULL); 30 if(status!=0) self->Err("rt_mutex_create error (%s)\n",strerror(-status)); 28 int status = rt_mutex_create(&mutex, NULL); 29 if (status != 0) 30 self->Err("rt_mutex_create error (%s)\n", strerror(-status)); 31 31 #else 32 //flag_locked=false;//revoir l'implementation nrt du is_locked 33 pthread_mutexattr_t attr; 34 if(pthread_mutexattr_init(&attr)!=0) 35 { 36 self->Err("pthread_mutexattr_init error\n"); 37 } 38 if(pthread_mutexattr_settype(&attr, PTHREAD_MUTEX_RECURSIVE) != 0) 39 { 40 self->Err("pthread_mutexattr_settype error\n"); 41 } 42 if(pthread_mutex_init(&mutex, &attr)!=0) 43 { 44 self->Err("pthread_mutex_init error\n"); 45 } 46 if(pthread_mutexattr_destroy(&attr)!=0) 47 { 48 self->Err("pthread_mutexattr_destroy error\n"); 49 } 32 // flag_locked=false;//revoir l'implementation nrt du is_locked 33 pthread_mutexattr_t attr; 34 if (pthread_mutexattr_init(&attr) != 0) { 35 self->Err("pthread_mutexattr_init error\n"); 36 } 37 if (pthread_mutexattr_settype(&attr, PTHREAD_MUTEX_RECURSIVE) != 0) { 38 self->Err("pthread_mutexattr_settype error\n"); 39 } 40 if (pthread_mutex_init(&mutex, &attr) != 0) { 41 self->Err("pthread_mutex_init error\n"); 42 } 43 if (pthread_mutexattr_destroy(&attr) != 0) { 44 self->Err("pthread_mutexattr_destroy error\n"); 45 } 50 46 #endif 51 47 } 52 48 53 Mutex_impl::~Mutex_impl() 54 { 55 int status; 49 Mutex_impl::~Mutex_impl() { 50 int status; 56 51 #ifdef __XENO__ 57 status=rt_mutex_delete(&mutex);52 status = rt_mutex_delete(&mutex); 58 53 #else 59 status=pthread_mutex_destroy(&mutex);54 status = pthread_mutex_destroy(&mutex); 60 55 #endif 61 if(status!=0) self->Err("error destroying mutex (%s)\n",strerror(-status)); 56 if (status != 0) 57 self->Err("error destroying mutex (%s)\n", strerror(-status)); 62 58 } 63 59 64 void Mutex_impl::GetMutex(void) 65 { 66 int status; 60 void Mutex_impl::GetMutex(void) { 61 int status; 67 62 #ifdef __XENO__ 68 status=rt_mutex_acquire(&mutex,TM_INFINITE);63 status = rt_mutex_acquire(&mutex, TM_INFINITE); 69 64 #else 70 //flag_locked=true;71 status=pthread_mutex_lock(&mutex);65 // flag_locked=true; 66 status = pthread_mutex_lock(&mutex); 72 67 #endif 73 if(status!=0) self->Err("error (%s)\n",strerror(-status)); 68 if (status != 0) 69 self->Err("error (%s)\n", strerror(-status)); 74 70 } 75 71 76 void Mutex_impl::ReleaseMutex(void) 77 { 78 int status; 72 void Mutex_impl::ReleaseMutex(void) { 73 int status; 79 74 #ifdef __XENO__ 80 status=rt_mutex_release(&mutex);75 status = rt_mutex_release(&mutex); 81 76 #else 82 status=pthread_mutex_unlock(&mutex);83 //flag_locked=false;77 status = pthread_mutex_unlock(&mutex); 78 // flag_locked=false; 84 79 #endif 85 if(status!=0) self->Err("error (%s)\n",strerror(-status)); 80 if (status != 0) 81 self->Err("error (%s)\n", strerror(-status)); 86 82 } 87 83 … … 92 88 RT_MUTEX_INFO info; 93 89 int status=rt_mutex_inquire(&mutex_rt,&info); 94 if(status!=0) mutex->Err("erreur rt_mutex_inquire (%s)\n",strerror(-status)); 90 if(status!=0) mutex->Err("erreur rt_mutex_inquire 91 (%s)\n",strerror(-status)); 95 92 if(info.locked>0) return true; 96 93 return false; -
trunk/lib/FlairCore/src/Object.cpp
r2 r15 33 33 using std::vector; 34 34 35 namespace flair 36 { 37 namespace core 38 { 35 namespace flair { 36 namespace core { 39 37 40 Time GetTime(void) 41 { 38 Time GetTime(void) { 42 39 #ifdef __XENO__ 43 40 return rt_timer_read(); 44 41 #else 45 46 47 return (Time)((Time)(t.tv_sec)*1000000 + (Time)(t.tv_usec))*1000;42 struct timeval t; 43 gettimeofday(&t, NULL); 44 return (Time)((Time)(t.tv_sec) * 1000000 + (Time)(t.tv_usec)) * 1000; 48 45 49 46 #endif 50 47 } 51 48 52 void Printf(const char *format, ...) 53 { 54 va_list args; 55 va_start(args, format); 49 void Printf(const char *format, ...) { 50 va_list args; 51 va_start(args, format); 56 52 #ifdef __XENO__ 57 if(rt_task_self()!=NULL) 58 { 59 rt_vfprintf(stderr,format, args); 60 } 61 else 53 if (rt_task_self() != NULL) { 54 rt_vfprintf(stderr, format, args); 55 } else 62 56 #endif 63 64 vfprintf(stderr,format, args);65 57 { 58 vfprintf(stderr, format, args); 59 } 66 60 67 va_end(args);61 va_end(args); 68 62 } 69 63 70 Object::Object(const Object * parent,string name,string type)71 { 72 pimpl_=new Object_impl(this,parent,name,type);73 if(parent!=NULL)parent->pimpl_->AddChild(this);64 Object::Object(const Object *parent, string name, string type) { 65 pimpl_ = new Object_impl(this, parent, name, type); 66 if (parent != NULL) 67 parent->pimpl_->AddChild(this); 74 68 } 75 69 76 Object::~Object() 77 { 78 if(pimpl_->parent!=NULL)pimpl_->parent->pimpl_->RemoveChild(this);79 70 Object::~Object() { 71 if (pimpl_->parent != NULL) 72 pimpl_->parent->pimpl_->RemoveChild(this); 73 delete pimpl_; 80 74 } 81 75 82 string Object::ObjectName(void) const 83 { 84 return pimpl_->name; 76 string Object::ObjectName(void) const { return pimpl_->name; } 77 78 string Object::ObjectType(void) const { return pimpl_->type; } 79 80 const Object *Object::Parent(void) const { return pimpl_->parent; } 81 82 vector<const Object *> *Object::TypeChilds(void) const { 83 return &(pimpl_->type_childs); 85 84 } 86 85 87 string Object::ObjectType(void) const 88 { 89 return pimpl_->type; 86 vector<const Object *> *Object::Childs(void) const { return &(pimpl_->childs); } 87 88 void Object::ColorPrintf(color_t color, const char *function, int line, 89 const char *format, va_list *args) const { 90 #ifdef __XENO__ 91 if (rt_task_self() != NULL) { 92 rt_fprintf(stderr, "\033[%dm", color); 93 if (line) { 94 rt_fprintf(stderr, "%s - line %d, %s: ", function, line, 95 pimpl_->name.c_str()); 96 } else { 97 rt_fprintf(stderr, "%s, %s: ", function, pimpl_->name.c_str()); 98 } 99 rt_vfprintf(stderr, format, *args); 100 rt_fprintf(stderr, "\033[%dm", color_t::Auto); 101 } else 102 #endif 103 { 104 fprintf(stderr, "\033[%dm", color); 105 if (line) { 106 fprintf(stderr, "%s - line %d, %s: ", function, line, 107 pimpl_->name.c_str()); 108 } else { 109 fprintf(stderr, "%s, %s: ", function, pimpl_->name.c_str()); 110 } 111 vfprintf(stderr, format, *args); 112 fprintf(stderr, "\033[%dm", color_t::Auto); 113 } 90 114 } 91 115 92 const Object* Object::Parent(void) const 93 { 94 return pimpl_->parent; 95 } 96 97 vector<const Object*>* Object::TypeChilds(void) const 98 { 99 return &(pimpl_->type_childs); 100 } 101 102 vector<const Object*>* Object::Childs(void) const 103 { 104 return &(pimpl_->childs); 105 } 106 107 void Object::ColorPrintf(color_t color, const char *function, int line, const char *format,va_list *args) const { 108 #ifdef __XENO__ 109 if(rt_task_self()!=NULL) 110 { 111 rt_fprintf(stderr,"\033[%dm", color); 112 if (line) { 113 rt_fprintf(stderr,"%s - line %d, %s: ", function, line, pimpl_->name.c_str()); 114 } else { 115 rt_fprintf(stderr,"%s, %s: ", function, pimpl_->name.c_str()); 116 } 117 rt_vfprintf(stderr,format, *args); 118 rt_fprintf(stderr,"\033[%dm", color_t::Auto); 119 } 120 else 121 #endif 122 { 123 fprintf(stderr,"\033[%dm", color); 124 if (line) { 125 fprintf(stderr,"%s - line %d, %s: ", function, line, pimpl_->name.c_str()); 126 } else { 127 fprintf(stderr,"%s, %s: ", function, pimpl_->name.c_str()); 128 } 129 vfprintf(stderr,format, *args); 130 fprintf(stderr,"\033[%dm", color_t::Auto); 131 } 132 } 133 134 void Object::Information(const char *function, int line, const char *format, ...) const { 135 va_list args; 136 va_start(args, format); 137 ColorPrintf(color_t::Green, function, line, format, &args); 138 va_end (args); 116 void Object::Information(const char *function, int line, const char *format, 117 ...) const { 118 va_list args; 119 va_start(args, format); 120 ColorPrintf(color_t::Green, function, line, format, &args); 121 va_end(args); 139 122 } 140 123 141 124 void Object::Warning(const char *function, const char *format, ...) const { 142 143 144 145 va_end(args);125 va_list args; 126 va_start(args, format); 127 ColorPrintf(color_t::Orange, function, 0, format, &args); 128 va_end(args); 146 129 } 147 130 148 131 void Object::Error(const char *function, const char *format, ...) const { 149 150 151 152 va_end(args);132 va_list args; 133 va_start(args, format); 134 ColorPrintf(color_t::Red, function, 0, format, &args); 135 va_end(args); 153 136 154 pimpl_->error_occured=true;137 pimpl_->error_occured = true; 155 138 } 156 139 157 bool Object::ErrorOccured(bool recursive) const 158 { 159 return pimpl_->ErrorOccured(recursive); 140 bool Object::ErrorOccured(bool recursive) const { 141 return pimpl_->ErrorOccured(recursive); 160 142 } 161 143 -
trunk/lib/FlairCore/src/Object.h
r2 r15 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/lib/FlairCore/src/Object_impl.cpp
r2 r15 23 23 using namespace flair::core; 24 24 25 Object_impl::Object_impl(const Object * self,const Object* parent,string name,string type)26 {27 //Printf("Object %s\n",name.c_str());28 this->self=self;29 this->parent=parent;30 this->name=name;31 this->type=type;32 error_occured=false;25 Object_impl::Object_impl(const Object *self, const Object *parent, string name, 26 string type) { 27 // Printf("Object %s\n",name.c_str()); 28 this->self = self; 29 this->parent = parent; 30 this->name = name; 31 this->type = type; 32 error_occured = false; 33 33 34 if(parent!=NULL)35 {36 if(name=="") this->name=parent->ObjectName();37 34 if (parent != NULL) { 35 if (name == "") 36 this->name = parent->ObjectName(); 37 } 38 38 } 39 39 40 Object_impl::~Object_impl() 41 { 42 //Printf("destruction Object %s %s\n",name.c_str(),type.c_str()); 40 Object_impl::~Object_impl() { 41 // Printf("destruction Object %s %s\n",name.c_str(),type.c_str()); 43 42 44 while(childs.size()!=0)45 {46 //Printf("child %i %s%s\n",childs.size(),childs.front()->ObjectName().c_str(),childs.front()->ObjectType().c_str());47 //if(childs.front()!=NULL)48 49 43 while (childs.size() != 0) { 44 // Printf("child %i %s 45 // %s\n",childs.size(),childs.front()->ObjectName().c_str(),childs.front()->ObjectType().c_str()); 46 // if(childs.front()!=NULL) 47 delete childs.front(); 48 } 50 49 51 if(type_childs.size()!=0) 52 { 53 type_childs.clear(); 54 self->Warn("type_childs not cleared\n"); 55 } 50 if (type_childs.size() != 0) { 51 type_childs.clear(); 52 self->Warn("type_childs not cleared\n"); 53 } 56 54 57 //Printf("destruction Object %s %s ok\n",name.c_str(),type.c_str());55 // Printf("destruction Object %s %s ok\n",name.c_str(),type.c_str()); 58 56 } 59 57 60 void Object_impl::AddChild(const Object* child) 61 { 62 childs.push_back(child); 63 //self->Printf("added Object %s %s (%s %s)\n",child->ObjectName().c_str(),child->ObjectType().c_str(),name.c_str(),type.c_str()); 64 if(child->ObjectType()==type) type_childs.push_back(child); 58 void Object_impl::AddChild(const Object *child) { 59 childs.push_back(child); 60 // self->Printf("added Object %s %s (%s 61 // %s)\n",child->ObjectName().c_str(),child->ObjectType().c_str(),name.c_str(),type.c_str()); 62 if (child->ObjectType() == type) 63 type_childs.push_back(child); 65 64 } 66 65 67 void Object_impl::RemoveChild(const Object * child)68 { 69 //self->Printf("removed Object %s %s (%s%s)\n",child->ObjectName().c_str(),child->ObjectType().c_str(),name.c_str(),type.c_str());66 void Object_impl::RemoveChild(const Object *child) { 67 // self->Printf("removed Object %s %s (%s 68 // %s)\n",child->ObjectName().c_str(),child->ObjectType().c_str(),name.c_str(),type.c_str()); 70 69 71 for(vector<const Object*>::iterator it=childs.begin() ; it < childs.end(); it++ ) 72 { 73 if(*it==child) 74 { 75 childs.erase (it); 76 break; 77 } 70 for (vector<const Object *>::iterator it = childs.begin(); it < childs.end(); 71 it++) { 72 if (*it == child) { 73 childs.erase(it); 74 break; 78 75 } 76 } 79 77 80 for(vector<const Object*>::iterator it=type_childs.begin() ; it < type_childs.end(); it++ ) 81 { 82 if(*it==child) 83 { 84 type_childs.erase (it); 85 break; 86 } 78 for (vector<const Object *>::iterator it = type_childs.begin(); 79 it < type_childs.end(); it++) { 80 if (*it == child) { 81 type_childs.erase(it); 82 break; 87 83 } 84 } 88 85 } 89 86 90 bool Object_impl::ErrorOccured(bool recursive) 91 { 92 if(recursive==true) 93 { 94 for(size_t i=0;i<childs.size();i++) 95 { 96 if(childs[i]->ErrorOccured(true)==true) 97 { 98 return true; 99 } 100 } 87 bool Object_impl::ErrorOccured(bool recursive) { 88 if (recursive == true) { 89 for (size_t i = 0; i < childs.size(); i++) { 90 if (childs[i]->ErrorOccured(true) == true) { 91 return true; 92 } 101 93 } 102 return error_occured; 94 } 95 return error_occured; 103 96 } -
trunk/lib/FlairCore/src/OneAxisRotation.cpp
r2 r15 16 16 /*********************************************************************/ 17 17 18 // this "filter" is in core but it should be in filter19 // filter depends on sensoractuator20 // sensoractuators depends on oneaxisrotation21 // so if oneaxisrotation is in fiter we have a circular dependency22 // TODO: fix this!18 // this "filter" is in core but it should be in filter 19 // filter depends on sensoractuator 20 // sensoractuators depends on oneaxisrotation 21 // so if oneaxisrotation is in fiter we have a circular dependency 22 // TODO: fix this! 23 23 24 24 #include "OneAxisRotation.h" … … 29 29 using std::string; 30 30 31 namespace flair 32 { 33 namespace core 34 { 31 namespace flair { 32 namespace core { 35 33 36 OneAxisRotation::OneAxisRotation(const gui::LayoutPosition* position,string name): gui::GroupBox(position,name) 37 { 38 pimpl_=new OneAxisRotation_impl(this); 34 OneAxisRotation::OneAxisRotation(const gui::LayoutPosition *position, 35 string name) 36 : gui::GroupBox(position, name) { 37 pimpl_ = new OneAxisRotation_impl(this); 39 38 } 40 39 41 OneAxisRotation::~OneAxisRotation() 42 { 43 delete pimpl_; 40 OneAxisRotation::~OneAxisRotation() { delete pimpl_; } 41 42 void OneAxisRotation::ComputeRotation(Vector3D &vector) const { 43 pimpl_->ComputeRotation(vector); 44 44 } 45 45 46 void OneAxisRotation::ComputeRotation(Vector3D& vector) const 47 { 48 pimpl_->ComputeRotation(vector); 46 void OneAxisRotation::ComputeRotation(Euler &euler) const { 47 pimpl_->ComputeRotation(euler); 49 48 } 50 49 51 void OneAxisRotation::ComputeRotation(Euler& euler) const 52 { 53 pimpl_->ComputeRotation(euler); 50 void OneAxisRotation::ComputeRotation(Quaternion &quaternion) const { 51 pimpl_->ComputeRotation(quaternion); 54 52 } 55 53 56 void OneAxisRotation::ComputeRotation(Quaternion& quaternion) const { 57 pimpl_->ComputeRotation(quaternion); 58 } 59 60 void OneAxisRotation::ComputeRotation(RotationMatrix& matrix) const { 61 pimpl_->ComputeRotation(matrix); 54 void OneAxisRotation::ComputeRotation(RotationMatrix &matrix) const { 55 pimpl_->ComputeRotation(matrix); 62 56 } 63 57 -
trunk/lib/FlairCore/src/OneAxisRotation.h
r2 r15 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/lib/FlairCore/src/OneAxisRotation_impl.cpp
r2 r15 28 28 using namespace flair::gui; 29 29 30 OneAxisRotation_impl::OneAxisRotation_impl(GroupBox * box)31 { 32 rot_value=new DoubleSpinBox(box->NewRow(),"value"," deg",-180.,180.,10.,1);33 rot_axe=new ComboBox(box->LastRowLastCol(),"axis");34 35 36 30 OneAxisRotation_impl::OneAxisRotation_impl(GroupBox *box) { 31 rot_value = 32 new DoubleSpinBox(box->NewRow(), "value", " deg", -180., 180., 10., 1); 33 rot_axe = new ComboBox(box->LastRowLastCol(), "axis"); 34 rot_axe->AddItem("x"); 35 rot_axe->AddItem("y"); 36 rot_axe->AddItem("z"); 37 37 } 38 38 39 OneAxisRotation_impl::~OneAxisRotation_impl() 40 { 39 OneAxisRotation_impl::~OneAxisRotation_impl() {} 41 40 41 // compute rotation of each axis through ComputeRotation(Vector3D& vector) 42 void OneAxisRotation_impl::ComputeRotation(Quaternion &quat) const { 43 Vector3D rot = Vector3D(quat.q1, quat.q2, quat.q3); 44 ComputeRotation(rot); 45 quat.q1 = rot.x; 46 quat.q2 = rot.y; 47 quat.q3 = rot.z; 42 48 } 43 49 44 //compute rotation of each axis through ComputeRotation(Vector3D& vector) 45 void OneAxisRotation_impl::ComputeRotation(Quaternion& quat) const { 46 Vector3D rot=Vector3D(quat.q1,quat.q2,quat.q3); 47 ComputeRotation(rot); 48 quat.q1=rot.x; 49 quat.q2=rot.y; 50 quat.q3=rot.z; 50 void OneAxisRotation_impl::ComputeRotation(RotationMatrix &matrix) const { 51 printf("not yet implemented\n"); 51 52 } 52 53 53 void OneAxisRotation_impl::ComputeRotation(RotationMatrix& matrix) const { 54 printf("not yet implemented\n"); 54 // on utilise la rotation d'un vector pour faire une rotation de repere 55 // d'ou le signe negatif 56 void OneAxisRotation_impl::ComputeRotation(Vector3D &vector) const { 57 switch (rot_axe->CurrentIndex()) { 58 case 0: 59 vector.RotateXDeg(-rot_value->Value()); 60 break; 61 case 1: 62 vector.RotateYDeg(-rot_value->Value()); 63 break; 64 case 2: 65 vector.RotateZDeg(-rot_value->Value()); 66 break; 67 } 55 68 } 56 69 57 //on utilise la rotation d'un vector pour faire une rotation de repere 58 //d'ou le signe negatif 59 void OneAxisRotation_impl::ComputeRotation(Vector3D& vector) const 60 { 61 switch(rot_axe->CurrentIndex()) 62 { 63 case 0: 64 vector.RotateXDeg(-rot_value->Value()); 65 break; 66 case 1: 67 vector.RotateYDeg(-rot_value->Value()); 68 break; 69 case 2: 70 vector.RotateZDeg(-rot_value->Value()); 71 break; 72 } 70 void OneAxisRotation_impl::ComputeRotation(Euler &euler) const { 71 Quaternion quat; 72 euler.ToQuaternion(quat); 73 ComputeRotation(quat); 74 quat.ToEuler(euler); 73 75 } 74 75 void OneAxisRotation_impl::ComputeRotation(Euler& euler) const76 {77 Quaternion quat;78 euler.ToQuaternion(quat);79 ComputeRotation(quat);80 quat.ToEuler(euler);81 }82 -
trunk/lib/FlairCore/src/Picture.cpp
r2 r15 24 24 using std::string; 25 25 26 namespace flair 27 { 28 namespace gui 29 { 26 namespace flair { 27 namespace gui { 30 28 31 29 using namespace core; 32 30 33 Picture::Picture(const LayoutPosition* position,string name,const cvimage *image):SendData(position,name,"Picture",200) 34 { 35 this->image=image; 31 Picture::Picture(const LayoutPosition *position, string name, 32 const cvimage *image) 33 : SendData(position, name, "Picture", 200) { 34 this->image = image; 36 35 37 36 SetSendSize(image->GetDataType().GetSize()); 38 37 39 SetVolatileXmlProp("width",image->GetDataType().GetWidth());40 SetVolatileXmlProp("height",image->GetDataType().GetHeight());41 38 SetVolatileXmlProp("width", image->GetDataType().GetWidth()); 39 SetVolatileXmlProp("height", image->GetDataType().GetHeight()); 40 SendXml(); 42 41 } 43 42 44 Picture::~Picture() 45 { 43 Picture::~Picture() {} 44 45 void Picture::CopyDatas(char *buf) const { 46 if (image != NULL) { 47 image->GetMutex(); 48 memcpy(buf, image->img->imageData, image->GetDataType().GetSize()); 49 image->ReleaseMutex(); 50 } 46 51 } 47 48 49 void Picture::CopyDatas(char* buf) const50 {51 if(image!=NULL)52 {53 image->GetMutex();54 memcpy(buf,image->img->imageData,image->GetDataType().GetSize());55 image->ReleaseMutex();56 }57 }58 59 52 60 53 } // end namespace gui -
trunk/lib/FlairCore/src/Picture.h
r2 r15 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/lib/FlairCore/src/PushButton.cpp
r2 r15 22 22 using std::string; 23 23 24 namespace flair 25 { 26 namespace gui 27 { 24 namespace flair { 25 namespace gui { 28 26 29 PushButton::PushButton(const LayoutPosition * position,string name): Widget(position->getLayout(),name,"PushButton")30 {31 SetVolatileXmlProp("row",position->Row());32 SetVolatileXmlProp("col",position->Col());33 27 PushButton::PushButton(const LayoutPosition *position, string name) 28 : Widget(position->getLayout(), name, "PushButton") { 29 SetVolatileXmlProp("row", position->Row()); 30 SetVolatileXmlProp("col", position->Col()); 31 delete position; 34 32 35 33 SendXml(); 36 34 37 clicked=false;35 clicked = false; 38 36 } 39 37 40 PushButton::~PushButton() 41 { 38 PushButton::~PushButton() {} 42 39 40 void PushButton::XmlEvent(void) { 41 int clic = 0; 42 GetPersistentXmlProp("value", clic); 43 44 if (clic == 1) 45 clicked = true; 43 46 } 44 47 45 void PushButton::XmlEvent(void) 46 { 47 int clic=0; 48 GetPersistentXmlProp("value",clic); 49 50 if(clic==1) clicked=true; 51 } 52 53 bool PushButton::Clicked(void) 54 { 55 if(clicked==true) 56 { 57 clicked=false; 58 return true; 59 } 60 else 61 { 62 return false; 63 } 48 bool PushButton::Clicked(void) { 49 if (clicked == true) { 50 clicked = false; 51 return true; 52 } else { 53 return false; 54 } 64 55 } 65 56 -
trunk/lib/FlairCore/src/PushButton.h
r2 r15 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/lib/FlairCore/src/Quaternion.cpp
r2 r15 26 26 namespace core { 27 27 28 Quaternion::Quaternion(float inQ0, float inQ1,float inQ2,float inQ3):q0(inQ0),q1(inQ1),q2(inQ2),q3(inQ3) {29 }28 Quaternion::Quaternion(float inQ0, float inQ1, float inQ2, float inQ3) 29 : q0(inQ0), q1(inQ1), q2(inQ2), q3(inQ3) {} 30 30 31 Quaternion::~Quaternion() { 32 } 31 Quaternion::~Quaternion() {} 33 32 34 Quaternion &Quaternion::operator=(const Quaternion &quaternion) {35 q0=quaternion.q0;36 q1=quaternion.q1;37 q2=quaternion.q2;38 q3=quaternion.q3;39 33 Quaternion &Quaternion::operator=(const Quaternion &quaternion) { 34 q0 = quaternion.q0; 35 q1 = quaternion.q1; 36 q2 = quaternion.q2; 37 q3 = quaternion.q3; 38 return (*this); 40 39 } 41 40 42 41 float Quaternion::GetNorm(void) const { 43 return sqrt(q0*q0+q1*q1+q2*q2+q3*q3);42 return sqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); 44 43 } 45 44 46 45 void Quaternion::Normalize(void) { 47 float n=GetNorm();48 if(n!=0) {49 q0=q0/n;50 q1=q1/n;51 q2=q2/n;52 q3=q3/n;53 46 float n = GetNorm(); 47 if (n != 0) { 48 q0 = q0 / n; 49 q1 = q1 / n; 50 q2 = q2 / n; 51 q3 = q3 / n; 52 } 54 53 } 55 54 56 55 void Quaternion::Conjugate(void) { 57 q1=-q1;58 q2=-q2;59 q3=-q3;56 q1 = -q1; 57 q2 = -q2; 58 q3 = -q3; 60 59 } 61 60 62 61 Quaternion Quaternion::GetConjugate(void) { 63 return Quaternion(q0,-q1,-q2,-q3);62 return Quaternion(q0, -q1, -q2, -q3); 64 63 } 65 64 66 65 void Quaternion::GetLogarithm(Vector3D &logarithm) { 67 68 float v_norm=sqrtf(q1*q1+q2*q2+q3*q3);66 Normalize(); 67 float v_norm = sqrtf(q1 * q1 + q2 * q2 + q3 * q3); 69 68 70 if(v_norm!=0) {71 72 logarithm.x=(q1*v_arccos)/v_norm;73 logarithm.y=(q2*v_arccos)/v_norm;74 logarithm.z=(q3*v_arccos)/v_norm;75 76 logarithm.x=0;77 logarithm.y=0;78 logarithm.z=0;79 69 if (v_norm != 0) { 70 float v_arccos = acosf(q0); 71 logarithm.x = (q1 * v_arccos) / v_norm; 72 logarithm.y = (q2 * v_arccos) / v_norm; 73 logarithm.z = (q3 * v_arccos) / v_norm; 74 } else { 75 logarithm.x = 0; 76 logarithm.y = 0; 77 logarithm.z = 0; 78 } 80 79 } 81 80 82 81 Vector3D Quaternion::GetLogarithm(void) { 83 84 85 82 Vector3D vector; 83 GetLogarithm(vector); 84 return vector; 86 85 } 87 86 88 87 Quaternion Quaternion::GetDerivative(const Vector3D &angularSpeed) const { 89 const Quaternion Qw(0,angularSpeed.x,angularSpeed.y,angularSpeed.z);90 return 0.5*(*this)*Qw;88 const Quaternion Qw(0, angularSpeed.x, angularSpeed.y, angularSpeed.z); 89 return 0.5 * (*this) * Qw; 91 90 } 92 91 93 92 void Quaternion::Derivate(const Vector3D &angularSpeed) { 94 Quaternion Q=GetDerivative(angularSpeed);95 (*this)=Q;93 Quaternion Q = GetDerivative(angularSpeed); 94 (*this) = Q; 96 95 } 97 96 98 97 void Quaternion::ToEuler(Euler &euler) const { 99 euler.roll=atan2(2*(q0*q1+q2*q3), 1-2*(q1*q1+q2*q2));100 euler.pitch=asin(2*(q0*q2-q1*q3));101 euler.yaw = atan2(2*(q0*q3+q1*q2), 1-2*(q2*q2+q3*q3));98 euler.roll = atan2(2 * (q0 * q1 + q2 * q3), 1 - 2 * (q1 * q1 + q2 * q2)); 99 euler.pitch = asin(2 * (q0 * q2 - q1 * q3)); 100 euler.yaw = atan2(2 * (q0 * q3 + q1 * q2), 1 - 2 * (q2 * q2 + q3 * q3)); 102 101 } 103 102 104 103 Euler Quaternion::ToEuler(void) const { 105 106 107 104 Euler euler; 105 ToEuler(euler); 106 return euler; 108 107 } 109 108 110 109 void Quaternion::ToRotationMatrix(RotationMatrix &matrix) const { 111 112 113 114 115 116 117 118 119 120 121 122 123 110 float aSq = q0 * q0; 111 float bSq = q1 * q1; 112 float cSq = q2 * q2; 113 float dSq = q3 * q3; 114 matrix.m[0][0] = aSq + bSq - cSq - dSq; 115 matrix.m[0][1] = 2.0f * (q1 * q2 - q0 * q3); 116 matrix.m[0][2] = 2.0f * (q0 * q2 + q1 * q3); 117 matrix.m[1][0] = 2.0f * (q1 * q2 + q0 * q3); 118 matrix.m[1][1] = aSq - bSq + cSq - dSq; 119 matrix.m[1][2] = 2.0f * (q2 * q3 - q0 * q1); 120 matrix.m[2][0] = 2.0f * (q1 * q3 - q0 * q2); 121 matrix.m[2][1] = 2.0f * (q0 * q1 + q2 * q3); 122 matrix.m[2][2] = aSq - bSq - cSq + dSq; 124 123 } 125 124 126 125 Quaternion &Quaternion::operator+=(const Quaternion &quaternion) { 127 q0+=quaternion.q0;128 q1+=quaternion.q1;129 q2+=quaternion.q2;130 q3+=quaternion.q3;131 126 q0 += quaternion.q0; 127 q1 += quaternion.q1; 128 q2 += quaternion.q2; 129 q3 += quaternion.q3; 130 return (*this); 132 131 } 133 132 134 133 Quaternion &Quaternion::operator-=(const Quaternion &quaternion) { 135 q0-=quaternion.q0;136 q1-=quaternion.q1;137 q2-=quaternion.q2;138 q3-=quaternion.q3;139 134 q0 -= quaternion.q0; 135 q1 -= quaternion.q1; 136 q2 -= quaternion.q2; 137 q3 -= quaternion.q3; 138 return (*this); 140 139 } 141 140 142 Quaternion operator + (const Quaternion &quaternionA,const Quaternion &quaterniontB) { 143 return Quaternion( 144 quaternionA.q0 + quaterniontB.q0, 145 quaternionA.q1 + quaterniontB.q1, 146 quaternionA.q2 + quaterniontB.q2, 147 quaternionA.q3 + quaterniontB.q3); 141 Quaternion operator+(const Quaternion &quaternionA, 142 const Quaternion &quaterniontB) { 143 return Quaternion( 144 quaternionA.q0 + quaterniontB.q0, quaternionA.q1 + quaterniontB.q1, 145 quaternionA.q2 + quaterniontB.q2, quaternionA.q3 + quaterniontB.q3); 148 146 } 149 147 150 Quaternion operator- (const Quaternion &quaterniontA,const Quaternion &quaterniontB) { 151 return Quaternion( 152 quaterniontA.q0 - quaterniontB.q0, 153 quaterniontA.q1 - quaterniontB.q1, 154 quaterniontA.q2 - quaterniontB.q2, 155 quaterniontA.q3 - quaterniontB.q3); 148 Quaternion operator-(const Quaternion &quaterniontA, 149 const Quaternion &quaterniontB) { 150 return Quaternion( 151 quaterniontA.q0 - quaterniontB.q0, quaterniontA.q1 - quaterniontB.q1, 152 quaterniontA.q2 - quaterniontB.q2, quaterniontA.q3 - quaterniontB.q3); 156 153 } 157 154 158 155 Quaternion operator-(const Quaternion &quaternion) { 159 return Quaternion(-quaternion.q0,-quaternion.q1,-quaternion.q2,-quaternion.q3); 156 return Quaternion(-quaternion.q0, -quaternion.q1, -quaternion.q2, 157 -quaternion.q3); 160 158 } 161 159 162 Quaternion operator * (const Quaternion &quaterniontA,const Quaternion &quaterniontB) { 163 return Quaternion( 164 quaterniontA.q0 * quaterniontB.q0 - quaterniontA.q1 * quaterniontB.q1 - quaterniontA.q2 * quaterniontB.q2 - quaterniontA.q3 * quaterniontB.q3, 165 quaterniontA.q0 * quaterniontB.q1 + quaterniontA.q1 * quaterniontB.q0 + quaterniontA.q2 * quaterniontB.q3 - quaterniontA.q3 * quaterniontB.q2, 166 quaterniontA.q0 * quaterniontB.q2 - quaterniontA.q1 * quaterniontB.q3 + quaterniontA.q2 * quaterniontB.q0 + quaterniontA.q3 * quaterniontB.q1, 167 quaterniontA.q0 * quaterniontB.q3 + quaterniontA.q1 * quaterniontB.q2 - quaterniontA.q2 * quaterniontB.q1 + quaterniontA.q3 * quaterniontB.q0); 160 Quaternion operator*(const Quaternion &quaterniontA, 161 const Quaternion &quaterniontB) { 162 return Quaternion( 163 quaterniontA.q0 * quaterniontB.q0 - quaterniontA.q1 * quaterniontB.q1 - 164 quaterniontA.q2 * quaterniontB.q2 - quaterniontA.q3 * quaterniontB.q3, 165 quaterniontA.q0 * quaterniontB.q1 + quaterniontA.q1 * quaterniontB.q0 + 166 quaterniontA.q2 * quaterniontB.q3 - quaterniontA.q3 * quaterniontB.q2, 167 quaterniontA.q0 * quaterniontB.q2 - quaterniontA.q1 * quaterniontB.q3 + 168 quaterniontA.q2 * quaterniontB.q0 + quaterniontA.q3 * quaterniontB.q1, 169 quaterniontA.q0 * quaterniontB.q3 + quaterniontA.q1 * quaterniontB.q2 - 170 quaterniontA.q2 * quaterniontB.q1 + 171 quaterniontA.q3 * quaterniontB.q0); 168 172 } 169 173 170 Quaternion operator * (float coeff,const Quaternion &quaternion) { 171 return Quaternion( 172 coeff*quaternion.q0, 173 coeff*quaternion.q1, 174 coeff*quaternion.q2, 175 coeff*quaternion.q3); 174 Quaternion operator*(float coeff, const Quaternion &quaternion) { 175 return Quaternion(coeff * quaternion.q0, coeff * quaternion.q1, 176 coeff * quaternion.q2, coeff * quaternion.q3); 176 177 } 177 178 178 179 Quaternion operator * (const Quaternion &quaternion,float coeff) { 180 return Quaternion( 181 coeff*quaternion.q0, 182 coeff*quaternion.q1, 183 coeff*quaternion.q2, 184 coeff*quaternion.q3); 179 Quaternion operator*(const Quaternion &quaternion, float coeff) { 180 return Quaternion(coeff * quaternion.q0, coeff * quaternion.q1, 181 coeff * quaternion.q2, coeff * quaternion.q3); 185 182 } 186 183 -
trunk/lib/FlairCore/src/Quaternion.h
r2 r15 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/lib/FlairCore/src/RTDM_I2cPort.cpp
r2 r15 26 26 using std::string; 27 27 28 namespace flair 29 { 30 namespace core 31 { 28 namespace flair { 29 namespace core { 32 30 33 RTDM_I2cPort::RTDM_I2cPort(const Object * parent,string name,string device) : I2cPort(parent,name)34 {35 int err=0;36 31 RTDM_I2cPort::RTDM_I2cPort(const Object *parent, string name, string device) 32 : I2cPort(parent, name) { 33 int err = 0; 34 struct rti2c_config write_config; 37 35 38 //printf("i2c integer le mutex dans le driver, avec acces ioctl\n"); 39 fd = rt_dev_open(device.c_str(), 0); 40 if (fd < 0) 41 { 42 Err("rt_dev_open (%s)\n",ObjectName().c_str(),strerror(-fd)); 43 } 36 // printf("i2c integer le mutex dans le driver, avec acces ioctl\n"); 37 fd = rt_dev_open(device.c_str(), 0); 38 if (fd < 0) { 39 Err("rt_dev_open (%s)\n", ObjectName().c_str(), strerror(-fd)); 40 } 44 41 45 write_config.config_mask = RTI2C_SET_BAUD|RTI2C_SET_TIMEOUT_RX|RTI2C_SET_TIMEOUT_TX; 46 write_config.baud_rate = 400000; 47 write_config.rx_timeout = 500000; 48 write_config.tx_timeout = 1000000;//5ms pour les xbldc, normalement 1ms 49 // the rest implicitely remains default 42 write_config.config_mask = 43 RTI2C_SET_BAUD | RTI2C_SET_TIMEOUT_RX | RTI2C_SET_TIMEOUT_TX; 44 write_config.baud_rate = 400000; 45 write_config.rx_timeout = 500000; 46 write_config.tx_timeout = 1000000; // 5ms pour les xbldc, normalement 1ms 47 // the rest implicitely remains default 50 48 51 52 err = rt_dev_ioctl(fd, RTI2C_RTIOC_SET_CONFIG, &write_config);53 if (err) 54 { 55 Err("rt_dev_ioctl RTI2C_RTIOC_SET_CONFIG error (%s)\n",ObjectName().c_str(),strerror(-err));56 49 // config 50 err = rt_dev_ioctl(fd, RTI2C_RTIOC_SET_CONFIG, &write_config); 51 if (err) { 52 Err("rt_dev_ioctl RTI2C_RTIOC_SET_CONFIG error (%s)\n", 53 ObjectName().c_str(), strerror(-err)); 54 } 57 55 } 58 56 59 RTDM_I2cPort::~RTDM_I2cPort() 60 { 61 rt_dev_close(fd); 57 RTDM_I2cPort::~RTDM_I2cPort() { rt_dev_close(fd); } 58 59 int RTDM_I2cPort::SetSlave(uint16_t address) { 60 int err = rt_dev_ioctl(fd, RTI2C_RTIOC_SET_SLAVE, &address); 61 if (err) { 62 Err("rt_dev_ioctl RTI2C_RTIOC_SET_SLAVE error (%s)\n", strerror(-err)); 63 } 64 65 return err; 62 66 } 63 67 64 int RTDM_I2cPort::SetSlave(uint16_t address) 65 { 66 int err = rt_dev_ioctl(fd, RTI2C_RTIOC_SET_SLAVE, &address); 67 if (err) 68 { 69 Err("rt_dev_ioctl RTI2C_RTIOC_SET_SLAVE error (%s)\n",strerror(-err)); 70 } 68 void RTDM_I2cPort::SetRxTimeout(Time timeout_ns) { 69 struct rti2c_config write_config; 71 70 72 return err; 71 write_config.config_mask = RTI2C_SET_TIMEOUT_RX; 72 write_config.rx_timeout = timeout_ns; 73 74 int err = rt_dev_ioctl(fd, RTI2C_RTIOC_SET_CONFIG, &write_config); 75 if (err) { 76 Err("rt_dev_ioctl RTI2C_RTIOC_SET_CONFIG (%s)\n", ObjectName().c_str(), 77 strerror(-err)); 78 } 73 79 } 74 80 75 void RTDM_I2cPort::SetRxTimeout(Time timeout_ns) 76 { 77 struct rti2c_config write_config; 81 void RTDM_I2cPort::SetTxTimeout(Time timeout_ns) { 82 struct rti2c_config write_config; 78 83 79 write_config.config_mask = RTI2C_SET_TIMEOUT_RX;80 write_config.rx_timeout= timeout_ns;84 write_config.config_mask = RTI2C_SET_TIMEOUT_TX; 85 write_config.tx_timeout = timeout_ns; 81 86 82 int err = rt_dev_ioctl(fd, RTI2C_RTIOC_SET_CONFIG, &write_config);83 if (err) 84 { 85 Err("rt_dev_ioctl RTI2C_RTIOC_SET_CONFIG (%s)\n",ObjectName().c_str(),strerror(-err));86 87 int err = rt_dev_ioctl(fd, RTI2C_RTIOC_SET_CONFIG, &write_config); 88 if (err) { 89 Err("rt_dev_ioctl RTI2C_RTIOC_SET_CONFIG (%s)\n", ObjectName().c_str(), 90 strerror(-err)); 91 } 87 92 } 88 93 89 void RTDM_I2cPort::SetTxTimeout(Time timeout_ns) 90 { 91 struct rti2c_config write_config; 92 93 write_config.config_mask = RTI2C_SET_TIMEOUT_TX; 94 write_config.tx_timeout = timeout_ns; 95 96 int err = rt_dev_ioctl(fd, RTI2C_RTIOC_SET_CONFIG, &write_config ); 97 if (err) 98 { 99 Err("rt_dev_ioctl RTI2C_RTIOC_SET_CONFIG (%s)\n",ObjectName().c_str(),strerror(-err)); 100 } 94 ssize_t RTDM_I2cPort::Write(const void *buf, size_t nbyte) { 95 return rt_dev_write(fd, buf, nbyte); 101 96 } 102 97 103 ssize_t RTDM_I2cPort::Write(const void *buf,size_t nbyte) 104 { 105 return rt_dev_write(fd, buf, nbyte); 106 } 107 108 ssize_t RTDM_I2cPort::Read(void *buf,size_t nbyte) 109 { 110 return rt_dev_read(fd, buf, nbyte); 98 ssize_t RTDM_I2cPort::Read(void *buf, size_t nbyte) { 99 return rt_dev_read(fd, buf, nbyte); 111 100 } 112 101 … … 119 108 using namespace flair::core; 120 109 110 namespace flair { 111 namespace core { 121 112 122 namespace flair 123 { 124 namespace core 125 { 126 127 RTDM_I2cPort::RTDM_I2cPort(const Object* parent,string name,string device) : I2cPort(parent,name) 128 { 129 Err("not available in non real time\n"); 113 RTDM_I2cPort::RTDM_I2cPort(const Object *parent, string name, string device) 114 : I2cPort(parent, name) { 115 Err("not available in non real time\n"); 130 116 } 131 117 132 RTDM_I2cPort::~RTDM_I2cPort() 133 { 118 RTDM_I2cPort::~RTDM_I2cPort() {} 134 119 135 }120 int RTDM_I2cPort::SetSlave(uint16_t address) { return -1; } 136 121 137 int RTDM_I2cPort::SetSlave(uint16_t address) 138 { 139 return -1; 140 } 122 void RTDM_I2cPort::SetRxTimeout(Time timeout_ns) {} 141 123 142 void RTDM_I2cPort::SetRxTimeout(Time timeout_ns) 143 { 144 } 124 void RTDM_I2cPort::SetTxTimeout(Time timeout_ns) {} 145 125 146 void RTDM_I2cPort::SetTxTimeout(Time timeout_ns) 147 { 148 } 126 ssize_t RTDM_I2cPort::Write(const void *buf, size_t nbyte) { return -1; } 149 127 150 ssize_t RTDM_I2cPort::Write(const void *buf,size_t nbyte) 151 { 152 return -1; 153 } 154 155 ssize_t RTDM_I2cPort::Read(void *buf,size_t nbyte) 156 { 157 return -1; 158 } 128 ssize_t RTDM_I2cPort::Read(void *buf, size_t nbyte) { return -1; } 159 129 160 130 } // end namespace core -
trunk/lib/FlairCore/src/RTDM_I2cPort.h
r2 r15 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/lib/FlairCore/src/RTDM_SerialPort.cpp
r2 r15 26 26 using std::string; 27 27 28 namespace flair 29 { 30 namespace core 31 { 28 namespace flair { 29 namespace core { 32 30 33 RTDM_SerialPort::RTDM_SerialPort(const Object* parent,string name,string device) : SerialPort(parent,name) 34 { 35 struct rtser_config write_config; 31 RTDM_SerialPort::RTDM_SerialPort(const Object *parent, string name, 32 string device) 33 : SerialPort(parent, name) { 34 struct rtser_config write_config; 36 35 37 write_config.config_mask= RTSER_SET_BAUD | RTSER_SET_TIMESTAMP_HISTORY,38 write_config.baud_rate= 115200,39 40 36 write_config.config_mask = RTSER_SET_BAUD | RTSER_SET_TIMESTAMP_HISTORY, 37 write_config.baud_rate = 115200, 38 write_config.timestamp_history = RTSER_DEF_TIMESTAMP_HISTORY, 39 // the rest implicitely remains default 41 40 42 fd = rt_dev_open(device.c_str(), 0); 43 if (fd < 0) 44 { 45 Err("erreur rt_dev_open (%s)\n",strerror(-fd)); 46 } 41 fd = rt_dev_open(device.c_str(), 0); 42 if (fd < 0) { 43 Err("erreur rt_dev_open (%s)\n", strerror(-fd)); 44 } 47 45 48 // config 49 int err = rt_dev_ioctl(fd, RTSER_RTIOC_SET_CONFIG, &write_config ); 50 if (err) 51 { 52 Err("erreur rt_dev_ioctl RTSER_RTIOC_SET_CONFIG (%s)\n",strerror(-err)); 53 } 46 // config 47 int err = rt_dev_ioctl(fd, RTSER_RTIOC_SET_CONFIG, &write_config); 48 if (err) { 49 Err("erreur rt_dev_ioctl RTSER_RTIOC_SET_CONFIG (%s)\n", strerror(-err)); 50 } 54 51 } 55 52 56 RTDM_SerialPort::~RTDM_SerialPort() 57 { 58 rt_dev_close(fd); 53 RTDM_SerialPort::~RTDM_SerialPort() { rt_dev_close(fd); } 54 55 void RTDM_SerialPort::SetBaudrate(int baudrate) { 56 struct rtser_config write_config; 57 58 write_config.config_mask = RTSER_SET_BAUD; 59 write_config.baud_rate = baudrate; 60 // the rest implicitely remains default 61 62 // config 63 int err = rt_dev_ioctl(fd, RTSER_RTIOC_SET_CONFIG, &write_config); 64 if (err) { 65 Err("erreur rt_dev_ioctl RTSER_RTIOC_SET_CONFIG (%s)\n", strerror(-err)); 66 } 59 67 } 60 68 61 void RTDM_SerialPort::SetBaudrate(int baudrate) 62 { 63 struct rtser_config write_config; 69 void RTDM_SerialPort::SetRxTimeout(core::Time timeout_ns) { 70 struct rtser_config write_config; 64 71 65 write_config.config_mask = RTSER_SET_BAUD;66 write_config.baud_rate = baudrate;67 72 write_config.config_mask = RTSER_SET_TIMEOUT_RX; 73 write_config.rx_timeout = timeout_ns; 74 // the rest implicitely remains default 68 75 69 // config 70 int err = rt_dev_ioctl(fd, RTSER_RTIOC_SET_CONFIG, &write_config ); 71 if (err) 72 { 73 Err("erreur rt_dev_ioctl RTSER_RTIOC_SET_CONFIG (%s)\n",strerror(-err)); 74 } 76 // config 77 int err = rt_dev_ioctl(fd, RTSER_RTIOC_SET_CONFIG, &write_config); 78 if (err) { 79 Err("erreur rt_dev_ioctl RTSER_RTIOC_SET_CONFIG (%s)\n", strerror(-err)); 80 } 75 81 } 76 82 77 void RTDM_SerialPort::SetRxTimeout(core::Time timeout_ns) 78 { 79 struct rtser_config write_config; 83 void RTDM_SerialPort::FlushInput(void) { 84 char tmp; 80 85 81 write_config.config_mask = RTSER_SET_TIMEOUT_RX; 82 write_config.rx_timeout = timeout_ns; 83 // the rest implicitely remains default 84 85 // config 86 int err = rt_dev_ioctl(fd, RTSER_RTIOC_SET_CONFIG, &write_config ); 87 if (err) 88 { 89 Err("erreur rt_dev_ioctl RTSER_RTIOC_SET_CONFIG (%s)\n",strerror(-err)); 90 } 86 SetRxTimeout(1000000); 87 while (rt_dev_read(fd, &tmp, 1) == 1) 88 ; 89 SetRxTimeout(TIME_INFINITE); 91 90 } 92 91 93 void RTDM_SerialPort::FlushInput(void) 94 { 95 char tmp; 96 97 SetRxTimeout(1000000); 98 while(rt_dev_read(fd,&tmp,1)==1); 99 SetRxTimeout(TIME_INFINITE); 92 ssize_t RTDM_SerialPort::Write(const void *buf, size_t nbyte) { 93 return rt_dev_write(fd, buf, nbyte); 100 94 } 101 95 102 ssize_t RTDM_SerialPort::Write(const void *buf,size_t nbyte) 103 { 104 return rt_dev_write(fd, buf, nbyte); 105 } 106 107 ssize_t RTDM_SerialPort::Read(void *buf,size_t nbyte) 108 { 109 return rt_dev_read(fd, buf, nbyte); 96 ssize_t RTDM_SerialPort::Read(void *buf, size_t nbyte) { 97 return rt_dev_read(fd, buf, nbyte); 110 98 } 111 99 … … 118 106 using namespace flair::core; 119 107 108 namespace flair { 109 namespace core { 120 110 121 namespace flair 122 { 123 namespace core 124 { 125 126 RTDM_SerialPort::RTDM_SerialPort(const Object* parent,string name,string device) : SerialPort(parent,name) 127 { 128 Err("not available in non real time\n"); 111 RTDM_SerialPort::RTDM_SerialPort(const Object *parent, string name, 112 string device) 113 : SerialPort(parent, name) { 114 Err("not available in non real time\n"); 129 115 } 130 116 131 RTDM_SerialPort::~RTDM_SerialPort() 132 { 117 RTDM_SerialPort::~RTDM_SerialPort() {} 133 118 134 }119 ssize_t RTDM_SerialPort::Write(const void *buf, size_t nbyte) { return -1; } 135 120 136 ssize_t RTDM_SerialPort::Write(const void *buf,size_t nbyte) 137 { 138 return -1; 139 } 121 ssize_t RTDM_SerialPort::Read(void *buf, size_t nbyte) { return -1; } 140 122 141 ssize_t RTDM_SerialPort::Read(void *buf,size_t nbyte) 142 { 143 return -1; 144 } 123 void RTDM_SerialPort::SetBaudrate(int baudrate) {} 145 124 146 void RTDM_SerialPort::SetBaudrate(int baudrate) 147 { 148 } 125 void RTDM_SerialPort::SetRxTimeout(core::Time timeout_ns) {} 149 126 150 void RTDM_SerialPort::SetRxTimeout(core::Time timeout_ns) 151 { 152 } 153 154 void RTDM_SerialPort::FlushInput(void) 155 { 156 } 127 void RTDM_SerialPort::FlushInput(void) {} 157 128 158 129 } // end namespace core -
trunk/lib/FlairCore/src/RTDM_SerialPort.h
r2 r15 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/lib/FlairCore/src/RangeFinderPlot.cpp
r2 r15 11 11 // version: $Id: $ 12 12 // 13 // purpose: Class displaying a 2D plot on the ground station for laser range finder like Hokuyo 13 // purpose: Class displaying a 2D plot on the ground station for laser range 14 // finder like Hokuyo 14 15 // 15 16 // … … 26 27 using namespace flair::core; 27 28 28 namespace flair { namespace gui { 29 namespace flair { 30 namespace gui { 29 31 30 RangeFinderPlot::RangeFinderPlot(const LayoutPosition* position,string name, 31 string x_name,float xmin,float xmax, 32 string y_name,float ymin,float ymax, 33 const cvmatrix* datas,float start_angle,float end_angle,uint32_t nb_samples): 34 SendData(position,name,"RangeFinderPlot",200) { 35 this->datas=datas; 32 RangeFinderPlot::RangeFinderPlot(const LayoutPosition *position, string name, 33 string x_name, float xmin, float xmax, 34 string y_name, float ymin, float ymax, 35 const cvmatrix *datas, float start_angle, 36 float end_angle, uint32_t nb_samples) 37 : SendData(position, name, "RangeFinderPlot", 200) { 38 this->datas = datas; 36 39 37 40 SetSendSize(datas->GetDataType().GetSize()); 38 41 39 SetVolatileXmlProp("xmin",xmin); 40 SetVolatileXmlProp("xmax",xmax); 41 SetVolatileXmlProp("ymin",ymin); 42 SetVolatileXmlProp("ymax",ymax); 43 SetVolatileXmlProp("x_name",x_name); 44 SetVolatileXmlProp("y_name",y_name); 45 SetVolatileXmlProp("start_angle",start_angle); 46 SetVolatileXmlProp("end_angle",end_angle); 47 SetVolatileXmlProp("nb_samples",nb_samples); 48 SetVolatileXmlProp("type",datas->GetDataType().GetElementDataType().GetDescription()); 49 SendXml(); 42 SetVolatileXmlProp("xmin", xmin); 43 SetVolatileXmlProp("xmax", xmax); 44 SetVolatileXmlProp("ymin", ymin); 45 SetVolatileXmlProp("ymax", ymax); 46 SetVolatileXmlProp("x_name", x_name); 47 SetVolatileXmlProp("y_name", y_name); 48 SetVolatileXmlProp("start_angle", start_angle); 49 SetVolatileXmlProp("end_angle", end_angle); 50 SetVolatileXmlProp("nb_samples", nb_samples); 51 SetVolatileXmlProp( 52 "type", datas->GetDataType().GetElementDataType().GetDescription()); 53 SendXml(); 50 54 51 if(datas->Cols()!=1 || datas->Rows()!=nb_samples) Err("Wrong input matrix size\n"); 55 if (datas->Cols() != 1 || datas->Rows() != nb_samples) 56 Err("Wrong input matrix size\n"); 52 57 } 53 58 54 59 RangeFinderPlot::~RangeFinderPlot() {} 55 60 56 void RangeFinderPlot::CopyDatas(char *buf) const {57 58 memcpy(buf,datas->getCvMat()->data.ptr,datas->GetDataType().GetSize());59 61 void RangeFinderPlot::CopyDatas(char *buf) const { 62 datas->GetMutex(); 63 memcpy(buf, datas->getCvMat()->data.ptr, datas->GetDataType().GetSize()); 64 datas->ReleaseMutex(); 60 65 } 61 66 -
trunk/lib/FlairCore/src/RangeFinderPlot.h
r2 r15 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/lib/FlairCore/src/RotationMatrix.cpp
r2 r15 21 21 #include "math.h" 22 22 23 namespace flair 24 { 25 namespace core 26 { 23 namespace flair { 24 namespace core { 27 25 28 26 RotationMatrix::RotationMatrix() { 29 for(int i=0;i<3;i++) { 30 for(int j=0;j<3;j++) { 31 if(i==j) { 32 m[i][j]=1; 33 }else { 34 m[i][j]=0; 35 } 36 } 27 for (int i = 0; i < 3; i++) { 28 for (int j = 0; j < 3; j++) { 29 if (i == j) { 30 m[i][j] = 1; 31 } else { 32 m[i][j] = 0; 33 } 37 34 } 35 } 38 36 } 39 37 40 RotationMatrix::~RotationMatrix() { 41 42 } 38 RotationMatrix::~RotationMatrix() {} 43 39 44 40 void RotationMatrix::ToEuler(Euler &euler) const { 45 euler.roll=atanf(m[1][2]/m[2][2]);46 euler.pitch=asinf(-m[0][2]);47 euler.yaw=atan2f(m[0][1],m[0][0]);41 euler.roll = atanf(m[1][2] / m[2][2]); 42 euler.pitch = asinf(-m[0][2]); 43 euler.yaw = atan2f(m[0][1], m[0][0]); 48 44 } 49 45 50 46 Euler RotationMatrix::ToEuler(void) const { 51 52 53 47 Euler euler; 48 ToEuler(euler); 49 return euler; 54 50 } 55 51 56 float & RotationMatrix::operator()(size_t row,size_t col) {57 if(row<3 && col<3) {58 59 60 Printf("RotationMatrix: index (%i,%i) out of bound\n",row,col);61 62 52 float &RotationMatrix::operator()(size_t row, size_t col) { 53 if (row < 3 && col < 3) { 54 return m[row][col]; 55 } else { 56 Printf("RotationMatrix: index (%i,%i) out of bound\n", row, col); 57 return m[2][2]; 58 } 63 59 } 64 60 65 const float & RotationMatrix::operator()(size_t row,size_t col) const {66 if(row<3 && col<3) {67 68 69 Printf("RotationMatrix: index (%i,%i) out of bound\n",row,col);70 71 61 const float &RotationMatrix::operator()(size_t row, size_t col) const { 62 if (row < 3 && col < 3) { 63 return m[row][col]; 64 } else { 65 Printf("RotationMatrix: index (%i,%i) out of bound\n", row, col); 66 return m[2][2]; 67 } 72 68 } 73 69 -
trunk/lib/FlairCore/src/RotationMatrix.h
r2 r15 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/lib/FlairCore/src/SendData.cpp
r2 r15 26 26 using namespace flair::core; 27 27 28 namespace flair 29 { 30 namespace gui 31 { 28 namespace flair { 29 namespace gui { 32 30 33 SendData::SendData(const LayoutPosition* position,string name,string type,uint16_t default_periodms,bool default_enabled) :Widget(position->getLayout(),name,type) { 34 pimpl_=new SendData_impl(); 31 SendData::SendData(const LayoutPosition *position, string name, string type, 32 uint16_t default_periodms, bool default_enabled) 33 : Widget(position->getLayout(), name, type) { 34 pimpl_ = new SendData_impl(); 35 35 36 pimpl_->send_size=0;36 pimpl_->send_size = 0; 37 37 38 //default refesh rate: (ms)39 pimpl_->send_period=default_periodms;40 pimpl_->is_enabled=default_enabled;38 // default refesh rate: (ms) 39 pimpl_->send_period = default_periodms; 40 pimpl_->is_enabled = default_enabled; 41 41 42 SetVolatileXmlProp("row",position->Row());43 SetVolatileXmlProp("col",position->Col());44 GetPersistentXmlProp("period",pimpl_->send_period);45 SetPersistentXmlProp("period",pimpl_->send_period);46 GetPersistentXmlProp("enabled",pimpl_->is_enabled);47 SetPersistentXmlProp("enabled",pimpl_->is_enabled);42 SetVolatileXmlProp("row", position->Row()); 43 SetVolatileXmlProp("col", position->Col()); 44 GetPersistentXmlProp("period", pimpl_->send_period); 45 SetPersistentXmlProp("period", pimpl_->send_period); 46 GetPersistentXmlProp("enabled", pimpl_->is_enabled); 47 SetPersistentXmlProp("enabled", pimpl_->is_enabled); 48 48 49 49 delete position; 50 50 51 if(getUiCom()!=NULL) {52 //register SendData for sending to ground station53 54 //resume if necessary55 56 51 if (getUiCom() != NULL) { 52 // register SendData for sending to ground station 53 getUiCom()->AddSendData(this); 54 // resume if necessary 55 getUiCom()->UpdateSendData(this); 56 } 57 57 } 58 58 59 59 SendData::~SendData() { 60 if(getUiCom()!=NULL) {61 //unregister SendData for sending to ground station62 63 60 if (getUiCom() != NULL) { 61 // unregister SendData for sending to ground station 62 getUiCom()->RemoveSendData(this); 63 } 64 64 65 65 delete pimpl_; 66 66 } 67 67 68 68 void SendData::XmlEvent(void) { 69 70 71 bool something_changed=false;69 uint16_t send_period; 70 bool is_enabled; 71 bool something_changed = false; 72 72 73 if(GetPersistentXmlProp("period",send_period) && GetPersistentXmlProp("enabled",is_enabled)) { 74 if(send_period!=SendPeriod()) something_changed=true; 75 if(is_enabled!=IsEnabled()) something_changed=true; 76 } 73 if (GetPersistentXmlProp("period", send_period) && 74 GetPersistentXmlProp("enabled", is_enabled)) { 75 if (send_period != SendPeriod()) 76 something_changed = true; 77 if (is_enabled != IsEnabled()) 78 something_changed = true; 79 } 77 80 78 if(something_changed) {79 81 if (something_changed) { 82 getFrameworkManager()->BlockCom(); 80 83 81 82 84 SetSendPeriod(send_period); 85 SetEnabled(is_enabled); 83 86 84 87 getFrameworkManager()->UpdateSendData(this); 85 88 86 //ack pour la station sol87 //period and enabled are already in persistent prop88 SetVolatileXmlProp("period",send_period);89 SetVolatileXmlProp("enabled",is_enabled);90 89 // ack pour la station sol 90 // period and enabled are already in persistent prop 91 SetVolatileXmlProp("period", send_period); 92 SetVolatileXmlProp("enabled", is_enabled); 93 SendXml(); 91 94 92 93 95 getFrameworkManager()->UnBlockCom(); 96 } 94 97 95 98 ExtraXmlEvent(); 96 99 } 97 100 98 size_t SendData::SendSize(void) const { 99 return pimpl_->send_size; 101 size_t SendData::SendSize(void) const { return pimpl_->send_size; } 102 103 uint16_t SendData::SendPeriod(void) const { return pimpl_->send_period; } 104 105 bool SendData::IsEnabled(void) const { return pimpl_->is_enabled; } 106 107 void SendData::SetEnabled(bool value) { pimpl_->is_enabled = value; } 108 109 void SendData::SetSendSize(size_t value) { 110 pimpl_->send_size = value; 111 112 if (getUiCom() != NULL) 113 getUiCom()->UpdateDataToSendSize(); 100 114 } 101 115 102 uint16_t SendData::SendPeriod(void) const { 103 return pimpl_->send_period; 104 } 105 106 bool SendData::IsEnabled(void) const { 107 return pimpl_->is_enabled; 108 } 109 110 void SendData::SetEnabled(bool value) { 111 pimpl_->is_enabled=value; 112 } 113 114 void SendData::SetSendSize(size_t value) { 115 pimpl_->send_size=value; 116 117 if(getUiCom()!=NULL) getUiCom()->UpdateDataToSendSize(); 118 } 119 120 void SendData::SetSendPeriod(uint16_t value) { 121 pimpl_->send_period=value; 122 } 116 void SendData::SetSendPeriod(uint16_t value) { pimpl_->send_period = value; } 123 117 124 118 } // end namespace core -
trunk/lib/FlairCore/src/SendData.h
r2 r15 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/lib/FlairCore/src/SendData_impl.cpp
r2 r15 18 18 #include "SendData_impl.h" 19 19 20 SendData_impl::SendData_impl() 21 { 22 } 20 SendData_impl::SendData_impl() {} 23 21 24 SendData_impl::~SendData_impl() 25 { 26 } 22 SendData_impl::~SendData_impl() {} -
trunk/lib/FlairCore/src/SerialPort.h
r2 r15 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/lib/FlairCore/src/SharedMem.cpp
r2 r15 21 21 using std::string; 22 22 23 namespace flair 24 { 25 namespace core 26 { 23 namespace flair { 24 namespace core { 27 25 28 SharedMem::SharedMem(const Object * parent,string name,size_t size): Object(parent,name,"shmem")29 {30 pimpl_=new SharedMem_impl(this,name,size);26 SharedMem::SharedMem(const Object *parent, string name, size_t size) 27 : Object(parent, name, "shmem") { 28 pimpl_ = new SharedMem_impl(this, name, size); 31 29 } 32 30 33 SharedMem::~SharedMem() 34 { 35 delete pimpl_; 31 SharedMem::~SharedMem() { delete pimpl_; } 32 33 void SharedMem::Write(const char *buf, size_t size) { 34 pimpl_->Write(buf, size); 36 35 } 37 36 38 void SharedMem::Write(const char* buf,size_t size) 39 { 40 pimpl_->Write(buf,size); 41 } 42 43 void SharedMem::Read(char* buf,size_t size) const 44 { 45 pimpl_->Read(buf,size); 46 } 37 void SharedMem::Read(char *buf, size_t size) const { pimpl_->Read(buf, size); } 47 38 48 39 } // end namespace core -
trunk/lib/FlairCore/src/SharedMem.h
r2 r15 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/lib/FlairCore/src/SharedMem_impl.cpp
r2 r15 26 26 using namespace flair::core; 27 27 28 SharedMem_impl::SharedMem_impl(const SharedMem * self,string name,size_t size)29 {30 this->size=size;31 this->self=self;28 SharedMem_impl::SharedMem_impl(const SharedMem *self, string name, 29 size_t size) { 30 this->size = size; 31 this->self = self; 32 32 33 33 #ifdef __XENO__ 34 heap_binded=false; 35 int status=rt_heap_create(&heap,name.c_str(),size,H_SHARED|H_FIFO|H_NONCACHED); 36 if(status==-EEXIST) 37 { 38 heap_binded=true; 39 status=rt_heap_bind(&heap,name.c_str(),TM_INFINITE); 40 } 41 if(status!=0) 42 { 43 self->Err("rt_heap_create error (%s)\n",strerror(-status)); 44 return; 45 } 34 heap_binded = false; 35 int status = rt_heap_create(&heap, name.c_str(), size, 36 H_SHARED | H_FIFO | H_NONCACHED); 37 if (status == -EEXIST) { 38 heap_binded = true; 39 status = rt_heap_bind(&heap, name.c_str(), TM_INFINITE); 40 } 41 if (status != 0) { 42 self->Err("rt_heap_create error (%s)\n", strerror(-status)); 43 return; 44 } 46 45 47 void *ptr; 48 status=rt_heap_alloc(&heap,0,TM_NONBLOCK ,&ptr); 49 if(status!=0) 50 { 51 self->Err("rt_heap_alloc error (%s)\n",strerror(-status)); 52 } 53 mem_segment =(char*)ptr; 46 void *ptr; 47 status = rt_heap_alloc(&heap, 0, TM_NONBLOCK, &ptr); 48 if (status != 0) { 49 self->Err("rt_heap_alloc error (%s)\n", strerror(-status)); 50 } 51 mem_segment = (char *)ptr; 54 52 55 mutex_binded=false; 56 string mutex_name="mutex_"+ name; 57 status=rt_mutex_create(&mutex,mutex_name.c_str()); 58 if(status==-EEXIST) 59 { 60 mutex_binded=true; 61 status=rt_mutex_bind(&mutex,mutex_name.c_str(),TM_INFINITE); 62 } 63 if(status!=0) 64 { 65 self->Err("rt_mutex_create error (%s)\n",strerror(-status)); 66 return; 67 } 53 mutex_binded = false; 54 string mutex_name = "mutex_" + name; 55 status = rt_mutex_create(&mutex, mutex_name.c_str()); 56 if (status == -EEXIST) { 57 mutex_binded = true; 58 status = rt_mutex_bind(&mutex, mutex_name.c_str(), TM_INFINITE); 59 } 60 if (status != 0) { 61 self->Err("rt_mutex_create error (%s)\n", strerror(-status)); 62 return; 63 } 68 64 69 65 #else 70 shm_name="/" + name; 71 fd = shm_open(shm_name.c_str(), O_RDWR | O_CREAT, 0666); 72 if (fd == -1) 73 { 74 self->Err("Error creating shared memory\n"); 75 } 76 ftruncate(fd, size); 66 shm_name = "/" + name; 67 fd = shm_open(shm_name.c_str(), O_RDWR | O_CREAT, 0666); 68 if (fd == -1) { 69 self->Err("Error creating shared memory\n"); 70 } 71 ftruncate(fd, size); 77 72 78 sem_name="/" +name; 79 sem = sem_open(sem_name.c_str(), O_CREAT, 0666, 1); 80 if (sem == SEM_FAILED) 81 { 82 self->Err("Error creating semaphore\n"); 83 } 73 sem_name = "/" + name; 74 sem = sem_open(sem_name.c_str(), O_CREAT, 0666, 1); 75 if (sem == SEM_FAILED) { 76 self->Err("Error creating semaphore\n"); 77 } 84 78 85 mem_segment =(char*)mmap(NULL, size, PROT_READ | PROT_WRITE, MAP_SHARED, fd, 0);86 if (mem_segment == MAP_FAILED)87 88 89 79 mem_segment = 80 (char *)mmap(NULL, size, PROT_READ | PROT_WRITE, MAP_SHARED, fd, 0); 81 if (mem_segment == MAP_FAILED) { 82 self->Err("Failed to map memory\n"); 83 } 90 84 #endif 91 85 } 92 86 93 SharedMem_impl::~SharedMem_impl() 94 { 95 int status; 87 SharedMem_impl::~SharedMem_impl() { 88 int status; 96 89 #ifdef __XENO__ 97 /* unnecessary because heap is opened in H_SINGLE mode 98 status=rt_heap_free(&heap,mem_segment); 99 if(status!=0) 100 { 101 self->Err("rt_heap_free error (%s)\n",strerror(-status)); 90 /* unnecessary because heap is opened in H_SINGLE mode 91 status=rt_heap_free(&heap,mem_segment); 92 if(status!=0) 93 { 94 self->Err("rt_heap_free error (%s)\n",strerror(-status)); 95 } 96 */ 97 98 if (heap_binded == false) { 99 status = rt_heap_delete(&heap); 100 if (status != 0) { 101 self->Err("rt_heap_delete error (%s)\n", strerror(-status)); 102 102 } 103 */103 } 104 104 105 if(heap_binded==false) 106 { 107 status=rt_heap_delete(&heap); 108 if(status!=0) 109 { 110 self->Err("rt_heap_delete error (%s)\n",strerror(-status)); 111 } 105 if (mutex_binded == false) { 106 status = rt_mutex_delete(&mutex); 107 if (status != 0) { 108 self->Err("error destroying mutex (%s)\n", strerror(-status)); 112 109 } 110 } 111 #else 112 status = munmap(mem_segment, size); 113 if (status != 0) { 114 self->Err("Failed to unmap memory (%s)\n", strerror(-status)); 115 } 113 116 114 if(mutex_binded==false) 115 { 116 status=rt_mutex_delete(&mutex); 117 if(status!=0) 118 { 119 self->Err("error destroying mutex (%s)\n",strerror(-status)); 120 } 121 } 122 #else 123 status = munmap(mem_segment, size); 124 if(status!=0) 125 { 126 self->Err("Failed to unmap memory (%s)\n",strerror(-status)); 127 } 117 status = close(fd); 118 if (status != 0) { 119 self->Err("Failed to close file (%s)\n", strerror(-status)); 120 } 128 121 129 status = close(fd); 130 if(status!=0) 131 { 132 self->Err("Failed to close file (%s)\n",strerror(-status)); 133 } 122 // do not check erros as it can be done by another process 123 status = shm_unlink(shm_name.c_str()); /* 124 if(status!=0) 125 { 126 self->Err("Failed to unlink memory (%s)\n",strerror(-status)); 127 } 128 */ 129 // do not check erros as it can be done by another process 130 status = sem_unlink(sem_name.c_str()); /* 131 if(status!=0) 132 { 133 self->Err("Failed to unlink semaphore (%s)\n",strerror(-status)); 134 }*/ 134 135 135 //do not check erros as it can be done by another process 136 status = shm_unlink(shm_name.c_str());/* 137 if(status!=0) 138 { 139 self->Err("Failed to unlink memory (%s)\n",strerror(-status)); 140 } 141 */ 142 //do not check erros as it can be done by another process 143 status = sem_unlink(sem_name.c_str());/* 144 if(status!=0) 145 { 146 self->Err("Failed to unlink semaphore (%s)\n",strerror(-status)); 147 }*/ 148 149 status = sem_close(sem); 150 if(status!=0) 151 { 152 self->Err("Failed to close semaphore (%s)\n",strerror(-status)); 153 } 136 status = sem_close(sem); 137 if (status != 0) { 138 self->Err("Failed to close semaphore (%s)\n", strerror(-status)); 139 } 154 140 #endif 155 141 } 156 142 157 158 void SharedMem_impl::Write(const char* buf,size_t size) 159 { 143 void SharedMem_impl::Write(const char *buf, size_t size) { 160 144 #ifdef __XENO__ 161 int status=rt_mutex_acquire(&mutex,TM_INFINITE); 162 if(status!=0) self->Err("error (%s)\n",strerror(-status)); 163 memcpy(mem_segment,buf,size); 164 status=rt_mutex_release(&mutex); 165 if(status!=0) self->Err("error (%s)\n",strerror(-status)); 145 int status = rt_mutex_acquire(&mutex, TM_INFINITE); 146 if (status != 0) 147 self->Err("error (%s)\n", strerror(-status)); 148 memcpy(mem_segment, buf, size); 149 status = rt_mutex_release(&mutex); 150 if (status != 0) 151 self->Err("error (%s)\n", strerror(-status)); 166 152 #else 167 168 memcpy(mem_segment,buf,size);169 153 sem_wait(sem); 154 memcpy(mem_segment, buf, size); 155 sem_post(sem); 170 156 #endif 171 157 } 172 158 173 void SharedMem_impl::Read(char* buf,size_t size) 174 { 159 void SharedMem_impl::Read(char *buf, size_t size) { 175 160 #ifdef __XENO__ 176 int status=rt_mutex_acquire(&mutex,TM_INFINITE); 177 if(status!=0) self->Err("error (%s)\n",strerror(-status)); 178 memcpy(buf,mem_segment,size); 179 status=rt_mutex_release(&mutex); 180 if(status!=0) self->Err("error (%s)\n",strerror(-status)); 161 int status = rt_mutex_acquire(&mutex, TM_INFINITE); 162 if (status != 0) 163 self->Err("error (%s)\n", strerror(-status)); 164 memcpy(buf, mem_segment, size); 165 status = rt_mutex_release(&mutex); 166 if (status != 0) 167 self->Err("error (%s)\n", strerror(-status)); 181 168 #else 182 183 memcpy(buf,mem_segment,size);184 169 sem_wait(sem); 170 memcpy(buf, mem_segment, size); 171 sem_post(sem); 185 172 #endif 186 173 } -
trunk/lib/FlairCore/src/Socket.cpp
r2 r15 23 23 using std::string; 24 24 25 namespace flair 26 { 27 namespace core 28 { 25 namespace flair { 26 namespace core { 29 27 30 Socket::Socket(const Object* parent, string name,uint16_t port): Object(parent,name) { 31 pimpl_=new Socket_impl(this,name,port); 28 Socket::Socket(const Object *parent, string name, uint16_t port) 29 : Object(parent, name) { 30 pimpl_ = new Socket_impl(this, name, port); 32 31 } 33 32 34 Socket::Socket(const Object* parent, string name,string address,bool broadcast): Object(parent,name) { 35 pimpl_=new Socket_impl(this,name,address,broadcast); 33 Socket::Socket(const Object *parent, string name, string address, 34 bool broadcast) 35 : Object(parent, name) { 36 pimpl_ = new Socket_impl(this, name, address, broadcast); 36 37 } 37 38 38 Socket::~Socket() { 39 delete pimpl_; 39 Socket::~Socket() { delete pimpl_; } 40 41 void Socket::SendMessage(const char *message, size_t message_len) { 42 pimpl_->SendMessage(message, message_len); 40 43 } 41 44 42 void Socket::SendMessage(const char* message,size_t message_len) { 43 pimpl_->SendMessage(message,message_len); 45 void Socket::SendMessage(string message) { pimpl_->SendMessage(message); } 46 47 ssize_t Socket::RecvMessage(char *buf, size_t buf_len, Time timeout, char *src, 48 size_t *src_len) { 49 return pimpl_->RecvMessage(buf, buf_len, timeout, src, src_len); 44 50 } 45 51 46 void Socket::SendMessage(string message) { 47 pimpl_->SendMessage(message); 52 void Socket::NetworkToHost(char *data, size_t dataSize) { 53 if (core::IsBigEndian()) 54 return; 55 if (dataSize == 1) 56 return; 57 if ((dataSize == 2) || (dataSize == 4) || (dataSize == 8) || 58 (dataSize == 16)) { 59 char dataInHostEndianness[dataSize]; 60 for (unsigned int i = 0; i < dataSize; i++) { 61 dataInHostEndianness[i] = data[dataSize - i - 1]; 62 } 63 memcpy(data, dataInHostEndianness, dataSize); 64 return; 65 } 66 throw std::runtime_error( 67 string("Unsupported data size (") + std::to_string(dataSize) + 68 string(") in host to network endianness conversion")); 48 69 } 49 70 50 ssize_t Socket::RecvMessage(char* buf,size_t buf_len,Time timeout,char* src,size_t* src_len) { 51 return pimpl_->RecvMessage(buf,buf_len,timeout,src,src_len); 52 } 53 54 void Socket::NetworkToHost(char *data,size_t dataSize) { 55 if (core::IsBigEndian()) return; 56 if (dataSize==1) return; 57 if ((dataSize==2)||(dataSize==4)||(dataSize==8)||(dataSize==16)) { 58 char dataInHostEndianness[dataSize]; 59 for (unsigned int i=0;i<dataSize;i++) { 60 dataInHostEndianness[i]=data[dataSize-i-1]; 61 } 62 memcpy(data,dataInHostEndianness,dataSize); 63 return; 71 void Socket::HostToNetwork(char *data, size_t dataSize) { 72 if (IsBigEndian()) 73 return; 74 if (dataSize == 1) 75 return; 76 if ((dataSize == 2) || (dataSize == 4) || (dataSize == 8) || 77 (dataSize == 16)) { 78 char dataInNetworkEndianness[dataSize]; 79 for (unsigned int i = 0; i < dataSize; i++) { 80 dataInNetworkEndianness[i] = data[dataSize - i - 1]; 64 81 } 65 throw std::runtime_error(string("Unsupported data size (")+std::to_string(dataSize)+string(") in host to network endianness conversion")); 66 } 67 68 void Socket::HostToNetwork(char *data,size_t dataSize) { 69 if (IsBigEndian()) return; 70 if (dataSize==1) return; 71 if ((dataSize==2)||(dataSize==4)||(dataSize==8)||(dataSize==16)) { 72 char dataInNetworkEndianness[dataSize]; 73 for (unsigned int i=0;i<dataSize;i++) { 74 dataInNetworkEndianness[i]=data[dataSize-i-1]; 75 } 76 memcpy(data,dataInNetworkEndianness,dataSize); 77 return; 78 } 79 throw std::runtime_error(string("Unsupported data size (")+std::to_string(dataSize)+string(") in host to network endianness conversion")); 82 memcpy(data, dataInNetworkEndianness, dataSize); 83 return; 84 } 85 throw std::runtime_error( 86 string("Unsupported data size (") + std::to_string(dataSize) + 87 string(") in host to network endianness conversion")); 80 88 } 81 89 -
trunk/lib/FlairCore/src/Socket.h
r2 r15 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/lib/FlairCore/src/Socket_impl.cpp
r2 r15 29 29 using namespace flair::core; 30 30 31 Socket_impl::Socket_impl(const Socket* self,string name,uint16_t port) 32 { 33 this->self=self; 34 this->port=port; 35 this->address=""; 36 this->broadcast=false; 37 Init(); 38 } 39 40 Socket_impl::Socket_impl(const Socket* self,string name,string address,bool broadcast) 41 { 42 this->self=self; 43 int pos = address.find(":"); 44 this->address=address.substr (0,pos); 45 port=atoi(address.substr(pos+1).c_str()); 46 this->broadcast=broadcast; 47 48 if(pos==0 || address=="") 49 { 50 self->Err("address %s is not correct\n",address.c_str()); 51 } 52 Init(); 53 54 } 55 56 void Socket_impl::Init(void) 57 { 58 int yes=1; 59 60 fd = socket(AF_INET, SOCK_DGRAM, 0); //UDP 61 62 if(broadcast==true) 63 { 64 if(setsockopt(fd, SOL_SOCKET, SO_BROADCAST, &yes, sizeof(int) )!=0) 65 self->Err("Setsockopt error\n"); 66 } 67 68 if(setsockopt(fd, SOL_SOCKET, SO_REUSEADDR, &yes, sizeof(int) )!=0) 69 self->Err("Setsockopt error\n"); 70 71 if(address=="" || broadcast==true) 72 { 73 sockaddr_in sin = { 0 }; 74 75 if(broadcast==true) 76 { 77 struct hostent *hostinfo; 78 79 hostinfo = gethostbyname(this->address.c_str()); 80 if (hostinfo == NULL) 81 { 82 self->Err("hostinfo error\n"); 83 } 84 sin.sin_addr = *(in_addr *) hostinfo->h_addr; 85 } 86 else 87 { 88 sin.sin_addr.s_addr=INADDR_ANY; 89 } 90 91 sin.sin_port = htons(port); 92 sin.sin_family = AF_INET; 93 if(bind(fd,(sockaddr *) &sin, sizeof sin) == -1) 94 { 95 self->Err("bind error\n"); 96 } 97 } 98 99 100 #ifdef __XENO__ 101 string tmp_name; 102 int status; 103 is_running=true; 104 105 //pipe 106 tmp_name= getFrameworkManager()->ObjectName() + "-" + self->ObjectName()+ "-pipe"; 107 //xenomai limitation 108 if(tmp_name.size()>31) self->Err("rt_pipe_create error (%s is too long)\n",tmp_name.c_str()); 31 Socket_impl::Socket_impl(const Socket *self, string name, uint16_t port) { 32 this->self = self; 33 this->port = port; 34 this->address = ""; 35 this->broadcast = false; 36 Init(); 37 } 38 39 Socket_impl::Socket_impl(const Socket *self, string name, string address, 40 bool broadcast) { 41 this->self = self; 42 int pos = address.find(":"); 43 this->address = address.substr(0, pos); 44 port = atoi(address.substr(pos + 1).c_str()); 45 this->broadcast = broadcast; 46 47 if (pos == 0 || address == "") { 48 self->Err("address %s is not correct\n", address.c_str()); 49 } 50 Init(); 51 } 52 53 void Socket_impl::Init(void) { 54 int yes = 1; 55 56 fd = socket(AF_INET, SOCK_DGRAM, 0); // UDP 57 58 if (broadcast == true) { 59 if (setsockopt(fd, SOL_SOCKET, SO_BROADCAST, &yes, sizeof(int)) != 0) 60 self->Err("Setsockopt error\n"); 61 } 62 63 if (setsockopt(fd, SOL_SOCKET, SO_REUSEADDR, &yes, sizeof(int)) != 0) 64 self->Err("Setsockopt error\n"); 65 66 if (address == "" || broadcast == true) { 67 sockaddr_in sin = {0}; 68 69 if (broadcast == true) { 70 struct hostent *hostinfo; 71 72 hostinfo = gethostbyname(this->address.c_str()); 73 if (hostinfo == NULL) { 74 self->Err("hostinfo error\n"); 75 } 76 sin.sin_addr = *(in_addr *)hostinfo->h_addr; 77 } else { 78 sin.sin_addr.s_addr = INADDR_ANY; 79 } 80 81 sin.sin_port = htons(port); 82 sin.sin_family = AF_INET; 83 if (bind(fd, (sockaddr *)&sin, sizeof sin) == -1) { 84 self->Err("bind error\n"); 85 } 86 } 87 88 #ifdef __XENO__ 89 string tmp_name; 90 int status; 91 is_running = true; 92 93 // pipe 94 tmp_name = 95 getFrameworkManager()->ObjectName() + "-" + self->ObjectName() + "-pipe"; 96 // xenomai limitation 97 if (tmp_name.size() > 31) 98 self->Err("rt_pipe_create error (%s is too long)\n", tmp_name.c_str()); 109 99 #ifdef RT_PIPE_SIZE 110 status=rt_pipe_create(&pipe, tmp_name.c_str(), P_MINOR_AUTO,RT_PIPE_SIZE);100 status = rt_pipe_create(&pipe, tmp_name.c_str(), P_MINOR_AUTO, RT_PIPE_SIZE); 111 101 #else 112 status=rt_pipe_create(&pipe, tmp_name.c_str(), P_MINOR_AUTO,0); 113 #endif 114 if(status!=0) 115 { 116 self->Err("rt_pipe_create error (%s)\n",strerror(-status)); 117 } 118 119 //start user side thread 102 status = rt_pipe_create(&pipe, tmp_name.c_str(), P_MINOR_AUTO, 0); 103 #endif 104 if (status != 0) { 105 self->Err("rt_pipe_create error (%s)\n", strerror(-status)); 106 } 107 108 // start user side thread 120 109 #ifdef NRT_STACK_SIZE 121 // Initialize thread creation attributes 122 pthread_attr_t attr; 123 if(pthread_attr_init(&attr) != 0) 124 { 125 self->Err("pthread_attr_init error\n"); 126 } 127 if(pthread_attr_setstacksize(&attr, NRT_STACK_SIZE) != 0) 128 { 129 self->Err("pthread_attr_setstacksize error\n"); 130 } 131 if(pthread_create(&user_thread, &attr, user, (void*)this) < 0) 132 { 133 self->Err("pthread_create error\n"); 134 } 135 if(pthread_attr_destroy(&attr) != 0) 136 { 137 self->Err("pthread_attr_destroy error\n"); 138 } 139 #else //NRT_STACK_SIZE 140 if(pthread_create(&user_thread, NULL, user, (void*)this) < 0) 141 { 142 self->Err("pthread_create error\n"); 143 } 144 #endif //NRT_STACK_SIZE 110 // Initialize thread creation attributes 111 pthread_attr_t attr; 112 if (pthread_attr_init(&attr) != 0) { 113 self->Err("pthread_attr_init error\n"); 114 } 115 if (pthread_attr_setstacksize(&attr, NRT_STACK_SIZE) != 0) { 116 self->Err("pthread_attr_setstacksize error\n"); 117 } 118 if (pthread_create(&user_thread, &attr, user, (void *)this) < 0) { 119 self->Err("pthread_create error\n"); 120 } 121 if (pthread_attr_destroy(&attr) != 0) { 122 self->Err("pthread_attr_destroy error\n"); 123 } 124 #else // NRT_STACK_SIZE 125 if (pthread_create(&user_thread, NULL, user, (void *)this) < 0) { 126 self->Err("pthread_create error\n"); 127 } 128 #endif // NRT_STACK_SIZE 145 129 #endif //__XENO__ 146 130 147 if(address!="") 148 { 149 struct hostent *hostinfo; 150 hostinfo = gethostbyname(address.c_str()); 151 if (hostinfo == NULL) 152 { 153 self->Err("gethostbyname\n"); 154 } 155 156 sock_in.sin_addr=*(in_addr *) hostinfo->h_addr; 157 sock_in.sin_port = htons(port); 158 sock_in.sin_family = AF_INET; 159 } 160 } 161 162 Socket_impl::~Socket_impl() 163 { 164 #ifdef __XENO__ 165 is_running=false; 166 167 pthread_join(user_thread,NULL); 168 int status=rt_pipe_delete(&pipe); 169 if(status!=0) self->Err("rt_pipe_delete error (%s)\n",strerror(-status)); 170 171 #endif 172 close(fd); 173 } 174 175 void Socket_impl::SendMessage(const char* src,size_t src_len) 176 { 177 ssize_t written; 178 string to_send; 179 180 if(broadcast==true) 181 { 182 to_send=getFrameworkManager()->ObjectName()+ ":" + string(src, src_len); 183 src_len=to_send.size(); 184 src=(char*)to_send.c_str(); 185 } 186 187 #ifdef __XENO__ 188 //Printf("send pipe %s\n",src); 189 written=rt_pipe_write(&pipe,src,src_len,P_NORMAL); 190 191 if(written<0) 192 { 193 self->Err("rt_pipe_write error (%s)\n",strerror(-written)); 194 } 195 else if (written != (ssize_t)src_len) 196 { 197 self->Err("rt_pipe_write error %i/%i\n",written,to_send.size()); 198 } 131 if (address != "") { 132 struct hostent *hostinfo; 133 hostinfo = gethostbyname(address.c_str()); 134 if (hostinfo == NULL) { 135 self->Err("gethostbyname\n"); 136 } 137 138 sock_in.sin_addr = *(in_addr *)hostinfo->h_addr; 139 sock_in.sin_port = htons(port); 140 sock_in.sin_family = AF_INET; 141 } 142 } 143 144 Socket_impl::~Socket_impl() { 145 #ifdef __XENO__ 146 is_running = false; 147 148 pthread_join(user_thread, NULL); 149 int status = rt_pipe_delete(&pipe); 150 if (status != 0) 151 self->Err("rt_pipe_delete error (%s)\n", strerror(-status)); 152 153 #endif 154 close(fd); 155 } 156 157 void Socket_impl::SendMessage(const char *src, size_t src_len) { 158 ssize_t written; 159 string to_send; 160 161 if (broadcast == true) { 162 to_send = getFrameworkManager()->ObjectName() + ":" + string(src, src_len); 163 src_len = to_send.size(); 164 src = (char *)to_send.c_str(); 165 } 166 167 #ifdef __XENO__ 168 // Printf("send pipe %s\n",src); 169 written = rt_pipe_write(&pipe, src, src_len, P_NORMAL); 170 171 if (written < 0) { 172 self->Err("rt_pipe_write error (%s)\n", strerror(-written)); 173 } else if (written != (ssize_t)src_len) { 174 self->Err("rt_pipe_write error %i/%i\n", written, to_send.size()); 175 } 199 176 #else 200 written=sendto(fd,src,src_len, 0, (struct sockaddr *) &sock_in, sizeof(sock_in)); 201 202 if(written!=(ssize_t)src_len) 203 { 204 self->Err("sendto error\n"); 205 } 206 #endif 207 } 208 209 void Socket_impl::SendMessage(string message) 210 { 211 ssize_t written; 212 213 if(broadcast==true) message=self->Parent()->ObjectName()+ ":" + message; 214 //Printf("SendMessage %s\n",message.c_str()); 215 #ifdef __XENO__ 216 written=rt_pipe_write(&pipe,message.c_str(),message.size(),P_NORMAL); 217 218 if(written<0) 219 { 220 self->Err("rt_pipe_write error (%s)\n",strerror(-written)); 221 } 222 else if (written != (ssize_t)message.size()) 223 { 224 self->Err("rt_pipe_write error %i/%i\n",written,message.size()); 225 } 177 written = 178 sendto(fd, src, src_len, 0, (struct sockaddr *)&sock_in, sizeof(sock_in)); 179 180 if (written != (ssize_t)src_len) { 181 self->Err("sendto error\n"); 182 } 183 #endif 184 } 185 186 void Socket_impl::SendMessage(string message) { 187 ssize_t written; 188 189 if (broadcast == true) 190 message = self->Parent()->ObjectName() + ":" + message; 191 // Printf("SendMessage %s\n",message.c_str()); 192 #ifdef __XENO__ 193 written = rt_pipe_write(&pipe, message.c_str(), message.size(), P_NORMAL); 194 195 if (written < 0) { 196 self->Err("rt_pipe_write error (%s)\n", strerror(-written)); 197 } else if (written != (ssize_t)message.size()) { 198 self->Err("rt_pipe_write error %i/%i\n", written, message.size()); 199 } 226 200 #else 227 written=sendto(fd,message.c_str(),message.size(), 0, (struct sockaddr *) &sock_in, sizeof(sock_in));228 if(written!=(ssize_t)message.size())229 230 231 232 233 #endif 234 } 235 236 ssize_t Socket_impl::RecvMessage(char * msg,size_t msg_len,Time timeout,char* src,size_t* src_len)237 {238 239 240 #ifdef __XENO__ 241 nb_read=rt_pipe_read(&pipe,&buffer,sizeof(buffer),timeout);201 written = sendto(fd, message.c_str(), message.size(), 0, 202 (struct sockaddr *)&sock_in, sizeof(sock_in)); 203 if (written != (ssize_t)message.size()) { 204 self->Err("sendto error\n"); 205 } 206 207 #endif 208 } 209 210 ssize_t Socket_impl::RecvMessage(char *msg, size_t msg_len, Time timeout, 211 char *src, size_t *src_len) { 212 ssize_t nb_read; 213 char buffer[128]; 214 #ifdef __XENO__ 215 nb_read = rt_pipe_read(&pipe, &buffer, sizeof(buffer), timeout); 242 216 #else 243 socklen_t sinsize = sizeof(sock_in); 244 struct timeval tv; 245 246 if(timeout!=TIME_NONBLOCK) { 247 int attr=fcntl(fd, F_GETFL,0); 248 fcntl(fd, F_SETFL, attr & (~O_NONBLOCK)); 249 250 tv.tv_sec = timeout/1000000000; 251 timeout=timeout-(timeout/1000000000)*1000000000; 252 tv.tv_usec = timeout/1000; 253 if (setsockopt(fd, SOL_SOCKET, SO_RCVTIMEO,&tv,sizeof(tv)) < 0) { 254 self->Err("setsockopt SO_RCVTIMEO failed\n"); 255 } 217 socklen_t sinsize = sizeof(sock_in); 218 struct timeval tv; 219 220 if (timeout != TIME_NONBLOCK) { 221 int attr = fcntl(fd, F_GETFL, 0); 222 fcntl(fd, F_SETFL, attr & (~O_NONBLOCK)); 223 224 tv.tv_sec = timeout / 1000000000; 225 timeout = timeout - (timeout / 1000000000) * 1000000000; 226 tv.tv_usec = timeout / 1000; 227 if (setsockopt(fd, SOL_SOCKET, SO_RCVTIMEO, &tv, sizeof(tv)) < 0) { 228 self->Err("setsockopt SO_RCVTIMEO failed\n"); 229 } 230 } else { 231 fcntl(fd, F_SETFL, O_NONBLOCK); 232 } 233 234 if (broadcast == false) { 235 nb_read = 236 recvfrom(fd, buffer, sizeof(buffer), 0, (sockaddr *)&sock_in, &sinsize); 237 } else { 238 nb_read = recvfrom(fd, buffer, sizeof(buffer), 0, NULL, NULL); 239 } 240 #endif 241 if (nb_read <= 0) { 242 return nb_read; 243 } else { 244 // printf("%s\n",buffer); 245 if (broadcast == true) { 246 int index = -1; 247 for (int i = 0; i < nb_read; i++) { 248 if (buffer[i] == ':') { 249 index = i; 250 break; 251 } 252 } 253 if (index < 0) { 254 self->Warn("Malformed message\n"); 255 return -1; 256 } else if (src_len != NULL && src != NULL) { 257 if (index + 1 > (int)(*src_len) && 258 src != NULL) { //+1 pour inserer un 0) 259 self->Warn("insufficent src size\n"); 260 return -1; 261 } 262 } else if (nb_read - index - 1 + 1 > 263 (int)msg_len) { //+1 pour inserer un 0 264 self->Warn("insufficent msg size (%i/%i)\n", nb_read - index - 1 + 1, 265 msg_len); 266 return -1; 267 } 268 if (src != NULL) { 269 memcpy(src, buffer, index); 270 src[index] = 0; 271 } 272 memcpy(msg, &buffer[index + 1], nb_read - index - 1); 273 msg[nb_read - index - 1] = 0; 274 return nb_read - index; 256 275 } else { 257 fcntl(fd, F_SETFL, O_NONBLOCK); 258 } 259 260 if(broadcast==false) { 261 nb_read = recvfrom(fd, buffer, sizeof(buffer), 0, (sockaddr *) &sock_in, &sinsize); 276 if (nb_read > (int)msg_len) { 277 self->Warn("insufficent msg size (%i/%i)\n", nb_read, msg_len); 278 return -1; 279 } 280 memcpy(msg, buffer, nb_read); 281 return nb_read; 282 } 283 } 284 } 285 286 #ifdef __XENO__ 287 void *Socket_impl::user(void *arg) { 288 Socket_impl *caller = (Socket_impl *)arg; 289 int pipe_fd = -1; 290 string devname; 291 292 devname = NRT_PIPE_PATH + getFrameworkManager()->ObjectName() + "-" + 293 caller->self->ObjectName() + "-pipe"; 294 while (pipe_fd < 0) { 295 pipe_fd = open(devname.c_str(), O_RDWR); 296 if (pipe_fd < 0 && errno != ENOENT) 297 caller->self->Err("open pipe_fd error (%s)\n", strerror(-errno)); 298 usleep(1000); 299 } 300 301 while (caller->is_running == true) { 302 fd_set set; 303 struct timeval timeout; 304 int rv; 305 306 FD_ZERO(&set); // clear the set 307 FD_SET(caller->fd, &set); // add our file descriptor to the set 308 FD_SET(pipe_fd, &set); // add our file descriptor to the set 309 310 timeout.tv_sec = 0; 311 timeout.tv_usec = SELECT_TIMEOUT_MS * 1000; 312 rv = select(FD_SETSIZE, &set, NULL, NULL, &timeout); 313 314 if (rv == -1) { 315 caller->self->Err("select error\n"); // an error occured 316 } else if (rv == 0) { 317 // printf("timeout\n"); 262 318 } else { 263 nb_read = recvfrom(fd, buffer, sizeof(buffer), 0, NULL,NULL); 264 } 265 #endif 266 if(nb_read<=0) { 267 return nb_read; 268 } else { 269 //printf("%s\n",buffer); 270 if(broadcast==true) { 271 int index=-1; 272 for(int i=0;i<nb_read;i++) { 273 if(buffer[i]==':') { 274 index=i; 275 break; 276 } 277 } 278 if(index<0) { 279 self->Warn("Malformed message\n"); 280 return -1; 281 } else if(src_len!=NULL && src!=NULL) { 282 if(index+1>(int)(*src_len) && src!=NULL) { //+1 pour inserer un 0) 283 self->Warn("insufficent src size\n"); 284 return -1; 285 } 286 } else if(nb_read-index-1+1>(int)msg_len) { //+1 pour inserer un 0 287 self->Warn("insufficent msg size (%i/%i)\n",nb_read-index-1+1,msg_len); 288 return -1; 289 } 290 if(src!=NULL) { 291 memcpy(src,buffer,index); 292 src[index]=0; 293 } 294 memcpy(msg,&buffer[index+1],nb_read-index-1); 295 msg[nb_read-index-1]=0; 296 return nb_read-index; 319 ssize_t nb_read, nb_write; 320 char buffer[1024]; 321 322 if (FD_ISSET(caller->fd, &set)) { 323 socklen_t sinsize = sizeof(caller->sock_in); 324 if (caller->broadcast == false) { 325 nb_read = recvfrom(caller->fd, buffer, sizeof(buffer), 0, 326 (sockaddr *)&(caller->sock_in), &sinsize); 297 327 } else { 298 if(nb_read>(int)msg_len) { 299 self->Warn("insufficent msg size (%i/%i)\n",nb_read,msg_len); 300 return -1; 301 } 302 memcpy(msg,buffer,nb_read); 303 return nb_read; 304 } 305 } 306 } 307 308 #ifdef __XENO__ 309 void* Socket_impl::user(void * arg) 310 { 311 Socket_impl *caller = (Socket_impl*)arg; 312 int pipe_fd=-1; 313 string devname; 314 315 devname= NRT_PIPE_PATH + getFrameworkManager()->ObjectName() + "-" + caller->self->ObjectName()+ "-pipe"; 316 while(pipe_fd<0) 317 { 318 pipe_fd = open(devname.c_str(), O_RDWR); 319 if (pipe_fd < 0 && errno!=ENOENT) caller->self->Err("open pipe_fd error (%s)\n",strerror(-errno)); 320 usleep(1000); 321 } 322 323 while(caller->is_running==true) 324 { 325 fd_set set; 326 struct timeval timeout; 327 int rv; 328 329 FD_ZERO(&set); // clear the set 330 FD_SET(caller->fd, &set); // add our file descriptor to the set 331 FD_SET(pipe_fd, &set); // add our file descriptor to the set 332 333 timeout.tv_sec = 0; 334 timeout.tv_usec = SELECT_TIMEOUT_MS*1000; 335 rv = select(FD_SETSIZE, &set, NULL, NULL, &timeout); 336 337 if(rv == -1) 338 { 339 caller->self->Err("select error\n"); // an error occured 340 } 341 else if(rv == 0) 342 { 343 //printf("timeout\n"); 344 } 345 else 346 { 347 ssize_t nb_read,nb_write; 348 char buffer[1024]; 349 350 if(FD_ISSET(caller->fd, &set)) 351 { 352 socklen_t sinsize = sizeof(caller->sock_in); 353 if (caller->broadcast==false) 354 { 355 nb_read = recvfrom(caller->fd, buffer, sizeof(buffer), 0, (sockaddr *) &(caller->sock_in), &sinsize); 356 } 357 else 358 { 359 nb_read = recvfrom(caller->fd, buffer, sizeof(buffer), 0, NULL,NULL); 360 } 361 if(nb_read < 0) 362 { 363 caller->self->Err("recvfrom error\n"); 364 } 365 //printf("user %s\n",buffer); 366 //on ne garde que les messages venant pas de soi meme 367 if (caller->broadcast==false || (caller->broadcast==true && getFrameworkManager()->ObjectName().compare(0,getFrameworkManager()->ObjectName().size(),buffer,getFrameworkManager()->ObjectName().size()) != 0)) 368 { 369 nb_write=write(pipe_fd,buffer,nb_read); 370 if(nb_write!=nb_read) 371 { 372 caller->self->Err("write error\n"); 373 } 374 } 375 else 376 { 377 //printf("self %s\n",buffer); 378 } 379 } 380 if(FD_ISSET(pipe_fd, &set)) 381 { 382 nb_read=read(pipe_fd,buffer,sizeof(buffer)); 383 //printf("read pipe %i %s\n",nb_read,buffer); 384 if(nb_read>0) 385 { 386 //printf("send %s\n",buffer); 387 nb_write=sendto(caller->fd,buffer,nb_read, 0, (struct sockaddr *) &(caller->sock_in), sizeof(caller->sock_in)); 388 if(nb_write!=nb_read) 389 { 390 caller->self->Err("sendto error\n"); 391 } 392 } 393 } 394 } 395 } 396 397 close(pipe_fd); 398 pthread_exit(0); 399 } 400 #endif 328 nb_read = recvfrom(caller->fd, buffer, sizeof(buffer), 0, NULL, NULL); 329 } 330 if (nb_read < 0) { 331 caller->self->Err("recvfrom error\n"); 332 } 333 // printf("user %s\n",buffer); 334 // on ne garde que les messages venant pas de soi meme 335 if (caller->broadcast == false || 336 (caller->broadcast == true && 337 getFrameworkManager()->ObjectName().compare( 338 0, getFrameworkManager()->ObjectName().size(), buffer, 339 getFrameworkManager()->ObjectName().size()) != 0)) { 340 nb_write = write(pipe_fd, buffer, nb_read); 341 if (nb_write != nb_read) { 342 caller->self->Err("write error\n"); 343 } 344 } else { 345 // printf("self %s\n",buffer); 346 } 347 } 348 if (FD_ISSET(pipe_fd, &set)) { 349 nb_read = read(pipe_fd, buffer, sizeof(buffer)); 350 // printf("read pipe %i %s\n",nb_read,buffer); 351 if (nb_read > 0) { 352 // printf("send %s\n",buffer); 353 nb_write = sendto(caller->fd, buffer, nb_read, 0, 354 (struct sockaddr *)&(caller->sock_in), 355 sizeof(caller->sock_in)); 356 if (nb_write != nb_read) { 357 caller->self->Err("sendto error\n"); 358 } 359 } 360 } 361 } 362 } 363 364 close(pipe_fd); 365 pthread_exit(0); 366 } 367 #endif -
trunk/lib/FlairCore/src/SpinBox.cpp
r2 r15 20 20 using std::string; 21 21 22 namespace flair { namespace gui { 22 namespace flair { 23 namespace gui { 23 24 24 SpinBox::SpinBox(const LayoutPosition* position,string name,int min,int max,int step,int default_value):Box(position,name,"SpinBox") { 25 //update value from xml file 26 if(default_value<min) default_value=min; 27 if(default_value>max) default_value=max; 28 box_value=default_value; 25 SpinBox::SpinBox(const LayoutPosition *position, string name, int min, int max, 26 int step, int default_value) 27 : Box(position, name, "SpinBox") { 28 // update value from xml file 29 if (default_value < min) 30 default_value = min; 31 if (default_value > max) 32 default_value = max; 33 box_value = default_value; 29 34 30 SetVolatileXmlProp("min",min);31 SetVolatileXmlProp("max",max);32 SetVolatileXmlProp("step",step);33 GetPersistentXmlProp("value",box_value);34 SetPersistentXmlProp("value",box_value);35 SetVolatileXmlProp("min", min); 36 SetVolatileXmlProp("max", max); 37 SetVolatileXmlProp("step", step); 38 GetPersistentXmlProp("value", box_value); 39 SetPersistentXmlProp("value", box_value); 35 40 36 41 SendXml(); 37 42 } 38 43 39 SpinBox::SpinBox(const LayoutPosition* position,string name,string suffix,int min,int max,int step,int default_value):Box(position,name,"SpinBox") { 40 //update value from xml file 41 if(default_value<min) default_value=min; 42 if(default_value>max) default_value=max; 43 box_value=default_value; 44 SpinBox::SpinBox(const LayoutPosition *position, string name, string suffix, 45 int min, int max, int step, int default_value) 46 : Box(position, name, "SpinBox") { 47 // update value from xml file 48 if (default_value < min) 49 default_value = min; 50 if (default_value > max) 51 default_value = max; 52 box_value = default_value; 44 53 45 SetVolatileXmlProp("suffix",suffix);46 SetVolatileXmlProp("min",min);47 SetVolatileXmlProp("max",max);48 SetVolatileXmlProp("step",step);49 GetPersistentXmlProp("value",box_value);50 SetPersistentXmlProp("value",box_value);51 54 SetVolatileXmlProp("suffix", suffix); 55 SetVolatileXmlProp("min", min); 56 SetVolatileXmlProp("max", max); 57 SetVolatileXmlProp("step", step); 58 GetPersistentXmlProp("value", box_value); 59 SetPersistentXmlProp("value", box_value); 60 SendXml(); 52 61 } 53 62 54 SpinBox::~SpinBox() { 55 } 63 SpinBox::~SpinBox() {} 56 64 57 65 int SpinBox::Value(void) const { 58 66 int tmp; 59 67 60 61 tmp=box_value;62 68 GetMutex(); 69 tmp = box_value; 70 ReleaseMutex(); 63 71 64 72 return tmp; 65 73 } 66 74 67 75 void SpinBox::XmlEvent(void) { 68 GetMutex(); 69 if(GetPersistentXmlProp("value",box_value)) SetValueChanged(); 70 ReleaseMutex(); 76 GetMutex(); 77 if (GetPersistentXmlProp("value", box_value)) 78 SetValueChanged(); 79 ReleaseMutex(); 71 80 } 72 81 -
trunk/lib/FlairCore/src/SpinBox.h
r2 r15 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/lib/FlairCore/src/Tab.cpp
r2 r15 20 20 using std::string; 21 21 22 namespace flair 23 { 24 namespace gui 25 { 22 namespace flair { 23 namespace gui { 26 24 27 Tab::Tab(const TabWidget * parent,string name,int position): Layout(parent,name,"Tab")28 {29 SetVolatileXmlProp("position",position);30 25 Tab::Tab(const TabWidget *parent, string name, int position) 26 : Layout(parent, name, "Tab") { 27 SetVolatileXmlProp("position", position); 28 SendXml(); 31 29 } 32 30 33 Tab::~Tab() 34 { 35 36 } 31 Tab::~Tab() {} 37 32 38 33 } // end namespace gui -
trunk/lib/FlairCore/src/Tab.h
r2 r15 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/lib/FlairCore/src/TabWidget.cpp
r2 r15 22 22 using std::string; 23 23 24 namespace flair 25 { 26 namespace gui 27 { 24 namespace flair { 25 namespace gui { 28 26 29 TabWidget::TabWidget(const LayoutPosition* position,string name,TabPosition_t tabPosition): Widget(position->getLayout(),name,"TabWidget") 30 { 31 SetVolatileXmlProp("row",position->Row()); 32 SetVolatileXmlProp("col",position->Col()); 33 SetVolatileXmlProp("position",(int)tabPosition); 34 SendXml(); 27 TabWidget::TabWidget(const LayoutPosition *position, string name, 28 TabPosition_t tabPosition) 29 : Widget(position->getLayout(), name, "TabWidget") { 30 SetVolatileXmlProp("row", position->Row()); 31 SetVolatileXmlProp("col", position->Col()); 32 SetVolatileXmlProp("position", (int)tabPosition); 33 SendXml(); 35 34 36 35 delete position; 37 36 } 38 37 39 TabWidget::~TabWidget() 40 { 41 } 38 TabWidget::~TabWidget() {} 42 39 43 40 } // end namespace gui -
trunk/lib/FlairCore/src/TabWidget.h
r2 r15 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/lib/FlairCore/src/TcpSocket.cpp
r2 r15 28 28 namespace core { 29 29 30 TcpSocket::TcpSocket(const Object* parent,const std::string name,bool _blockOnSend,bool _blockOnReceive):ConnectedSocket(parent,name),isConnected(false) { 31 blockOnSend=_blockOnSend; 32 blockOnReceive=_blockOnReceive; 30 TcpSocket::TcpSocket(const Object *parent, const std::string name, 31 bool _blockOnSend, bool _blockOnReceive) 32 : ConnectedSocket(parent, name), isConnected(false) { 33 blockOnSend = _blockOnSend; 34 blockOnReceive = _blockOnReceive; 33 35 } 34 36 35 37 TcpSocket::~TcpSocket() { 36 //Info("Debug: destroying TCP socket %s", ObjectName().c_str()); 38 // Info("Debug: destroying TCP socket %s", ObjectName().c_str()); 39 close(socket); 40 } 41 42 void TcpSocket::Listen(const unsigned int port, 43 const std::string localAddress) { 44 socket = ::socket(AF_INET, SOCK_STREAM, 0); 45 46 sockaddr_in my_addr; 47 my_addr.sin_family = AF_INET; 48 my_addr.sin_port = htons(port); 49 if (localAddress == "ANY") { 50 my_addr.sin_addr.s_addr = INADDR_ANY; 51 } else { 52 inet_aton(localAddress.c_str(), &(my_addr.sin_addr)); 53 } 54 memset(&(my_addr.sin_zero), '\0', 8); 55 56 if (bind(socket, (sockaddr *)&my_addr, sizeof(my_addr)) < 0) { 57 char errorMsg[256]; 58 Err("TCP bind, %s\n", strerror_r(errno, errorMsg, sizeof(errorMsg))); 59 } 60 61 listen(socket, 1); 62 } 63 64 TcpSocket *TcpSocket::Accept(Time timeout) { 65 char errorMsg[256]; 66 TcpSocket *acceptedSocket = nullptr; 67 68 struct timeval tv; 69 if (timeout != 0) { 70 tv.tv_sec = timeout / 1000; // timeout is in ms 71 tv.tv_usec = (timeout % 1000) * 1000; 72 } 73 fd_set rset; 74 FD_ZERO(&rset); 75 FD_SET(socket, &rset); 76 int ret = select(socket + 1, &rset, nullptr, nullptr, 77 (timeout == 0) ? nullptr : &tv); // man 2 accept 78 if (ret < 0) { 79 Err("select: %s\n", strerror_r(errno, errorMsg, sizeof(errorMsg))); 80 } else { 81 if (ret == 0) { 82 // timeout reached 83 // Err("timeout reached\n"); 84 } else { 85 // our socket is readable, a new connection can be accepted 86 acceptedSocket = new TcpSocket(this->Parent(), this->ObjectName(), 87 blockOnSend, blockOnReceive); 88 sockaddr_in their_addr; 89 socklen_t namelen = sizeof(their_addr); 90 if ((acceptedSocket->socket = 91 accept(socket, (sockaddr *)&their_addr, &namelen)) < 0) { 92 Err("error: %s\n", strerror_r(errno, errorMsg, sizeof(errorMsg))); 93 delete acceptedSocket; 94 acceptedSocket = nullptr; 95 } 96 } 97 } 98 99 return acceptedSocket; 100 } 101 102 bool TcpSocket::Connect(const unsigned int distantPort, 103 const std::string distantAddress, Time timeout) { 104 bool success = false; 105 char errorMsg[256]; 106 107 if (isConnected) { 108 if (this->distantPort == distantPort && 109 this->distantAddress == distantAddress) { 110 return true; 111 } else { 112 close(socket); 113 } 114 } 115 socket = ::socket(AF_INET, SOCK_STREAM, 0); 116 if (socket == -1) 117 return false; 118 119 sockaddr_in serv_addr; 120 serv_addr.sin_family = AF_INET; 121 serv_addr.sin_port = htons(short(distantPort)); 122 if (inet_pton(AF_INET, distantAddress.c_str(), &serv_addr.sin_addr) <= 0) { 123 printf("incorrect network address."); 37 124 close(socket); 38 } 39 40 void TcpSocket::Listen(const unsigned int port,const std::string localAddress) { 41 socket=::socket(AF_INET,SOCK_STREAM,0); 42 43 sockaddr_in my_addr; 44 my_addr.sin_family = AF_INET; 45 my_addr.sin_port = htons(port); 46 if (localAddress=="ANY") { 47 my_addr.sin_addr.s_addr=INADDR_ANY; 125 return false; 126 } 127 memset(&(serv_addr.sin_zero), '\0', 8); 128 129 // go non blocking 130 int flags = fcntl(socket, F_GETFL); 131 fcntl(socket, F_SETFL, flags | O_NONBLOCK); 132 if (connect(socket, (sockaddr *)&serv_addr, sizeof(serv_addr)) == -1) { 133 if ((errno != EINPROGRESS) && (errno != EAGAIN)) { 134 Err("socket connect: %s\n", 135 strerror_r(errno, errorMsg, sizeof(errorMsg))); 136 success = false; 48 137 } else { 49 inet_aton(localAddress.c_str(),&(my_addr.sin_addr)); 138 // now block with a timeout 139 struct timeval tv; 140 if (timeout != 0) { 141 tv.tv_sec = timeout / 1000; // timeout is in ms 142 tv.tv_usec = (timeout % 1000) * 1000; 143 } 144 fd_set wset; 145 FD_ZERO(&wset); 146 FD_SET(socket, &wset); 147 int ret = 148 select(socket + 1, NULL, &wset, NULL, 149 (timeout == 0) ? NULL : &tv); // man 2 connect EINPROGRESS 150 if (ret < 0) { 151 Err("select: %s\n", strerror_r(errno, errorMsg, sizeof(errorMsg))); 152 success = false; 153 } else { 154 if (ret == 0) { 155 // timeout reached 156 // Err("timeout reached\n"); 157 success = false; 158 } else { 159 // something happened on our socket. Check if an error occured 160 int error; 161 socklen_t len = sizeof(error); 162 if (getsockopt(socket, SOL_SOCKET, SO_ERROR, &error, &len) != 0) { 163 // Err("getsockopt: 164 // %s\n",strerror_r(errno,errorMsg,sizeof(errorMsg))); 165 success = false; 166 } else if (error != 0) { 167 // Err("socket error: 168 // %d(%s)\n",error,strerror_r(error,errorMsg,sizeof(errorMsg))); 169 success = false; 170 } else { 171 if (connect(socket, (sockaddr *)&serv_addr, sizeof(serv_addr)) == 172 -1) { 173 success = false; 174 } else { 175 // Info("connected indeed ^^\n"); 176 success = true; 177 } 178 } 179 } 180 } 50 181 } 51 memset(&(my_addr.sin_zero), '\0', 8); 52 53 if (bind(socket,(sockaddr*)&my_addr,sizeof(my_addr))<0) { 54 char errorMsg[256]; 55 Err("TCP bind, %s\n",strerror_r(errno,errorMsg,sizeof(errorMsg))); 56 } 57 58 listen(socket,1); 59 } 60 61 TcpSocket *TcpSocket::Accept(Time timeout) { 62 char errorMsg[256]; 63 TcpSocket *acceptedSocket=nullptr; 64 182 } else { 183 success = true; // never reached suprisingly... 184 } 185 // switch back to blocking mode (default) 186 fcntl(socket, F_SETFL, flags); 187 188 if (!success) { 189 close(socket); 190 // Info("Debug: Connect to %s:%d failed\n", distantAddress.c_str(), 191 // distantPort); 192 return false; 193 } else { 194 isConnected = true; 195 this->distantPort = distantPort; 196 this->distantAddress = distantAddress; 197 // Info("Debug: Connect to %s:%d succeeded\n", distantAddress.c_str(), 198 // distantPort); 199 return true; 200 } 201 } 202 203 ssize_t TcpSocket::SendMessage(const char *buffer, size_t bufferSize, 204 Time timeout) { 205 int flags = 0; 206 if (!blockOnSend) { 207 flags |= MSG_DONTWAIT; 208 } else { 65 209 struct timeval tv; 66 if (timeout!=0) { 67 tv.tv_sec=timeout/1000; //timeout is in ms 68 tv.tv_usec=(timeout%1000)*1000; 69 } 70 fd_set rset; 71 FD_ZERO(&rset); 72 FD_SET(socket, &rset); 73 int ret=select(socket + 1, &rset, nullptr, nullptr,(timeout==0)?nullptr:&tv); //man 2 accept 74 if (ret<0) { 75 Err("select: %s\n",strerror_r(errno,errorMsg,sizeof(errorMsg))); 76 } else { 77 if (ret==0) { 78 //timeout reached 79 //Err("timeout reached\n"); 80 } else { 81 //our socket is readable, a new connection can be accepted 82 acceptedSocket=new TcpSocket(this->Parent(),this->ObjectName(),blockOnSend,blockOnReceive); 83 sockaddr_in their_addr; 84 socklen_t namelen = sizeof(their_addr); 85 if ((acceptedSocket->socket=accept(socket,(sockaddr*)&their_addr, &namelen))<0) { 86 Err("error: %s\n",strerror_r(errno,errorMsg,sizeof(errorMsg))); 87 delete acceptedSocket; 88 acceptedSocket=nullptr; 89 } 90 } 91 } 92 93 return acceptedSocket; 94 } 95 96 bool TcpSocket::Connect(const unsigned int distantPort,const std::string distantAddress,Time timeout) { 97 bool success=false; 98 char errorMsg[256]; 99 100 if (isConnected) { 101 if (this->distantPort==distantPort && this->distantAddress==distantAddress) { 102 return true; 103 } else { 104 close(socket); 105 } 106 } 107 socket=::socket(AF_INET,SOCK_STREAM,0); 108 if (socket==-1) return false; 109 110 sockaddr_in serv_addr; 111 serv_addr.sin_family = AF_INET; 112 serv_addr.sin_port = htons(short(distantPort)); 113 if (inet_pton(AF_INET, distantAddress.c_str(), &serv_addr.sin_addr) <= 0) { 114 printf("incorrect network address."); 115 close(socket); 116 return false; 117 } 118 memset(&(serv_addr.sin_zero), '\0', 8); 119 120 //go non blocking 121 int flags=fcntl(socket, F_GETFL); 122 fcntl(socket, F_SETFL, flags | O_NONBLOCK); 123 if (connect(socket, (sockaddr*)&serv_addr, sizeof(serv_addr))==-1) { 124 if ((errno != EINPROGRESS) && (errno != EAGAIN)){ 125 Err("socket connect: %s\n",strerror_r(errno,errorMsg,sizeof(errorMsg))); 126 success=false; 127 } else { 128 //now block with a timeout 129 struct timeval tv; 130 if (timeout!=0) { 131 tv.tv_sec=timeout/1000; //timeout is in ms 132 tv.tv_usec=(timeout%1000)*1000; 133 } 134 fd_set wset; 135 FD_ZERO(&wset); 136 FD_SET(socket, &wset); 137 int ret=select(socket + 1, NULL, &wset, NULL,(timeout==0)?NULL:&tv); //man 2 connect EINPROGRESS 138 if (ret<0) { 139 Err("select: %s\n",strerror_r(errno,errorMsg,sizeof(errorMsg))); 140 success=false; 141 } else { 142 if (ret==0) { 143 //timeout reached 144 //Err("timeout reached\n"); 145 success=false; 146 } else { 147 //something happened on our socket. Check if an error occured 148 int error; 149 socklen_t len = sizeof(error); 150 if (getsockopt(socket, SOL_SOCKET, SO_ERROR, &error, &len)!=0) { 151 //Err("getsockopt: %s\n",strerror_r(errno,errorMsg,sizeof(errorMsg))); 152 success=false; 153 } else if (error!=0) { 154 //Err("socket error: %d(%s)\n",error,strerror_r(error,errorMsg,sizeof(errorMsg))); 155 success=false; 156 } else { 157 if (connect(socket, (sockaddr*)&serv_addr, sizeof(serv_addr))==-1) { 158 success=false; 159 } else { 160 //Info("connected indeed ^^\n"); 161 success=true; 162 } 163 } 164 } 165 } 166 } 167 } else { 168 success=true; //never reached suprisingly... 169 } 170 //switch back to blocking mode (default) 171 fcntl(socket, F_SETFL, flags); 172 173 if (!success) { 174 close(socket); 175 //Info("Debug: Connect to %s:%d failed\n", distantAddress.c_str(), distantPort); 176 return false; 177 } else { 178 isConnected=true; 179 this->distantPort=distantPort; 180 this->distantAddress=distantAddress; 181 //Info("Debug: Connect to %s:%d succeeded\n", distantAddress.c_str(), distantPort); 182 return true; 183 } 184 } 185 186 ssize_t TcpSocket::SendMessage(const char* buffer,size_t bufferSize,Time timeout){ 187 int flags=0; 188 if (!blockOnSend) { 189 flags|=MSG_DONTWAIT; 190 } else { 191 struct timeval tv; 192 tv.tv_sec=timeout/1000; //timeout is in ms 193 tv.tv_usec=(timeout%1000)*1000; 194 195 setsockopt(socket,SOL_SOCKET,SO_SNDTIMEO,(char *)&tv,sizeof(struct timeval)); 196 } 197 ssize_t bytesSent=send(socket, buffer, bufferSize, flags); 198 199 return bytesSent; 200 } 201 202 ssize_t TcpSocket::RecvMessage(char* buffer,size_t bufferSize,Time timeout){ 203 int flags=0; 204 if (!blockOnReceive) { 205 flags|=MSG_DONTWAIT; 206 } else { 207 struct timeval tv; 208 tv.tv_sec=timeout/1000; //timeout is in ms 209 tv.tv_usec=(timeout%1000)*1000; 210 211 setsockopt(socket,SOL_SOCKET,SO_RCVTIMEO,(char *)&tv,sizeof(struct timeval)); 212 } 213 ssize_t bytesRead=recv(socket,buffer,bufferSize,flags); 214 215 return bytesRead; 216 } 217 218 uint16_t TcpSocket::NetworkToHost16(uint16_t data) { 219 return ntohs(data); 220 } 221 222 uint16_t TcpSocket::HostToNetwork16(uint16_t data) { 223 return htons(data); 224 } 225 226 uint32_t TcpSocket::NetworkToHost32(uint32_t data) { 227 return ntohl(data); 228 } 229 230 uint32_t TcpSocket::HostToNetwork32(uint32_t data) { 231 return htonl(data); 232 } 210 tv.tv_sec = timeout / 1000; // timeout is in ms 211 tv.tv_usec = (timeout % 1000) * 1000; 212 213 setsockopt(socket, SOL_SOCKET, SO_SNDTIMEO, (char *)&tv, 214 sizeof(struct timeval)); 215 } 216 ssize_t bytesSent = send(socket, buffer, bufferSize, flags); 217 218 return bytesSent; 219 } 220 221 ssize_t TcpSocket::RecvMessage(char *buffer, size_t bufferSize, Time timeout) { 222 int flags = 0; 223 if (!blockOnReceive) { 224 flags |= MSG_DONTWAIT; 225 } else { 226 struct timeval tv; 227 tv.tv_sec = timeout / 1000; // timeout is in ms 228 tv.tv_usec = (timeout % 1000) * 1000; 229 230 setsockopt(socket, SOL_SOCKET, SO_RCVTIMEO, (char *)&tv, 231 sizeof(struct timeval)); 232 } 233 ssize_t bytesRead = recv(socket, buffer, bufferSize, flags); 234 235 return bytesRead; 236 } 237 238 uint16_t TcpSocket::NetworkToHost16(uint16_t data) { return ntohs(data); } 239 240 uint16_t TcpSocket::HostToNetwork16(uint16_t data) { return htons(data); } 241 242 uint32_t TcpSocket::NetworkToHost32(uint32_t data) { return ntohl(data); } 243 244 uint32_t TcpSocket::HostToNetwork32(uint32_t data) { return htonl(data); } 233 245 234 246 } // end namespace core -
trunk/lib/FlairCore/src/TcpSocket.h
r2 r15 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 42 43 44 45 46 47 48 49 45 private: 46 int socket; // socket file descriptor 47 bool blockOnSend; 48 bool blockOnReceive; 49 bool isConnected; 50 unsigned int distantPort; 51 std::string distantAddress; 52 }; 50 53 51 54 } // end namespace core -
trunk/lib/FlairCore/src/TextEdit.cpp
r2 r15 22 22 using std::string; 23 23 24 namespace flair 25 { 26 namespace gui 27 { 24 namespace flair { 25 namespace gui { 28 26 29 TextEdit::TextEdit(const LayoutPosition * position,string name,size_t buf_size): Widget(position->getLayout(),name,"TextEdit")30 {31 SetVolatileXmlProp("row",position->Row());32 SetVolatileXmlProp("col",position->Col());33 27 TextEdit::TextEdit(const LayoutPosition *position, string name, size_t buf_size) 28 : Widget(position->getLayout(), name, "TextEdit") { 29 SetVolatileXmlProp("row", position->Row()); 30 SetVolatileXmlProp("col", position->Col()); 31 SendXml(); 34 32 35 33 delete position; 36 34 37 // text_node=AddXmlChild("Text");35 // text_node=AddXmlChild("Text"); 38 36 39 printf_buffer=(char*)malloc(buf_size); 40 if(printf_buffer==NULL) Err("erreur malloc\n"); 37 printf_buffer = (char *)malloc(buf_size); 38 if (printf_buffer == NULL) 39 Err("erreur malloc\n"); 41 40 } 42 41 43 TextEdit::~TextEdit() 44 { 45 free(printf_buffer); 46 } 42 TextEdit::~TextEdit() { free(printf_buffer); } 47 43 44 void TextEdit::Append(const char *format, ...) { 45 int n; 48 46 49 void TextEdit::Append(const char * format, ...) 50 { 51 int n; 47 va_list args; 48 va_start(args, format); 49 n = vsprintf(printf_buffer, format, args); 50 va_end(args); 51 if (n <= 0) 52 return; 52 53 53 va_list args; 54 va_start(args, format); 55 n = vsprintf(printf_buffer,format, args); 56 va_end (args); 57 if (n<=0) return; 58 59 SetVolatileXmlProp("value",printf_buffer,text_node); 60 SendXml(); 61 54 SetVolatileXmlProp("value", printf_buffer, text_node); 55 SendXml(); 62 56 } 63 57 -
trunk/lib/FlairCore/src/TextEdit.h
r2 r15 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 TextEdit 26 * 27 * \brief Class displaying a QTextEdit on the ground station 28 * 29 * QTextEdit allows printing on multiple lines. \n 30 * 31 */ 32 class TextEdit:public Widget 33 { 34 public: 35 /*! 36 * \brief Constructor 37 * 38 * Construct a QTabWidget at given position. \n 39 * The TextEdit will automatically be child of position->getLayout() Layout. After calling this constructor, 40 * position will be deleted as it is no longer usefull. 41 * 42 * \param parent parent 43 * \param name name 44 * \param buf_size size of the text buffer 45 */ 46 TextEdit(const LayoutPosition* position,std::string name,size_t buf_size=255); 23 /*! \class TextEdit 24 * 25 * \brief Class displaying a QTextEdit on the ground station 26 * 27 * QTextEdit allows printing on multiple lines. \n 28 * 29 */ 30 class TextEdit : public Widget { 31 public: 32 /*! 33 * \brief Constructor 34 * 35 * Construct a QTabWidget at given position. \n 36 * The TextEdit will automatically be child of position->getLayout() Layout. 37 *After calling this constructor, 38 * position will be deleted as it is no longer usefull. 39 * 40 * \param parent parent 41 * \param name name 42 * \param buf_size size of the text buffer 43 */ 44 TextEdit(const LayoutPosition *position, std::string name, 45 size_t buf_size = 255); 47 46 48 49 50 51 52 47 /*! 48 * \brief Destructor 49 * 50 */ 51 ~TextEdit(); 53 52 54 55 56 57 58 59 void Append(const char *format, ...);53 /*! 54 * \brief Append a line 55 * 56 * \param format text string to display, see standard printf 57 */ 58 void Append(const char *format, ...); 60 59 61 62 char*printf_buffer;63 64 60 private: 61 char *printf_buffer; 62 xmlNodePtr text_node; 63 }; 65 64 66 65 } // end namespace gui -
trunk/lib/FlairCore/src/Thread.cpp
r2 r15 27 27 using std::string; 28 28 29 namespace flair 30 { 31 namespace core 32 { 29 namespace flair { 30 namespace core { 33 31 34 Thread::Thread(const Object * parent,string name,uint8_t priority): Object(parent,name,"Thread")35 {36 pimpl_=new Thread_impl(this,priority);32 Thread::Thread(const Object *parent, string name, uint8_t priority) 33 : Object(parent, name, "Thread") { 34 pimpl_ = new Thread_impl(this, priority); 37 35 } 38 36 39 Thread::~Thread() 40 { 41 delete pimpl_; 42 } 37 Thread::~Thread() { delete pimpl_; } 43 38 44 void Thread::Start(void) 45 { 46 pimpl_->Start(); 47 } 39 void Thread::Start(void) { pimpl_->Start(); } 48 40 49 void Thread::SafeStop(void) 50 { 51 pimpl_->SafeStop(); 52 } 41 void Thread::SafeStop(void) { pimpl_->SafeStop(); } 53 42 54 bool Thread::ToBeStopped(void) const 55 { 56 return pimpl_->ToBeStopped(); 57 } 43 bool Thread::ToBeStopped(void) const { return pimpl_->ToBeStopped(); } 58 44 59 45 #ifdef __XENO__ 60 void Thread::WarnUponSwitches(bool value) 61 { 62 // Ask Xenomai to warn us upon switches to secondary mode. 63 if(value==true) 64 { 65 rt_task_set_mode(0, T_WARNSW, NULL); 66 } 67 else 68 { 69 rt_task_set_mode(T_WARNSW, 0, NULL); 70 } 46 void Thread::WarnUponSwitches(bool value) { 47 // Ask Xenomai to warn us upon switches to secondary mode. 48 if (value == true) { 49 rt_task_set_mode(0, T_WARNSW, NULL); 50 } else { 51 rt_task_set_mode(T_WARNSW, 0, NULL); 52 } 71 53 } 72 54 #else 73 void Thread::WarnUponSwitches(bool value) 74 { 75 //Warn("Not applicable in non real time\n"); 55 void Thread::WarnUponSwitches(bool value) { 56 // Warn("Not applicable in non real time\n"); 76 57 } 77 58 #endif 78 59 79 void Thread::Join(void) 80 { 81 pimpl_->Join(); 60 void Thread::Join(void) { pimpl_->Join(); } 61 62 void Thread::SetPeriodUS(uint32_t period) { pimpl_->SetPeriodUS(period); } 63 64 uint32_t Thread::GetPeriodUS(void) const { return pimpl_->GetPeriodUS(); } 65 66 void Thread::SetPeriodMS(uint32_t period) { pimpl_->SetPeriodMS(period); } 67 68 uint32_t Thread::GetPeriodMS(void) const { return pimpl_->GetPeriodMS(); } 69 70 bool Thread::IsPeriodSet(void) { return pimpl_->period_set; } 71 72 void Thread::WaitPeriod(void) const { pimpl_->WaitPeriod(); } 73 74 void Thread::Suspend(void) { pimpl_->Suspend(); } 75 76 bool Thread::SuspendUntil(Time date) { return pimpl_->SuspendUntil(date); } 77 78 bool Thread::IsSuspended(void) const { return pimpl_->IsSuspended(); } 79 80 void Thread::Resume(void) { pimpl_->Resume(); } 81 82 int Thread::WaitUpdate(const IODevice *device) { 83 return pimpl_->WaitUpdate(device); 82 84 } 83 85 84 void Thread::SetPeriodUS(uint32_t period) { 85 pimpl_->SetPeriodUS(period); 86 } 87 88 uint32_t Thread::GetPeriodUS(void) const { 89 return pimpl_->GetPeriodUS(); 90 } 91 92 void Thread::SetPeriodMS(uint32_t period) { 93 pimpl_->SetPeriodMS(period); 94 } 95 96 uint32_t Thread::GetPeriodMS(void) const { 97 return pimpl_->GetPeriodMS(); 98 } 99 100 101 bool Thread::IsPeriodSet(void) 102 { 103 return pimpl_->period_set; 104 } 105 106 void Thread::WaitPeriod(void) const 107 { 108 pimpl_->WaitPeriod(); 109 } 110 111 void Thread::Suspend(void) 112 { 113 pimpl_->Suspend(); 114 } 115 116 bool Thread::SuspendUntil(Time date){ 117 return pimpl_->SuspendUntil(date); 118 } 119 120 bool Thread::IsSuspended(void) const 121 { 122 return pimpl_->IsSuspended(); 123 } 124 125 void Thread::Resume(void) 126 { 127 pimpl_->Resume(); 128 } 129 130 int Thread::WaitUpdate(const IODevice* device) 131 { 132 return pimpl_->WaitUpdate(device); 133 } 134 135 void Thread::SleepUntil(Time time) const 136 { 86 void Thread::SleepUntil(Time time) const { 137 87 #ifdef __XENO__ 138 int status=rt_task_sleep_until(time);139 if(status!=0) Err("%s, error rt_task_sleep_until (%s), resume time: %lld, actual time: %lld\n",140 ObjectName().c_str(),141 strerror(-status),142 time,143 GetTime()); 144 //Printf("rt_task_sleep_until, resume time: %lld, actual time:%lld\n",time,GetTime());88 int status = rt_task_sleep_until(time); 89 if (status != 0) 90 Err("%s, error rt_task_sleep_until (%s), resume time: %lld, actual time: " 91 "%lld\n", 92 ObjectName().c_str(), strerror(-status), time, GetTime()); 93 // Printf("rt_task_sleep_until, resume time: %lld, actual time: 94 // %lld\n",time,GetTime()); 145 95 #else 146 Time current=GetTime(); 147 if(current<time) 148 { 149 usleep((time-current)/1000); 150 } 96 Time current = GetTime(); 97 if (current < time) { 98 usleep((time - current) / 1000); 99 } 151 100 #endif 152 101 } 153 102 154 void Thread::SleepMS(uint32_t time) const 155 { 103 void Thread::SleepMS(uint32_t time) const { 156 104 #ifdef __XENO__ 157 int status=rt_task_sleep(time*1000*1000); 158 if(status!=0) Err("erreur rt_task_sleep (%s)\n",strerror(-status)); 105 int status = rt_task_sleep(time * 1000 * 1000); 106 if (status != 0) 107 Err("erreur rt_task_sleep (%s)\n", strerror(-status)); 159 108 #else 160 usleep(time*1000);109 usleep(time * 1000); 161 110 #endif 162 111 } 163 112 164 void Thread::SleepUS(uint32_t time) const 165 { 113 void Thread::SleepUS(uint32_t time) const { 166 114 #ifdef __XENO__ 167 int status=rt_task_sleep(time*1000); 168 if(status!=0) Err("erreur rt_task_sleep (%s)\n",strerror(-status)); 115 int status = rt_task_sleep(time * 1000); 116 if (status != 0) 117 Err("erreur rt_task_sleep (%s)\n", strerror(-status)); 169 118 #else 170 119 usleep(time); 171 120 #endif 172 121 } -
trunk/lib/FlairCore/src/Thread.h
r2 r15 19 19 class Thread_impl; 20 20 21 namespace flair 22 { 23 namespace core 24 { 25 26 class IODevice; 27 28 /*! \class Thread 29 * 30 * \brief Abstract class for a thread 31 * 32 * To implement a thread, Run() method must be reimplemented. \n 33 * When Start() is called, it will automatically call Run() reimplemented method. 34 * A thread can be periodic, in this case WaitPeriod() will block untill period is met. 35 * Thread can also e synnchronized with an IODevice, using WaitUpdate() method. \n 36 * Thread period is by default 100ms. 37 */ 38 class Thread: public Object 39 { 40 friend class ::Thread_impl; 41 42 public: 43 /*! 44 * \brief Constructor 45 * 46 * \param parent parent 47 * \param name name 48 * \param priority priority, should be >20 (<20 is reserved for internal use) 49 */ 50 Thread(const Object* parent,std::string name,uint8_t priority);//priority>20, for real time only 51 52 /*! 53 * \brief Destructor 54 * 55 * If thread is started, SafeStop() and Join() will 56 * be automatically called. 57 * 58 */ 59 virtual ~Thread(); 60 61 /*! 62 * \brief Start the thread 63 * 64 */ 65 void Start(void); 66 67 /*! 68 * \brief Set a stop flag 69 * 70 * ToBeStopped() will return true after calling this method. 71 */ 72 void SafeStop(void); 73 74 /*! 75 * \brief Set a stop flag 76 * 77 * Reimplemented Run() can poll this method to 78 * determine when to stop the thread. 79 * 80 * \return true if SafeStop() was called 81 */ 82 bool ToBeStopped(void) const; 83 84 /*! 85 * \brief Join the thread 86 * 87 * This method will block untill Run() returns. 88 * 89 */ 90 void Join(void); 91 92 /*! 93 * \brief Set the period in micro second 94 * 95 * After calling this method, IsPeriodSet will return true. 96 * 97 * \param period_us period in us 98 */ 99 void SetPeriodUS(uint32_t period_us); 100 101 uint32_t GetPeriodUS() const; 102 103 /*! 104 * \brief Set the period in milli second 105 * 106 * After calling this method, IsPeriodSet will return true. 107 * 108 * \param period_ums period in ms 109 */ 110 void SetPeriodMS(uint32_t period_ms); 111 112 uint32_t GetPeriodMS() const; 113 114 /*! 115 * \brief Returns if period was set 116 * 117 * \return true if a period was set using SetPeriodUS or SetPeriodMS 118 * false otherwise 119 */ 120 bool IsPeriodSet(void); 121 122 /*! 123 * \brief Wait the period 124 * 125 * This method will block untill period is met. \n 126 * If no period was set (see SetPeriodUS, SetPeriodMS and IsPeriodSet), this method 127 * returns immediately. 128 * 129 */ 130 void WaitPeriod(void) const; 131 132 /*! 133 * \brief Wait update of an IODevice 134 * 135 * This method will block untill IODevice::ProcessUpdate 136 * is called. \n 137 * This method is usefull to synchronize a thread with an IODevice. 138 * 139 * \param device IODevice to wait update from 140 */ 141 int WaitUpdate(const IODevice* device); 142 143 /*! 144 * \brief Suspend the thread 145 * 146 * This method will block untill Resume() is called. 147 * 148 */ 149 void Suspend(void); 150 151 /*! 152 * \brief Suspend the thread with timeout 153 * 154 * This method will block until Resume() is called or the absolute date specified occurs 155 * 156 * \param date absolute date in ns 157 * \return true if thread is woken up by a call to Resume, false otherwise 158 */ 159 bool SuspendUntil(Time date); 160 161 /*! 162 * \brief Resume the thread 163 * 164 * This method will unblock the call to Suspend(). 165 * 166 */ 167 void Resume(void); 168 169 /*! 170 * \brief Is the thread suspended? 171 * 172 * \return true if thread is suspended 173 * 174 */ 175 bool IsSuspended(void) const; 176 177 /*! 178 * \brief Sleep until absolute time 179 * 180 * This method will block untill time is reached. 181 * 182 * \param time absolute time 183 */ 184 void SleepUntil(Time time) const; 185 186 /*! 187 * \brief Sleep for a certain time in micro second 188 * 189 * This method will block untill time is elapsed. 190 * 191 * \param time_us time to wait in micro second 192 */ 193 void SleepUS(uint32_t time_us) const; 194 195 /*! 196 * \brief Sleep for a cartain time in milli second 197 * 198 * This method will block untill time is elapsed. 199 * 200 * \param time_ms time to wait in milli second 201 */ 202 void SleepMS(uint32_t time_ms) const; 203 204 /*! 205 * \brief Warn if real time / non real time switches occur 206 * 207 * If enabled, a message with the call stack will be displayed 208 * in case of real time / non real time switches. \n 209 * This method can help to debug application and see if switches occur. \n 210 * Note that it as no effect if this method is called from the non real time 211 * Framework library. 212 * 213 * \param enable enable or disable warns 214 */ 215 static void WarnUponSwitches(bool enable); 216 217 private: 218 /*! 219 * \brief Run method 220 * 221 * This method is automatically called by Start(). \n 222 * This method must be reimplemented, in order to implement the thread. 223 * 224 */ 225 virtual void Run(void)=0; 226 227 class Thread_impl* pimpl_; 228 }; 21 namespace flair { 22 namespace core { 23 24 class IODevice; 25 26 /*! \class Thread 27 * 28 * \brief Abstract class for a thread 29 * 30 * To implement a thread, Run() method must be reimplemented. \n 31 * When Start() is called, it will automatically call Run() reimplemented method. 32 * A thread can be periodic, in this case WaitPeriod() will block untill period 33 *is met. 34 * Thread can also e synnchronized with an IODevice, using WaitUpdate() method. 35 *\n 36 * Thread period is by default 100ms. 37 */ 38 class Thread : public Object { 39 friend class ::Thread_impl; 40 41 public: 42 /*! 43 * \brief Constructor 44 * 45 * \param parent parent 46 * \param name name 47 * \param priority priority, should be >20 (<20 is reserved for internal use) 48 */ 49 Thread(const Object *parent, std::string name, 50 uint8_t priority); // priority>20, for real time only 51 52 /*! 53 * \brief Destructor 54 * 55 * If thread is started, SafeStop() and Join() will 56 * be automatically called. 57 * 58 */ 59 virtual ~Thread(); 60 61 /*! 62 * \brief Start the thread 63 * 64 */ 65 void Start(void); 66 67 /*! 68 * \brief Set a stop flag 69 * 70 * ToBeStopped() will return true after calling this method. 71 */ 72 void SafeStop(void); 73 74 /*! 75 * \brief Set a stop flag 76 * 77 * Reimplemented Run() can poll this method to 78 * determine when to stop the thread. 79 * 80 * \return true if SafeStop() was called 81 */ 82 bool ToBeStopped(void) const; 83 84 /*! 85 * \brief Join the thread 86 * 87 * This method will block untill Run() returns. 88 * 89 */ 90 void Join(void); 91 92 /*! 93 * \brief Set the period in micro second 94 * 95 * After calling this method, IsPeriodSet will return true. 96 * 97 * \param period_us period in us 98 */ 99 void SetPeriodUS(uint32_t period_us); 100 101 uint32_t GetPeriodUS() const; 102 103 /*! 104 * \brief Set the period in milli second 105 * 106 * After calling this method, IsPeriodSet will return true. 107 * 108 * \param period_ums period in ms 109 */ 110 void SetPeriodMS(uint32_t period_ms); 111 112 uint32_t GetPeriodMS() const; 113 114 /*! 115 * \brief Returns if period was set 116 * 117 * \return true if a period was set using SetPeriodUS or SetPeriodMS 118 * false otherwise 119 */ 120 bool IsPeriodSet(void); 121 122 /*! 123 * \brief Wait the period 124 * 125 * This method will block untill period is met. \n 126 * If no period was set (see SetPeriodUS, SetPeriodMS and IsPeriodSet), this 127 *method 128 * returns immediately. 129 * 130 */ 131 void WaitPeriod(void) const; 132 133 /*! 134 * \brief Wait update of an IODevice 135 * 136 * This method will block untill IODevice::ProcessUpdate 137 * is called. \n 138 * This method is usefull to synchronize a thread with an IODevice. 139 * 140 * \param device IODevice to wait update from 141 */ 142 int WaitUpdate(const IODevice *device); 143 144 /*! 145 * \brief Suspend the thread 146 * 147 * This method will block untill Resume() is called. 148 * 149 */ 150 void Suspend(void); 151 152 /*! 153 * \brief Suspend the thread with timeout 154 * 155 * This method will block until Resume() is called or the absolute date 156 *specified occurs 157 * 158 * \param date absolute date in ns 159 * \return true if thread is woken up by a call to Resume, false otherwise 160 */ 161 bool SuspendUntil(Time date); 162 163 /*! 164 * \brief Resume the thread 165 * 166 * This method will unblock the call to Suspend(). 167 * 168 */ 169 void Resume(void); 170 171 /*! 172 * \brief Is the thread suspended? 173 * 174 * \return true if thread is suspended 175 * 176 */ 177 bool IsSuspended(void) const; 178 179 /*! 180 * \brief Sleep until absolute time 181 * 182 * This method will block untill time is reached. 183 * 184 * \param time absolute time 185 */ 186 void SleepUntil(Time time) const; 187 188 /*! 189 * \brief Sleep for a certain time in micro second 190 * 191 * This method will block untill time is elapsed. 192 * 193 * \param time_us time to wait in micro second 194 */ 195 void SleepUS(uint32_t time_us) const; 196 197 /*! 198 * \brief Sleep for a cartain time in milli second 199 * 200 * This method will block untill time is elapsed. 201 * 202 * \param time_ms time to wait in milli second 203 */ 204 void SleepMS(uint32_t time_ms) const; 205 206 /*! 207 * \brief Warn if real time / non real time switches occur 208 * 209 * If enabled, a message with the call stack will be displayed 210 * in case of real time / non real time switches. \n 211 * This method can help to debug application and see if switches occur. \n 212 * Note that it as no effect if this method is called from the non real time 213 * Framework library. 214 * 215 * \param enable enable or disable warns 216 */ 217 static void WarnUponSwitches(bool enable); 218 219 private: 220 /*! 221 * \brief Run method 222 * 223 * This method is automatically called by Start(). \n 224 * This method must be reimplemented, in order to implement the thread. 225 * 226 */ 227 virtual void Run(void) = 0; 228 229 class Thread_impl *pimpl_; 230 }; 229 231 230 232 } // end namespace core -
trunk/lib/FlairCore/src/Thread_impl.cpp
r2 r15 33 33 using namespace flair::core; 34 34 35 Thread_impl::Thread_impl(Thread* self,uint8_t priority) 36 { 37 isRunning=false; 38 tobestopped=false; 39 is_suspended=false; 40 period_set=false; 41 42 this->self=self; 43 cond=new ConditionVariable(self,self->ObjectName()); 44 45 if(priority<MIN_THREAD_PRIORITY) 46 { 47 priority=MIN_THREAD_PRIORITY; 48 // printf("Thread::Thread, %s: priority set to %i\n",self->ObjectName().c_str(), priority); 35 Thread_impl::Thread_impl(Thread *self, uint8_t priority) { 36 isRunning = false; 37 tobestopped = false; 38 is_suspended = false; 39 period_set = false; 40 41 this->self = self; 42 cond = new ConditionVariable(self, self->ObjectName()); 43 44 if (priority < MIN_THREAD_PRIORITY) { 45 priority = MIN_THREAD_PRIORITY; 46 // printf("Thread::Thread, %s: priority set to 47 // %i\n",self->ObjectName().c_str(), priority); 48 } 49 if (priority > MAX_THREAD_PRIORITY) { 50 priority = MAX_THREAD_PRIORITY; 51 self->Warn("priority set to %i\n", MAX_THREAD_PRIORITY); 52 } 53 54 this->priority = priority; 55 period = 100 * 1000 * 1000; // 100ms par defaut 56 min_jitter = 1000 * 1000 * 1000; 57 max_jitter = 0; 58 mean_jitter = 0; 59 last = 0; 60 cpt = 0; 61 } 62 63 Thread_impl::~Thread_impl() { 64 SafeStop(); 65 Join(); 66 } 67 68 void Thread_impl::Start(void) { 69 int status; 70 71 isRunning = true; 72 73 #ifdef __XENO__ 74 string th_name = 75 getFrameworkManager()->ObjectName() + "-" + self->ObjectName(); 76 77 #ifdef RT_STACK_SIZE 78 status = rt_task_create(&task_rt, th_name.c_str(), RT_STACK_SIZE, 79 (int)priority, T_JOINABLE); 80 #else 81 status = 82 rt_task_create(&task_rt, th_name.c_str(), 0, (int)priority, T_JOINABLE); 83 #endif // RT_STACK_SIZE 84 if (status != 0) { 85 self->Err("rt_task_create error (%s)\n", strerror(-status)); 86 } else { 87 //_printf("rt_task_create ok %s\n",th_name); 88 } 89 90 status = rt_task_start(&task_rt, &main_rt, (void *)this); 91 if (status != 0) { 92 self->Err("rt_task_start error (%s)\n", strerror(-status)); 93 } else { 94 //_printf("rt_task_start ok %s\n",th_name); 95 } 96 97 // Initialise the rt_print buffer for this task explicitly 98 rt_print_init(512, th_name.c_str()); 99 100 #else //__XENO__ 101 102 // Initialize thread creation attributes 103 pthread_attr_t attr; 104 if (pthread_attr_init(&attr) != 0) { 105 self->Err("Error pthread_attr_init\n"); 106 } 107 108 #ifdef NRT_STACK_SIZE 109 if (pthread_attr_setstacksize(&attr, NRT_STACK_SIZE) != 0) { 110 self->Err("Error pthread_attr_setstacksize\n"); 111 } 112 #endif // NRT_STACK_SIZE 113 114 if (pthread_attr_setinheritsched(&attr, PTHREAD_EXPLICIT_SCHED) != 0) { 115 self->Err("Error pthread_attr_setinheritsched\n"); 116 } 117 118 if (pthread_attr_setschedpolicy(&attr, SCHED_FIFO) != 0) { 119 self->Err("Error pthread_attr_setschedpolicy\n"); 120 } 121 122 struct sched_param parm; 123 parm.sched_priority = priority; 124 if (pthread_attr_setschedparam(&attr, &parm) != 0) { 125 self->Err("Error pthread_attr_setschedparam\n"); 126 } 127 128 next_time = GetTime() + period; 129 130 if (pthread_create(&task_nrt, &attr, main_nrt, (void *)this) != 0) { 131 self->Err("pthread_create error\n"); 132 } 133 134 if (pthread_attr_destroy(&attr) != 0) { 135 self->Err("Error pthread_attr_destroy\n"); 136 } 137 138 #endif //__XENO__ 139 } 140 141 #ifdef __XENO__ 142 void Thread_impl::main_rt(void *arg) { 143 Thread_impl *caller = (Thread_impl *)arg; 144 145 // Perform auto-init of rt_print buffers if the task doesn't do so 146 rt_print_auto_init(1); 147 148 caller->self->Run(); 149 150 caller->PrintStats(); 151 } 152 #else 153 void *Thread_impl::main_nrt(void *arg) { 154 Thread_impl *caller = (Thread_impl *)arg; 155 156 caller->self->Run(); 157 158 caller->PrintStats(); 159 160 pthread_exit(0); 161 } 162 #endif //__XENO__ 163 164 void Thread_impl::SetPeriodUS(uint32_t period) { 165 if (period == 0) { 166 self->Err("Period must be>0\n"); 167 return; 168 } 169 170 #ifdef __XENO__ 171 int status = rt_task_set_periodic(&task_rt, TM_NOW, period * 1000); 172 if (status != 0) 173 self->Err("Error rt_task_set_periodic %s\n", strerror(-status)); 174 #else 175 next_time -= period; 176 next_time += period * 1000; 177 #endif 178 this->period = period * 1000; 179 period_set = true; 180 } 181 182 uint32_t Thread_impl::GetPeriodUS() const { return this->period / 1000; } 183 184 void Thread_impl::SetPeriodMS(uint32_t period) { 185 if (period == 0) { 186 self->Err("Period must be>0\n"); 187 return; 188 } 189 190 #ifdef __XENO__ 191 int status = rt_task_set_periodic(&task_rt, TM_NOW, period * 1000 * 1000); 192 if (status != 0) 193 self->Err("Error rt_task_set_periodic %s\n", strerror(-status)); 194 #else 195 next_time -= period; 196 next_time += period * 1000 * 1000; 197 #endif 198 this->period = period * 1000 * 1000; 199 period_set = true; 200 } 201 202 uint32_t Thread_impl::GetPeriodMS() const { return this->period / 1000 / 1000; } 203 204 void Thread_impl::WaitPeriod(void) { 205 if (period_set == false) { 206 self->Err("Period must be set befaore calling this method\n"); 207 return; 208 } 209 #ifdef __XENO__ 210 unsigned long overruns_r; 211 int status = rt_task_wait_period(&overruns_r); 212 if (status != 0) 213 self->Err("Error rt_task_wait_period %s\n", strerror(-status)); 214 if (status == -ETIMEDOUT) 215 self->Err("overrun: %lld\n", overruns_r); 216 #else 217 self->SleepUntil(next_time); 218 next_time += period; 219 #endif 220 ComputeJitter(GetTime()); 221 } 222 223 void Thread_impl::Suspend(void) { 224 if (isRunning == false) { 225 self->Err("thread is not started\n"); 226 return; 227 } 228 229 cond->GetMutex(), is_suspended = true; 230 cond->CondWait(); 231 is_suspended = false; 232 cond->ReleaseMutex(); 233 } 234 235 bool Thread_impl::SuspendUntil(Time date) { 236 if (isRunning == false) { 237 self->Err("thread is not started\n"); 238 return false; 239 } 240 241 cond->GetMutex(), is_suspended = true; 242 bool success = cond->CondWaitUntil(date); 243 is_suspended = false; 244 cond->ReleaseMutex(); 245 return success; 246 } 247 248 bool Thread_impl::IsSuspended(void) { 249 bool result; 250 251 cond->GetMutex(); 252 result = is_suspended; 253 cond->ReleaseMutex(); 254 255 return result; 256 } 257 258 void Thread_impl::Resume(void) { 259 if (isRunning == false) { 260 self->Err("thread is not started\n"); 261 return; 262 } 263 264 cond->GetMutex(); 265 if (is_suspended == true) { 266 cond->CondSignal(); 267 } else { 268 self->Err("thread is not suspended\n"); 269 } 270 cond->ReleaseMutex(); 271 } 272 273 int Thread_impl::WaitUpdate(const IODevice *device) { 274 int status = 0; 275 276 if (IsSuspended() == true) { 277 self->Err("thread is already supended\n"); 278 status = -1; 279 } else { 280 cond->GetMutex(); 281 282 if (device->pimpl_->SetToWake(self) == 0) { 283 is_suspended = true; 284 cond->CondWait(); 285 is_suspended = false; 286 } else { 287 self->Err("%s is already waiting an update\n", 288 device->ObjectName().c_str()); 289 status = -1; 49 290 } 50 if(priority>MAX_THREAD_PRIORITY) 51 { 52 priority=MAX_THREAD_PRIORITY; 53 self->Warn("priority set to %i\n",MAX_THREAD_PRIORITY); 54 } 55 56 this->priority=priority; 57 period=100*1000*1000;//100ms par defaut 58 min_jitter=1000*1000*1000; 59 max_jitter=0; 60 mean_jitter=0; 61 last=0; 62 cpt=0; 63 } 64 65 Thread_impl::~Thread_impl() 66 { 67 SafeStop(); 68 Join(); 69 } 70 71 void Thread_impl::Start(void) 72 { 73 int status; 74 75 isRunning=true; 76 77 #ifdef __XENO__ 78 string th_name=getFrameworkManager()->ObjectName()+ "-" + self->ObjectName(); 79 80 #ifdef RT_STACK_SIZE 81 status=rt_task_create(&task_rt, th_name.c_str(), RT_STACK_SIZE, (int)priority, T_JOINABLE); 82 #else 83 status=rt_task_create(&task_rt, th_name.c_str(), 0,(int)priority, T_JOINABLE); 84 #endif //RT_STACK_SIZE 85 if(status!=0) 86 { 87 self->Err("rt_task_create error (%s)\n",strerror(-status)); 88 } 89 else 90 { 91 //_printf("rt_task_create ok %s\n",th_name); 92 } 93 94 status=rt_task_start(&task_rt, &main_rt, (void*)this); 95 if(status!=0) 96 { 97 self->Err("rt_task_start error (%s)\n",strerror(-status)); 98 } 99 else 100 { 101 //_printf("rt_task_start ok %s\n",th_name); 102 } 103 104 // Initialise the rt_print buffer for this task explicitly 105 rt_print_init(512, th_name.c_str()); 106 107 #else //__XENO__ 108 109 // Initialize thread creation attributes 110 pthread_attr_t attr; 111 if(pthread_attr_init(&attr) != 0) 112 { 113 self->Err("Error pthread_attr_init\n"); 114 } 115 116 #ifdef NRT_STACK_SIZE 117 if(pthread_attr_setstacksize(&attr, NRT_STACK_SIZE) != 0) 118 { 119 self->Err("Error pthread_attr_setstacksize\n"); 120 } 121 #endif //NRT_STACK_SIZE 122 123 if(pthread_attr_setinheritsched(&attr,PTHREAD_EXPLICIT_SCHED)!=0) 124 { 125 self->Err("Error pthread_attr_setinheritsched\n"); 126 } 127 128 if(pthread_attr_setschedpolicy(&attr, SCHED_FIFO)!=0) 129 { 130 self->Err("Error pthread_attr_setschedpolicy\n"); 131 } 132 133 struct sched_param parm; 134 parm.sched_priority = priority; 135 if(pthread_attr_setschedparam(&attr,&parm)!=0) 136 { 137 self->Err("Error pthread_attr_setschedparam\n"); 138 } 139 140 next_time=GetTime()+period; 141 142 if(pthread_create(&task_nrt, &attr, main_nrt, (void*)this) != 0) 143 { 144 self->Err("pthread_create error\n"); 145 } 146 147 if(pthread_attr_destroy(&attr) != 0) 148 { 149 self->Err("Error pthread_attr_destroy\n"); 150 } 151 152 #endif //__XENO__ 153 } 154 155 #ifdef __XENO__ 156 void Thread_impl::main_rt(void * arg) 157 { 158 Thread_impl *caller = (Thread_impl*)arg; 159 160 // Perform auto-init of rt_print buffers if the task doesn't do so 161 rt_print_auto_init(1); 162 163 caller->self->Run(); 164 165 caller->PrintStats(); 166 } 167 #else 168 void* Thread_impl::main_nrt(void * arg) 169 { 170 Thread_impl *caller = (Thread_impl*)arg; 171 172 caller->self->Run(); 173 174 caller->PrintStats(); 175 176 pthread_exit(0); 177 } 178 #endif //__XENO__ 179 180 void Thread_impl::SetPeriodUS(uint32_t period) { 181 if(period==0) { 182 self->Err("Period must be>0\n"); 183 return; 184 } 185 186 #ifdef __XENO__ 187 int status=rt_task_set_periodic(&task_rt, TM_NOW, period*1000); 188 if(status!=0) self->Err("Error rt_task_set_periodic %s\n",strerror(-status)); 189 #else 190 next_time-=period; 191 next_time+=period*1000; 192 #endif 193 this->period=period*1000; 194 period_set=true; 195 } 196 197 uint32_t Thread_impl::GetPeriodUS() const { 198 return this->period/1000; 199 } 200 201 void Thread_impl::SetPeriodMS(uint32_t period) { 202 if(period==0) { 203 self->Err("Period must be>0\n"); 204 return; 205 } 206 207 #ifdef __XENO__ 208 int status=rt_task_set_periodic(&task_rt, TM_NOW, period*1000*1000); 209 if(status!=0) self->Err("Error rt_task_set_periodic %s\n",strerror(-status)); 210 #else 211 next_time-=period; 212 next_time+=period*1000*1000; 213 #endif 214 this->period=period*1000*1000; 215 period_set=true; 216 } 217 218 uint32_t Thread_impl::GetPeriodMS() const { 219 return this->period/1000/1000; 220 } 221 222 void Thread_impl::WaitPeriod(void) 223 { 224 if(period_set==false) 225 { 226 self->Err("Period must be set befaore calling this method\n"); 227 return; 228 } 229 #ifdef __XENO__ 230 unsigned long overruns_r; 231 int status=rt_task_wait_period(&overruns_r); 232 if(status!=0) self->Err("Error rt_task_wait_period %s\n",strerror(-status)); 233 if(status==-ETIMEDOUT) self->Err("overrun: %lld\n",overruns_r); 234 #else 235 self->SleepUntil(next_time); 236 next_time+=period; 237 #endif 238 ComputeJitter(GetTime()); 239 } 240 241 242 void Thread_impl::Suspend(void) { 243 if(isRunning==false) { 244 self->Err("thread is not started\n"); 245 return; 246 } 247 248 cond->GetMutex(), 249 is_suspended=true; 250 cond->CondWait(); 251 is_suspended=false; 291 252 292 cond->ReleaseMutex(); 253 } 254 255 bool Thread_impl::SuspendUntil(Time date) { 256 if(isRunning==false) { 257 self->Err("thread is not started\n"); 258 return false; 259 } 260 261 cond->GetMutex(), 262 is_suspended=true; 263 bool success=cond->CondWaitUntil(date); 264 is_suspended=false; 265 cond->ReleaseMutex(); 266 return success; 267 } 268 269 bool Thread_impl::IsSuspended(void) 270 { 271 bool result; 272 273 cond->GetMutex(); 274 result=is_suspended; 275 cond->ReleaseMutex(); 276 277 return result; 278 } 279 280 void Thread_impl::Resume(void) 281 { 282 if(isRunning==false) 283 { 284 self->Err("thread is not started\n"); 285 return; 286 } 287 288 cond->GetMutex(); 289 if(is_suspended==true) 290 { 291 cond->CondSignal(); 292 } 293 else 294 { 295 self->Err("thread is not suspended\n"); 296 } 297 cond->ReleaseMutex(); 298 } 299 300 int Thread_impl::WaitUpdate(const IODevice* device) 301 { 302 int status=0; 303 304 if(IsSuspended()==true) 305 { 306 self->Err("thread is already supended\n"); 307 status=-1; 308 } 309 else 310 { 311 cond->GetMutex(); 312 313 if(device->pimpl_->SetToWake(self)==0) 314 { 315 is_suspended=true; 316 cond->CondWait(); 317 is_suspended=false; 318 } 319 else 320 { 321 self->Err("%s is already waiting an update\n",device->ObjectName().c_str()); 322 status=-1; 323 } 324 325 cond->ReleaseMutex(); 326 } 327 328 return status; 329 } 330 331 void Thread_impl::PrintStats(void) 332 { 333 #ifdef __XENO__ 334 RT_TASK_INFO info; 335 336 int status=rt_task_inquire(NULL, &info); 337 if(status!=0) 338 { 339 self->Err("Error rt_task_inquire %s\n",strerror(-status)); 340 } 341 else 342 #endif 343 { 293 } 294 295 return status; 296 } 297 298 void Thread_impl::PrintStats(void) { 299 #ifdef __XENO__ 300 RT_TASK_INFO info; 301 302 int status = rt_task_inquire(NULL, &info); 303 if (status != 0) { 304 self->Err("Error rt_task_inquire %s\n", strerror(-status)); 305 } else 306 #endif 307 { 344 308 #ifndef __XENO__ 345 //if(last!=0)346 #endif 347 {348 Printf("Thread::%s :\n",self->ObjectName().c_str()); 349 }350 #ifdef __XENO__ 351 Printf(" number of context switches: %i\n",info.ctxswitches);352 Printf(" number of primary->secondary mode switch: %i\n",info.modeswitches);353 //printf("number of page faults: %i\n",info.pagefaults);354 Printf(" execution time (ms) in primary mode: %lld\n",info.exectime/1000000);309 // if(last!=0) 310 #endif 311 { Printf("Thread::%s :\n", self->ObjectName().c_str()); } 312 #ifdef __XENO__ 313 Printf(" number of context switches: %i\n", info.ctxswitches); 314 Printf(" number of primary->secondary mode switch: %i\n", 315 info.modeswitches); 316 // printf("number of page faults: %i\n",info.pagefaults); 317 Printf(" execution time (ms) in primary mode: %lld\n", 318 info.exectime / 1000000); 355 319 #else 356 320 /* … … 358 322 getrusage(RUSAGE_THREAD,&r_usage); 359 323 printf(" memory usage = %ld\n",r_usage.ru_maxrss); 360 printf("RUSAGE :ru_utime => %lld [sec] : %lld [usec], :ru_stime => %lld [sec] : %lld [usec] \n", 324 printf("RUSAGE :ru_utime => %lld [sec] : %lld [usec], :ru_stime => %lld 325 [sec] : %lld [usec] \n", 361 326 (int64_t)r_usage.ru_utime.tv_sec, (int64_t)r_usage.ru_utime.tv_usec, 362 (int64_t)r_usage.ru_stime.tv_sec, (int64_t)r_usage.ru_stime.tv_usec);*/ 363 #endif 364 if(last!=0) 365 { 366 Printf(" min jitter (ns): %lld\n",min_jitter); 367 Printf(" max jitter (ns): %lld\n",max_jitter); 368 Printf(" jitter moy (ns): %lld\n",mean_jitter/cpt); 369 Printf(" itertions: %lld\n",cpt); 370 } 327 (int64_t)r_usage.ru_stime.tv_sec, 328 (int64_t)r_usage.ru_stime.tv_usec);*/ 329 #endif 330 if (last != 0) { 331 Printf(" min jitter (ns): %lld\n", min_jitter); 332 Printf(" max jitter (ns): %lld\n", max_jitter); 333 Printf(" jitter moy (ns): %lld\n", mean_jitter / cpt); 334 Printf(" itertions: %lld\n", cpt); 371 335 } 372 } 373 374 void Thread_impl::Join(void) 375 { 376 if(isRunning==true) 377 { 378 int status; 379 380 #ifdef __XENO__ 381 status=rt_task_join(&task_rt); 382 #else 383 status=pthread_join(task_nrt,NULL); 384 #endif 385 if(status!=0) self->Err("error %s\n",strerror(-status)); 386 isRunning=false; 387 } 388 } 389 390 void Thread_impl::ComputeJitter(Time time) 391 { 392 Time diff,delta; 393 diff=time-last; 394 395 if(diff>=period) 396 { 397 delta=diff-period; 398 } 399 else 400 { 401 delta=period-diff; 402 } 403 //if(delta==0) rt_printf("%lld %lld\n",time,last); 404 last=time; 405 if(diff==time) return; 406 407 if(delta>max_jitter) max_jitter=delta; 408 if(delta<min_jitter) min_jitter=delta; 409 mean_jitter+=delta; 410 cpt++; 411 412 //Printf("Thread::%s jitter moy (ns): %lld\n",self->ObjectName().c_str(),mean_jitter/cpt); 413 414 } 415 416 void Thread_impl::SafeStop(void) 417 { 418 tobestopped=true; 419 if(IsSuspended()) Resume(); 420 } 421 422 bool Thread_impl::ToBeStopped(void) 423 { 424 return tobestopped; 425 } 336 } 337 } 338 339 void Thread_impl::Join(void) { 340 if (isRunning == true) { 341 int status; 342 343 #ifdef __XENO__ 344 status = rt_task_join(&task_rt); 345 #else 346 status = pthread_join(task_nrt, NULL); 347 #endif 348 if (status != 0) 349 self->Err("error %s\n", strerror(-status)); 350 isRunning = false; 351 } 352 } 353 354 void Thread_impl::ComputeJitter(Time time) { 355 Time diff, delta; 356 diff = time - last; 357 358 if (diff >= period) { 359 delta = diff - period; 360 } else { 361 delta = period - diff; 362 } 363 // if(delta==0) rt_printf("%lld %lld\n",time,last); 364 last = time; 365 if (diff == time) 366 return; 367 368 if (delta > max_jitter) 369 max_jitter = delta; 370 if (delta < min_jitter) 371 min_jitter = delta; 372 mean_jitter += delta; 373 cpt++; 374 375 // Printf("Thread::%s jitter moy (ns): 376 // %lld\n",self->ObjectName().c_str(),mean_jitter/cpt); 377 } 378 379 void Thread_impl::SafeStop(void) { 380 tobestopped = true; 381 if (IsSuspended()) 382 Resume(); 383 } 384 385 bool Thread_impl::ToBeStopped(void) { return tobestopped; } -
trunk/lib/FlairCore/src/UdtSocket.cpp
r2 r15 24 24 using std::string; 25 25 26 namespace flair 27 { 28 namespace core 29 { 26 namespace flair { 27 namespace core { 30 28 31 UdtSocket::UdtSocket(const Object* parent,const std::string name,bool _blockOnSend,bool _blockOnReceive):ConnectedSocket(parent,name) { 32 UDT::startup(); 33 blockOnSend=_blockOnSend; 34 blockOnReceive=_blockOnReceive; 29 UdtSocket::UdtSocket(const Object *parent, const std::string name, 30 bool _blockOnSend, bool _blockOnReceive) 31 : ConnectedSocket(parent, name) { 32 UDT::startup(); 33 blockOnSend = _blockOnSend; 34 blockOnReceive = _blockOnReceive; 35 35 } 36 36 37 UdtSocket::~UdtSocket(){ 38 } 37 UdtSocket::~UdtSocket() {} 39 38 40 void UdtSocket::Listen(const unsigned int port,const std::string localAddress) { 41 socket = UDT::socket(AF_INET, SOCK_DGRAM, 0); 39 void UdtSocket::Listen(const unsigned int port, 40 const std::string localAddress) { 41 socket = UDT::socket(AF_INET, SOCK_DGRAM, 0); 42 42 43 44 45 46 43 UDT::setsockopt(socket, 0, UDT_SNDSYN, &blockOnSend, sizeof(bool)); 44 UDT::setsockopt(socket, 0, UDT_RCVSYN, &blockOnReceive, sizeof(bool)); 45 bool reuse = true; 46 UDT::setsockopt(socket, 0, UDT_REUSEADDR, &reuse, sizeof(bool)); 47 47 48 49 50 51 if (localAddress=="ANY") {52 my_addr.sin_addr.s_addr=INADDR_ANY;53 54 inet_aton(localAddress.c_str(),&(my_addr.sin_addr));55 56 48 sockaddr_in my_addr; 49 my_addr.sin_family = AF_INET; 50 my_addr.sin_port = htons(port); 51 if (localAddress == "ANY") { 52 my_addr.sin_addr.s_addr = INADDR_ANY; 53 } else { 54 inet_aton(localAddress.c_str(), &(my_addr.sin_addr)); 55 } 56 memset(&(my_addr.sin_zero), '\0', 8); 57 57 58 if (UDT::ERROR == UDT::bind(socket, (sockaddr*)&my_addr, sizeof(my_addr))) {59 Err("bind, %s\n",UDT::getlasterror().getErrorMessage());60 58 if (UDT::ERROR == UDT::bind(socket, (sockaddr *)&my_addr, sizeof(my_addr))) { 59 Err("bind, %s\n", UDT::getlasterror().getErrorMessage()); 60 } 61 61 62 62 UDT::listen(socket, 1); 63 63 } 64 64 65 65 UdtSocket *UdtSocket::Accept(Time timeout) { 66 67 UdtSocket *acceptedSocket=new UdtSocket(this->Parent(),this->ObjectName());68 acceptedSocket->blockOnSend=this->blockOnSend;69 acceptedSocket->blockOnReceive=this->blockOnReceive;66 // TIMEOUT UNSUPPORTED!! 67 UdtSocket *acceptedSocket = new UdtSocket(this->Parent(), this->ObjectName()); 68 acceptedSocket->blockOnSend = this->blockOnSend; 69 acceptedSocket->blockOnReceive = this->blockOnReceive; 70 70 71 72 71 sockaddr_in their_addr; 72 int namelen = sizeof(their_addr); 73 73 74 if ((acceptedSocket->socket = UDT::accept(socket, (sockaddr*)&their_addr, &namelen))==UDT::INVALID_SOCK) { 75 Err("accept: %s, code %i\n",UDT::getlasterror().getErrorMessage(),UDT::getlasterror().getErrorCode()); 76 } 74 if ((acceptedSocket->socket = UDT::accept(socket, (sockaddr *)&their_addr, 75 &namelen)) == UDT::INVALID_SOCK) { 76 Err("accept: %s, code %i\n", UDT::getlasterror().getErrorMessage(), 77 UDT::getlasterror().getErrorCode()); 78 } 77 79 78 80 return acceptedSocket; 79 81 } 80 82 81 bool UdtSocket::Connect(const unsigned int port,const std::string distantAddress,Time timeout) { 82 bool success=true; 83 socket=UDT::socket(AF_INET, SOCK_DGRAM, 0); 83 bool UdtSocket::Connect(const unsigned int port, 84 const std::string distantAddress, Time timeout) { 85 bool success = true; 86 socket = UDT::socket(AF_INET, SOCK_DGRAM, 0); 84 87 85 86 87 88 88 UDT::setsockopt(socket, 0, UDT_SNDSYN, &blockOnSend, sizeof(bool)); 89 UDT::setsockopt(socket, 0, UDT_RCVSYN, &blockOnReceive, sizeof(bool)); 90 bool reuse = true; 91 UDT::setsockopt(socket, 0, UDT_REUSEADDR, &reuse, sizeof(bool)); 89 92 90 91 92 93 94 95 success=false;96 97 93 sockaddr_in serv_addr; 94 serv_addr.sin_family = AF_INET; 95 serv_addr.sin_port = htons(short(port)); 96 if (inet_pton(AF_INET, distantAddress.c_str(), &serv_addr.sin_addr) <= 0) { 97 printf("incorrect network address."); 98 success = false; 99 } 100 memset(&(serv_addr.sin_zero), '\0', 8); 98 101 99 if (UDT::ERROR == UDT::connect(socket, (sockaddr*)&serv_addr, sizeof(serv_addr))) { 100 success=false; 101 } 102 if (!success) { 103 UDT::close(socket); 104 return false; 105 } else return true; 102 if (UDT::ERROR == 103 UDT::connect(socket, (sockaddr *)&serv_addr, sizeof(serv_addr))) { 104 success = false; 105 } 106 if (!success) { 107 UDT::close(socket); 108 return false; 109 } else 110 return true; 106 111 } 107 112 108 ssize_t UdtSocket::SendMessage(const char* buffer,size_t bufferSize,Time timeout){ 109 int udtTimeout=timeout; 110 if (blockOnSend) { 111 if(UDT::setsockopt(socket, 0, UDT_SNDTIMEO, &udtTimeout, sizeof(udtTimeout))!=0) Err("error UDT_SNDTIMEO %s\n", UDT::getlasterror().getErrorMessage()); 112 } 113 ssize_t bytesSent=UDT::sendmsg(socket, buffer, bufferSize, -1,true); 113 ssize_t UdtSocket::SendMessage(const char *buffer, size_t bufferSize, 114 Time timeout) { 115 int udtTimeout = timeout; 116 if (blockOnSend) { 117 if (UDT::setsockopt(socket, 0, UDT_SNDTIMEO, &udtTimeout, 118 sizeof(udtTimeout)) != 0) 119 Err("error UDT_SNDTIMEO %s\n", UDT::getlasterror().getErrorMessage()); 120 } 121 ssize_t bytesSent = UDT::sendmsg(socket, buffer, bufferSize, -1, true); 114 122 115 123 return bytesSent; 116 124 } 117 125 118 ssize_t UdtSocket::RecvMessage(char* buffer,size_t bufferSize,Time timeout){ 119 int udtTimeout=timeout; 120 if (blockOnReceive) { 121 if(UDT::setsockopt(socket, 0, UDT_RCVTIMEO, &udtTimeout, sizeof(udtTimeout))!=0) Err("error UDT_RCVTIMEO %s\n", UDT::getlasterror().getErrorMessage()); 122 } 123 ssize_t bytesRead= UDT::recvmsg(socket,buffer,bufferSize); 126 ssize_t UdtSocket::RecvMessage(char *buffer, size_t bufferSize, Time timeout) { 127 int udtTimeout = timeout; 128 if (blockOnReceive) { 129 if (UDT::setsockopt(socket, 0, UDT_RCVTIMEO, &udtTimeout, 130 sizeof(udtTimeout)) != 0) 131 Err("error UDT_RCVTIMEO %s\n", UDT::getlasterror().getErrorMessage()); 132 } 133 ssize_t bytesRead = UDT::recvmsg(socket, buffer, bufferSize); 124 134 125 /*126 if(bytesRead<0) {127 if(UDT::getlasterror().getErrorCode()==CUDTException::ECONNLOST) {128 connection_lost=true;129 }130 }131 */132 135 /* 136 if(bytesRead<0) { 137 if(UDT::getlasterror().getErrorCode()==CUDTException::ECONNLOST) { 138 connection_lost=true; 139 } 140 } 141 */ 142 return bytesRead; 133 143 } 134 144 135 uint16_t UdtSocket::NetworkToHost16(uint16_t data) { 136 return ntohs(data); 137 } 145 uint16_t UdtSocket::NetworkToHost16(uint16_t data) { return ntohs(data); } 138 146 139 uint16_t UdtSocket::HostToNetwork16(uint16_t data) { 140 return htons(data); 141 } 147 uint16_t UdtSocket::HostToNetwork16(uint16_t data) { return htons(data); } 142 148 143 uint32_t UdtSocket::NetworkToHost32(uint32_t data) { 144 return ntohl(data); 145 } 149 uint32_t UdtSocket::NetworkToHost32(uint32_t data) { return ntohl(data); } 146 150 147 uint32_t UdtSocket::HostToNetwork32(uint32_t data) { 148 return htonl(data); 149 } 151 uint32_t UdtSocket::HostToNetwork32(uint32_t data) { return htonl(data); } 150 152 151 153 } // end namespace core -
trunk/lib/FlairCore/src/UdtSocket.h
r2 r15 18 18 #include <ConnectedSocket.h> 19 19 20 namespace flair 21 { 22 namespace core 23 { 24 /*! \class UdtSocket 25 * 26 * \brief Class encapsulating a UDT socket 27 * 28 */ 29 class UdtSocket:public ConnectedSocket { 30 public: 31 UdtSocket(const Object* parent,const std::string name,bool blockOnSend=false,bool blockOnReceive=true); 32 ~UdtSocket(); 33 void Listen(const unsigned int port,const std::string localAddress="ANY"); 34 UdtSocket *Accept(Time timeout); //should throw an exception if not a listening socket 35 bool Connect(const unsigned int port,const std::string distantAddress,Time timeout); // /!\ timeout is ignored 36 ssize_t SendMessage(const char* message,size_t message_len,Time timeout); 37 ssize_t RecvMessage(char* buf,size_t buf_len,Time timeout); 20 namespace flair { 21 namespace core { 22 /*! \class UdtSocket 23 * 24 * \brief Class encapsulating a UDT socket 25 * 26 */ 27 class UdtSocket : public ConnectedSocket { 28 public: 29 UdtSocket(const Object *parent, const std::string name, 30 bool blockOnSend = false, bool blockOnReceive = true); 31 ~UdtSocket(); 32 void Listen(const unsigned int port, const std::string localAddress = "ANY"); 33 UdtSocket * 34 Accept(Time timeout); // should throw an exception if not a listening socket 35 bool Connect(const unsigned int port, const std::string distantAddress, 36 Time timeout); // /!\ timeout is ignored 37 ssize_t SendMessage(const char *message, size_t message_len, Time timeout); 38 ssize_t RecvMessage(char *buf, size_t buf_len, Time timeout); 38 39 39 40 41 42 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); 43 44 44 45 46 47 48 45 private: 46 UDTSOCKET socket; 47 bool blockOnSend; 48 bool blockOnReceive; 49 }; 49 50 50 51 } // end namespace core -
trunk/lib/FlairCore/src/Unix_I2cPort.cpp
r2 r15 18 18 #include "Unix_I2cPort.h" 19 19 #include <errno.h> 20 #include <fcntl.h> 20 #include <fcntl.h> /* File control definitions */ 21 21 #include <unistd.h> 22 22 #include <sys/ioctl.h> 23 23 #include <linux/i2c-dev.h> 24 24 25 26 25 using std::string; 27 26 28 namespace flair 29 { 30 namespace core 31 { 27 namespace flair { 28 namespace core { 32 29 33 Unix_I2cPort::Unix_I2cPort(const Object* parent,string name,string device) : I2cPort(parent,name) 34 { 35 //open port 36 fd = open( device.c_str(), O_RDWR ); 37 if (fd == -1) 38 { 39 Err("open_port: Unable to open %s\n",device.c_str()); 40 } 30 Unix_I2cPort::Unix_I2cPort(const Object *parent, string name, string device) 31 : I2cPort(parent, name) { 32 // open port 33 fd = open(device.c_str(), O_RDWR); 34 if (fd == -1) { 35 Err("open_port: Unable to open %s\n", device.c_str()); 36 } 41 37 } 42 38 43 Unix_I2cPort::~Unix_I2cPort() 44 { 45 close(fd); 39 Unix_I2cPort::~Unix_I2cPort() { close(fd); } 40 41 void Unix_I2cPort::SetRxTimeout(core::Time timeout_ns) { 42 Warn("not implemented\n"); 46 43 } 47 44 48 void Unix_I2cPort::SetRxTimeout(core::Time timeout_ns) 49 { 50 Warn("not implemented\n"); 45 void Unix_I2cPort::SetTxTimeout(core::Time timeout_ns) { 46 Warn("not implemented\n"); 51 47 } 52 48 53 void Unix_I2cPort::SetTxTimeout(core::Time timeout_ns) 54 { 55 Warn("not implemented\n"); 49 int Unix_I2cPort::SetSlave(uint16_t address) { 50 int err = ioctl(fd, I2C_SLAVE_FORCE, address); 51 if (err < 0) { 52 Err("Failed to set slave address\n"); 53 } 54 55 return err; 56 56 } 57 57 58 int Unix_I2cPort::SetSlave(uint16_t address) 59 { 60 int err=ioctl( fd, I2C_SLAVE_FORCE, address); 61 if( err < 0 ) 62 { 63 Err("Failed to set slave address\n"); 64 } 65 66 return err; 58 ssize_t Unix_I2cPort::Write(const void *buf, size_t nbyte) { 59 return write(fd, buf, nbyte); 67 60 } 68 61 69 ssize_t Unix_I2cPort::Write(const void *buf,size_t nbyte) 70 { 71 return write(fd,buf, nbyte); 72 } 73 74 ssize_t Unix_I2cPort::Read(void *buf,size_t nbyte) 75 { 76 return read(fd,buf, nbyte); 62 ssize_t Unix_I2cPort::Read(void *buf, size_t nbyte) { 63 return read(fd, buf, nbyte); 77 64 } 78 65 79 66 } // end namespace core 80 67 } // end namespace flair 81 -
trunk/lib/FlairCore/src/Unix_I2cPort.h
r2 r15 16 16 #include <I2cPort.h> 17 17 18 namespace flair 19 { 20 namespace core 21 { 22 /*! \class Unix_I2cPort 23 * 24 * \brief Class for unix serial port 25 * 26 */ 27 class Unix_I2cPort: public I2cPort 28 { 18 namespace flair { 19 namespace core { 20 /*! \class Unix_I2cPort 21 * 22 * \brief Class for unix serial port 23 * 24 */ 25 class Unix_I2cPort : public I2cPort { 29 26 30 31 32 33 34 35 36 37 38 39 40 Unix_I2cPort(const Object* parent,std::string port_name,std::string device);27 public: 28 /*! 29 * \brief Constructor 30 * 31 * Construct an unix i2c port 32 * 33 * \param parent parent 34 * \param name name 35 * \param device serial device (ex /dev/i2c-1) 36 */ 37 Unix_I2cPort(const Object *parent, std::string port_name, std::string device); 41 38 42 43 44 45 46 39 /*! 40 * \brief Destructor 41 * 42 */ 43 ~Unix_I2cPort(); 47 44 48 49 50 51 52 53 54 55 45 /*! 46 * \brief Set slave's address 47 * 48 * This method need to be called before any communication. 49 * 50 * \param address slave's address 51 */ 52 int SetSlave(uint16_t address); 56 53 57 58 59 60 61 62 63 64 54 /*! 55 * \brief Set RX timeout 56 * 57 * Timeout for waiting datas. 58 * 59 * \param timeout_ns timeout in nano second 60 */ 61 void SetRxTimeout(Time timeout_ns); 65 62 66 67 68 69 70 71 72 73 63 /*! 64 * \brief Set TX timeout 65 * 66 * Timeout for waiting an ACK from the slave. 67 * 68 * \param timeout_ns timeout in nano second 69 */ 70 void SetTxTimeout(Time timeout_ns); 74 71 75 76 77 78 79 80 81 82 83 ssize_t Write(const void *buf,size_t nbyte);72 /*! 73 * \brief Write datas 74 * 75 * \param buf pointer to datas 76 * \param nbyte length of datas 77 * 78 * \return amount of written datas 79 */ 80 ssize_t Write(const void *buf, size_t nbyte); 84 81 85 86 87 88 89 90 91 92 93 ssize_t Read(void *buf,size_t nbyte);82 /*! 83 * \brief Read datas 84 * 85 * \param buf pointer to datas 86 * \param nbyte length of datas 87 * 88 * \return amount of read datas 89 */ 90 ssize_t Read(void *buf, size_t nbyte); 94 91 95 96 97 92 private: 93 int fd; 94 }; 98 95 } // end namespace core 99 96 } // end namespace flair -
trunk/lib/FlairCore/src/Unix_SerialPort.cpp
r2 r15 17 17 18 18 #include "Unix_SerialPort.h" 19 #include <fcntl.h> 19 #include <fcntl.h> /* File control definitions */ 20 20 #include <unistd.h> 21 21 22 22 using std::string; 23 23 24 namespace flair 25 { 26 namespace core 27 { 24 namespace flair { 25 namespace core { 28 26 29 Unix_SerialPort::Unix_SerialPort(const Object * parent,string name,string device) : SerialPort(parent,name)30 { 31 //open port32 fd = open(device.c_str(), O_RDWR | O_NOCTTY);// |O_NDELAY|O_NONBLOCK); 33 if (fd == -1) 34 35 Err("open_port: Unable to open %s\n",device.c_str());36 37 //fcntl(fd, F_SETFL, 0); //read calls are non blocking27 Unix_SerialPort::Unix_SerialPort(const Object *parent, string name, 28 string device) 29 : SerialPort(parent, name) { 30 // open port 31 fd = open(device.c_str(), O_RDWR | O_NOCTTY); // |O_NDELAY|O_NONBLOCK); 32 if (fd == -1) { 33 Err("open_port: Unable to open %s\n", device.c_str()); 34 } 35 // fcntl(fd, F_SETFL, 0); //read calls are non blocking 38 36 39 //Get the current options for the port37 // Get the current options for the port 40 38 41 42 //Set the baud rates to 11520043 44 39 tcgetattr(fd, &options); 40 // Set the baud rates to 115200 41 cfsetispeed(&options, B115200); 42 cfsetospeed(&options, B115200); 45 43 46 options.c_cflag |= (CLOCAL | CREAD); //Enable the receiver and set local mode47 options.c_iflag = 0; //clear input options48 options.c_lflag=0; //clear local options49 options.c_oflag &= ~OPOST; //clear output options (raw output)44 options.c_cflag |= (CLOCAL | CREAD); // Enable the receiver and set local mode 45 options.c_iflag = 0; // clear input options 46 options.c_lflag = 0; // clear local options 47 options.c_oflag &= ~OPOST; // clear output options (raw output) 50 48 51 //Set the new options for the port52 53 54 55 49 // Set the new options for the port 50 options.c_cc[VTIME] = 0; 51 options.c_cc[VMIN] = 1; 52 FlushInput(); 53 tcsetattr(fd, TCSANOW, &options); 56 54 } 57 55 58 Unix_SerialPort::~Unix_SerialPort() 59 { 60 close(fd); 56 Unix_SerialPort::~Unix_SerialPort() { close(fd); } 57 58 void Unix_SerialPort::SetBaudrate(int baudrate) { 59 // set port options 60 struct termios options; 61 // Get the current options for the port 62 tcgetattr(fd, &options); 63 // Set the baud rates to 115200 64 65 switch (baudrate) { 66 case 1200: 67 cfsetispeed(&options, B1200); 68 cfsetospeed(&options, B1200); 69 break; 70 case 2400: 71 cfsetispeed(&options, B2400); 72 cfsetospeed(&options, B2400); 73 break; 74 case 4800: 75 cfsetispeed(&options, B4800); 76 cfsetospeed(&options, B4800); 77 break; 78 case 9600: 79 cfsetispeed(&options, B9600); 80 cfsetospeed(&options, B9600); 81 break; 82 case 19200: 83 cfsetispeed(&options, B19200); 84 cfsetospeed(&options, B19200); 85 break; 86 case 38400: 87 cfsetispeed(&options, B38400); 88 cfsetospeed(&options, B38400); 89 break; 90 case 115200: 91 cfsetispeed(&options, B115200); 92 cfsetospeed(&options, B115200); 93 break; 94 case 460800: 95 cfsetispeed(&options, B460800); 96 cfsetospeed(&options, B460800); 97 break; 98 case 921600: 99 cfsetispeed(&options, B921600); 100 cfsetospeed(&options, B921600); 101 break; 102 default: 103 Err("unsupported baudrate\n"); 104 } 105 tcsetattr(fd, TCSANOW, &options); 106 FlushInput(); 61 107 } 62 108 63 void Unix_SerialPort::SetBaudrate(int baudrate) 64 { 65 //set port options 66 struct termios options; 67 //Get the current options for the port 68 tcgetattr(fd, &options); 69 //Set the baud rates to 115200 109 void Unix_SerialPort::SetRxTimeout(core::Time timeout_ns) {} 70 110 71 switch(baudrate) 72 { 73 case 1200: 74 cfsetispeed(&options, B1200); 75 cfsetospeed(&options, B1200); 76 break; 77 case 2400: 78 cfsetispeed(&options, B2400); 79 cfsetospeed(&options, B2400); 80 break; 81 case 4800: 82 cfsetispeed(&options, B4800); 83 cfsetospeed(&options, B4800); 84 break; 85 case 9600: 86 cfsetispeed(&options, B9600); 87 cfsetospeed(&options, B9600); 88 break; 89 case 19200: 90 cfsetispeed(&options, B19200); 91 cfsetospeed(&options, B19200); 92 break; 93 case 38400: 94 cfsetispeed(&options, B38400); 95 cfsetospeed(&options, B38400); 96 break; 97 case 115200: 98 cfsetispeed(&options, B115200); 99 cfsetospeed(&options, B115200); 100 break; 101 case 460800: 102 cfsetispeed(&options, B460800); 103 cfsetospeed(&options, B460800); 104 break; 105 case 921600: 106 cfsetispeed(&options, B921600); 107 cfsetospeed(&options, B921600); 108 break; 109 default: 110 Err("unsupported baudrate\n"); 111 } 112 tcsetattr(fd, TCSANOW, &options); 113 FlushInput(); 111 void Unix_SerialPort::FlushInput(void) { tcflush(fd, TCIFLUSH); } 114 112 113 ssize_t Unix_SerialPort::Write(const void *buf, size_t nbyte) { 114 return write(fd, buf, nbyte); 115 115 } 116 116 117 void Unix_SerialPort::SetRxTimeout(core::Time timeout_ns) 118 { 117 ssize_t Unix_SerialPort::Read(void *buf, size_t nbyte) { 118 if (options.c_cc[VMIN] != nbyte) { 119 tcgetattr(fd, &options); // bug if not called? 120 options.c_cc[VTIME] = 0; 121 options.c_cc[VMIN] = nbyte; 122 tcsetattr(fd, TCSANOW, &options); 123 } 119 124 120 } 121 122 void Unix_SerialPort::FlushInput(void) 123 { 124 tcflush(fd, TCIFLUSH); 125 } 126 127 ssize_t Unix_SerialPort::Write(const void *buf,size_t nbyte) 128 { 129 return write(fd, buf, nbyte); 130 } 131 132 ssize_t Unix_SerialPort::Read(void *buf,size_t nbyte) 133 { 134 if(options.c_cc[VMIN] != nbyte) 135 { 136 tcgetattr(fd, &options);//bug if not called? 137 options.c_cc[VTIME] = 0; 138 options.c_cc[VMIN] = nbyte; 139 tcsetattr(fd, TCSANOW, &options); 140 } 141 142 return read(fd, buf, nbyte); 125 return read(fd, buf, nbyte); 143 126 } 144 127 145 128 } // end namespace core 146 129 } // end namespace flair 147 -
trunk/lib/FlairCore/src/Unix_SerialPort.h
r2 r15 17 17 #include <termios.h> /* POSIX terminal control definitions */ 18 18 19 namespace flair 20 { 21 namespace core 22 { 23 /*! \class RTDM_I2cPort 24 * 25 * \brief Class for unix serial port 26 * 27 */ 28 class Unix_SerialPort: public SerialPort 29 { 19 namespace flair { 20 namespace core { 21 /*! \class RTDM_I2cPort 22 * 23 * \brief Class for unix serial port 24 * 25 */ 26 class Unix_SerialPort : public SerialPort { 30 27 31 public: 32 /*! 33 * \brief Constructor 34 * 35 * Construct an unix serial port, with the following default values: \n 36 * - 115200bps baudrate 37 * 38 * \param parent parent 39 * \param name name 40 * \param device serial device (ex rtser1) 41 */ 42 Unix_SerialPort(const Object* parent,std::string port_name,std::string device); 28 public: 29 /*! 30 * \brief Constructor 31 * 32 * Construct an unix serial port, with the following default values: \n 33 * - 115200bps baudrate 34 * 35 * \param parent parent 36 * \param name name 37 * \param device serial device (ex rtser1) 38 */ 39 Unix_SerialPort(const Object *parent, std::string port_name, 40 std::string device); 43 41 44 45 46 47 48 42 /*! 43 * \brief Destructor 44 * 45 */ 46 ~Unix_SerialPort(); 49 47 50 51 52 53 54 55 56 48 /*! 49 * \brief Set baudrate 50 * 51 * \param baudrate baudrate 52 * 53 */ 54 void SetBaudrate(int baudrate); 57 55 58 59 60 61 62 63 64 65 56 /*! 57 * \brief Set RX timeout 58 * 59 * Timeout for waiting datas. 60 * 61 * \param timeout_ns timeout in nano second 62 */ 63 void SetRxTimeout(Time timeout_ns); 66 64 67 68 69 70 71 72 73 74 75 ssize_t Write(const void *buf,size_t nbyte);65 /*! 66 * \brief Write datas 67 * 68 * \param buf pointer to datas 69 * \param nbyte length of datas 70 * 71 * \return amount of written datas 72 */ 73 ssize_t Write(const void *buf, size_t nbyte); 76 74 77 78 79 80 81 82 83 84 85 ssize_t Read(void *buf,size_t nbyte);75 /*! 76 * \brief Read datas 77 * 78 * \param buf pointer to datas 79 * \param nbyte length of datas 80 * 81 * \return amount of read datas 82 */ 83 ssize_t Read(void *buf, size_t nbyte); 86 84 87 88 89 90 91 85 /*! 86 * \brief Flush input datas 87 * 88 */ 89 void FlushInput(void); 92 90 93 94 95 96 91 private: 92 int fd; 93 struct termios options; 94 }; 97 95 } // end namespace core 98 96 } // end namespace flair -
trunk/lib/FlairCore/src/Vector2D.cpp
r2 r15 20 20 #include <math.h> 21 21 22 namespace flair { namespace core { 22 namespace flair { 23 namespace core { 23 24 24 Vector2D::Vector2D(float inX,float inY): x(inX),y(inY) { 25 Vector2D::Vector2D(float inX, float inY) : x(inX), y(inY) {} 26 27 Vector2D::~Vector2D() {} 28 29 Vector2D &Vector2D::operator=(const Vector2D &vector) { 30 x = vector.x; 31 y = vector.y; 32 return (*this); 25 33 } 26 34 27 Vector2D ::~Vector2D() {28 35 Vector2D operator+(const Vector2D &vectorA, const Vector2D &vectorB) { 36 return Vector2D(vectorA.x + vectorB.x, vectorA.y + vectorB.y); 29 37 } 30 38 31 Vector2D &Vector2D::operator=(const Vector2D &vector) { 32 x=vector.x; 33 y=vector.y; 34 return (*this); 39 Vector2D operator-(const Vector2D &vectorA, const Vector2D &vectorB) { 40 return Vector2D(vectorA.x - vectorB.x, vectorA.y - vectorB.y); 35 41 } 36 42 37 Vector2D operator+ (const Vector2D &vectorA,const Vector2D &vectorB) { 38 return Vector2D(vectorA.x + vectorB.x,vectorA.y + vectorB.y); 43 Vector2D operator/(const Vector2D &vector, float coeff) { 44 if (coeff != 0) { 45 return Vector2D(vector.x / coeff, vector.y / coeff); 46 } else { 47 return Vector2D(0, 0); 48 } 39 49 } 40 50 41 Vector2D operator - (const Vector2D &vectorA,const Vector2D &vectorB) {42 return Vector2D(vectorA.x - vectorB.x,vectorA.y - vectorB.y);51 Vector2D operator*(const Vector2D &vector, float coeff) { 52 return Vector2D(vector.x * coeff, vector.y * coeff); 43 53 } 44 54 45 Vector2D operator/ (const Vector2D &vector, float coeff) { 46 if(coeff!=0) { 47 return Vector2D(vector.x/ coeff,vector.y/ coeff); 48 } else { 49 return Vector2D(0,0); 50 } 51 } 52 53 Vector2D operator * (const Vector2D &vector, float coeff) { 54 return Vector2D(vector.x * coeff,vector.y * coeff); 55 } 56 57 Vector2D operator * (float coeff,const Vector2D &vector) { 58 return Vector2D(vector.x * coeff,vector.y * coeff); 55 Vector2D operator*(float coeff, const Vector2D &vector) { 56 return Vector2D(vector.x * coeff, vector.y * coeff); 59 57 } 60 58 61 59 void Vector2D::Rotate(float value) { 62 63 xTmp=x*cosf(value)-y*sinf(value);64 y=x*sinf(value)+y*cosf(value);65 x=xTmp;60 float xTmp; 61 xTmp = x * cosf(value) - y * sinf(value); 62 y = x * sinf(value) + y * cosf(value); 63 x = xTmp; 66 64 } 67 65 68 void Vector2D::RotateDeg(float value) { 69 Rotate(Euler::ToRadian(value)); 66 void Vector2D::RotateDeg(float value) { Rotate(Euler::ToRadian(value)); } 67 68 float Vector2D::GetNorm(void) const { return sqrt(x * x + y * y); } 69 70 void Vector2D::Normalize(void) { 71 float n = GetNorm(); 72 if (n != 0) { 73 x = x / n; 74 y = y / n; 75 } 70 76 } 71 77 72 float Vector2D::GetNorm(void) const { 73 return sqrt(x*x+y*y); 78 void Vector2D::Saturate(Vector2D min, Vector2D max) { 79 if (x < min.x) 80 x = min.x; 81 if (x > max.x) 82 x = max.x; 83 84 if (y < min.y) 85 y = min.y; 86 if (y > max.y) 87 y = max.y; 74 88 } 75 89 76 void Vector2D::Normalize(void) { 77 float n=GetNorm(); 78 if(n!=0) { 79 x=x/n; 80 y=y/n; 81 } 82 } 83 84 void Vector2D::Saturate(Vector2D min,Vector2D max) { 85 if(x<min.x) x=min.x; 86 if(x>max.x) x=max.x; 87 88 if(y<min.y) y=min.y; 89 if(y>max.y) y=max.y; 90 } 91 92 void Vector2D::Saturate(float min,float max) { 93 Saturate(Vector2D(min,min),Vector2D(max,max)); 90 void Vector2D::Saturate(float min, float max) { 91 Saturate(Vector2D(min, min), Vector2D(max, max)); 94 92 } 95 93 96 94 void Vector2D::Saturate(const Vector2D &value) { 97 float x=fabs(value.x);98 float y=fabs(value.y);99 Saturate(Vector2D(-x,-y),Vector2D(x,y));95 float x = fabs(value.x); 96 float y = fabs(value.y); 97 Saturate(Vector2D(-x, -y), Vector2D(x, y)); 100 98 } 101 99 102 100 void Vector2D::Saturate(float value) { 103 float sat=fabs(value);104 Saturate(Vector2D(-sat,-sat),Vector2D(sat,sat));101 float sat = fabs(value); 102 Saturate(Vector2D(-sat, -sat), Vector2D(sat, sat)); 105 103 } 106 104 -
trunk/lib/FlairCore/src/Vector2D.h
r2 r15 14 14 #define VECTOR2D_H 15 15 16 namespace flair { namespace core { 16 namespace flair { 17 namespace core { 17 18 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 Vector2D(float x=0,float y=0);19 /*! \class Vector2D 20 * 21 * \brief Class defining a 2D vector 22 */ 23 class Vector2D { 24 public: 25 /*! 26 * \brief Constructor 27 * 28 * Construct a Vector2D using specified values. 29 * 30 * \param x 31 * \param y 32 */ 33 Vector2D(float x = 0, float y = 0); 33 34 34 35 36 37 38 35 /*! 36 * \brief Destructor 37 * 38 */ 39 ~Vector2D(); 39 40 40 41 42 43 44 45 41 /*! 42 * \brief Rotation 43 * 44 * \param value rotation value in radians 45 */ 46 void Rotate(float value); 46 47 47 48 49 50 51 52 48 /*! 49 * \brief Rotation 50 * 51 * \param value rotation value in degrees 52 */ 53 void RotateDeg(float value); 53 54 54 55 56 57 58 59 55 /*! 56 * \brief Norm 57 * 58 * \return value 59 */ 60 float GetNorm(void) const; 60 61 61 62 63 64 62 /*! 63 * \brief Normalize 64 */ 65 void Normalize(void); 65 66 66 67 68 69 70 71 72 73 74 void Saturate(Vector2D min,Vector2D max);67 /*! 68 * \brief Saturate 69 * 70 * Saturate between min and max 71 * 72 * \param min minimum Vector2D value 73 * \param max maximum Vector2D value 74 */ 75 void Saturate(Vector2D min, Vector2D max); 75 76 76 77 78 79 80 81 82 83 84 void Saturate(float min,float max);77 /*! 78 * \brief Saturate 79 * 80 * Saturate between min and max 81 * 82 * \param min minimum Vector2D(min,min) value 83 * \param max maximum Vector2D(max,max) value 84 */ 85 void Saturate(float min, float max); 85 86 86 87 88 89 90 91 92 93 87 /*! 88 * \brief Saturate 89 * 90 * Saturate between -abs(value) and abs(value) 91 * 92 * \param value saturation Vector2D value 93 */ 94 void Saturate(const Vector2D &value); 94 95 95 96 97 98 99 100 101 102 96 /*! 97 * \brief Saturate 98 * 99 * Saturate between -abs(Vector2D(value,value)) and abs(Vector2D(value,value)) 100 * 101 * \param value saturation Vector2D(value,value) 102 */ 103 void Saturate(float value); 103 104 105 /*! 106 * \brief x 107 */ 108 float x; 104 109 105 106 * \brief x107 108 float x;110 /*! 111 * \brief y 112 */ 113 float y; 109 114 110 /*! 111 * \brief y 112 */ 113 float y; 115 Vector2D &operator=(const Vector2D &vector); 116 }; 114 117 115 Vector2D &operator=(const Vector2D &vector); 116 }; 118 /*! Add 119 * 120 * \brief Add 121 * 122 * \param vectorA vector 123 * \param vectorB vector 124 */ 125 Vector2D operator+(const Vector2D &vectorA, const Vector2D &vectorB); 117 126 118 /*! Add 119 120 * \brief Add 121 122 123 124 125 Vector2D operator + (const Vector2D &vectorA,const Vector2D &vectorB);127 /*! Substract 128 * 129 * \brief Substract 130 * 131 * \param vectorA vector 132 * \param vectorB vector 133 */ 134 Vector2D operator-(const Vector2D &vectorA, const Vector2D &vectorB); 126 135 127 /*! Substract 128 * 129 * \brief Substract 130 * 131 * \param vectorA vector 132 * \param vectorB vector 133 */ 134 Vector2D operator - (const Vector2D &vectorA,const Vector2D &vectorB); 136 /*! Divid 137 * 138 * \brief Divid 139 * 140 * \param vector vector 141 * \param coeff coefficent 142 * \return vector/coefficient 143 */ 144 Vector2D operator/(const Vector2D &vector, float coeff); 135 145 136 /*! Divid 137 138 * \brief Divid 139 140 141 142 * \return vector/coefficient 143 144 Vector2D operator /(const Vector2D &vector, float coeff);146 /*! Multiply 147 * 148 * \brief Multiplyf 149 * 150 * \param vector vector 151 * \param coeff coefficent 152 * \return coefficient*vector 153 */ 154 Vector2D operator*(const Vector2D &vector, float coeff); 145 155 146 /*! Multiply 147 * 148 * \brief Multiplyf 149 * 150 * \param vector vector 151 * \param coeff coefficent 152 * \return coefficient*vector 153 */ 154 Vector2D operator * (const Vector2D &vector, float coeff); 155 156 /*! Multiply 157 * 158 * \brief Multiply 159 * 160 * \param coeff coefficent 161 * \param vector vector 162 * \return coefficient*vector 163 */ 164 Vector2D operator * (float coeff,const Vector2D &vector); 156 /*! Multiply 157 * 158 * \brief Multiply 159 * 160 * \param coeff coefficent 161 * \param vector vector 162 * \return coefficient*vector 163 */ 164 Vector2D operator*(float coeff, const Vector2D &vector); 165 165 166 166 } // end namespace core -
trunk/lib/FlairCore/src/Vector3D.cpp
r2 r15 25 25 //#include "Vector3DSpinBox.h" 26 26 27 namespace flair { namespace core { 28 29 Vector3D::Vector3D(float inX,float inY,float inZ): x(inX),y(inY),z(inZ){ 30 } 31 32 Vector3D::~Vector3D() { 33 34 } 27 namespace flair { 28 namespace core { 29 30 Vector3D::Vector3D(float inX, float inY, float inZ) : x(inX), y(inY), z(inZ) {} 31 32 Vector3D::~Vector3D() {} 35 33 /* 36 34 void Vector3D::operator=(const gui::Vector3DSpinBox *vector) { … … 42 40 43 41 Vector3D &Vector3D::operator=(const Vector3D &vector) { 44 x=vector.x;45 y=vector.y;46 z=vector.z;47 42 x = vector.x; 43 y = vector.y; 44 z = vector.z; 45 return (*this); 48 46 } 49 47 50 48 Vector3D &Vector3D::operator+=(const Vector3D &vector) { 51 x+=vector.x;52 y+=vector.y;53 z+=vector.z;54 49 x += vector.x; 50 y += vector.y; 51 z += vector.z; 52 return (*this); 55 53 } 56 54 57 55 Vector3D &Vector3D::operator-=(const Vector3D &vector) { 58 x-=vector.x;59 y-=vector.y;60 z-=vector.z;61 56 x -= vector.x; 57 y -= vector.y; 58 z -= vector.z; 59 return (*this); 62 60 } 63 61 64 62 float &Vector3D::operator[](size_t idx) { 65 if(idx==0) { 66 return x; 67 } else if(idx==1) { 68 return y; 69 } else if(idx==2) { 70 return z; 71 } else { 72 Printf("Vector3D: index %i out of bound\n",idx); 73 return z; 63 if (idx == 0) { 64 return x; 65 } else if (idx == 1) { 66 return y; 67 } else if (idx == 2) { 68 return z; 69 } else { 70 Printf("Vector3D: index %i out of bound\n", idx); 71 return z; 72 } 73 } 74 75 const float &Vector3D::operator[](size_t idx) const { 76 if (idx == 0) { 77 return x; 78 } else if (idx == 1) { 79 return y; 80 } else if (idx == 2) { 81 return z; 82 } else { 83 Printf("Vector3D: index %i out of bound\n", idx); 84 return z; 85 } 86 } 87 88 Vector3D CrossProduct(const Vector3D &vectorA, const Vector3D &vectorB) { 89 return Vector3D(vectorA.y * vectorB.z - vectorA.z * vectorB.y, 90 vectorA.z * vectorB.x - vectorA.x * vectorB.z, 91 vectorA.x * vectorB.y - vectorA.y * vectorB.x); 92 } 93 94 float DotProduct(const Vector3D &vectorA, const Vector3D &vectorB) { 95 return vectorA.x * vectorB.x + vectorA.y * vectorB.y + vectorA.z * vectorB.z; 96 } 97 98 Vector3D operator+(const Vector3D &vectorA, const Vector3D &vectorB) { 99 return Vector3D(vectorA.x + vectorB.x, vectorA.y + vectorB.y, 100 vectorA.z + vectorB.z); 101 } 102 103 Vector3D operator-(const Vector3D &vectorA, const Vector3D &vectorB) { 104 return Vector3D(vectorA.x - vectorB.x, vectorA.y - vectorB.y, 105 vectorA.z - vectorB.z); 106 } 107 108 Vector3D operator-(const Vector3D &vector) { 109 return Vector3D(-vector.x, -vector.y, -vector.z); 110 } 111 112 Vector3D operator*(const Vector3D &vectorA, const Vector3D &vectorB) { 113 return Vector3D(vectorA.x * vectorB.x, vectorA.y * vectorB.y, 114 vectorA.z * vectorB.z); 115 } 116 117 Vector3D operator*(const Vector3D &vector, float coeff) { 118 return Vector3D(vector.x * coeff, vector.y * coeff, vector.z * coeff); 119 } 120 121 Vector3D operator*(float coeff, const Vector3D &vector) { 122 return Vector3D(vector.x * coeff, vector.y * coeff, vector.z * coeff); 123 } 124 125 Vector3D operator/(const Vector3D &vector, float coeff) { 126 if (coeff != 0) { 127 return Vector3D(vector.x / coeff, vector.y / coeff, vector.z / coeff); 128 } else { 129 printf("Vector3D: err divinding by 0\n"); 130 return Vector3D(0, 0, 0); 131 } 132 } 133 134 void Vector3D::RotateX(float value) { 135 float y_tmp; 136 y_tmp = y * cosf(value) - z * sinf(value); 137 z = y * sinf(value) + z * cosf(value); 138 y = y_tmp; 139 } 140 141 void Vector3D::RotateXDeg(float value) { RotateX(Euler::ToRadian(value)); } 142 143 void Vector3D::RotateY(float value) { 144 float x_tmp; 145 x_tmp = x * cosf(value) + z * sinf(value); 146 z = -x * sinf(value) + z * cosf(value); 147 x = x_tmp; 148 } 149 150 void Vector3D::RotateYDeg(float value) { RotateY(Euler::ToRadian(value)); } 151 152 void Vector3D::RotateZ(float value) { 153 float x_tmp; 154 x_tmp = x * cosf(value) - y * sinf(value); 155 y = x * sinf(value) + y * cosf(value); 156 x = x_tmp; 157 } 158 159 void Vector3D::RotateZDeg(float value) { RotateZ(Euler::ToRadian(value)); } 160 161 void Vector3D::Rotate(const RotationMatrix &matrix) { 162 float a[3] = {0, 0, 0}; 163 float b[3] = {x, y, z}; 164 165 for (int i = 0; i < 3; i++) { 166 for (int j = 0; j < 3; j++) { 167 a[i] += matrix.m[i][j] * b[j]; 74 168 } 75 } 76 77 const float &Vector3D::operator[](size_t idx) const { 78 if(idx==0) { 79 return x; 80 } else if(idx==1) { 81 return y; 82 } else if(idx==2) { 83 return z; 84 } else { 85 Printf("Vector3D: index %i out of bound\n",idx); 86 return z; 87 } 88 } 89 90 Vector3D CrossProduct(const Vector3D &vectorA,const Vector3D &vectorB) { 91 return Vector3D(vectorA.y*vectorB.z - vectorA.z*vectorB.y, 92 vectorA.z*vectorB.x - vectorA.x*vectorB.z, 93 vectorA.x*vectorB.y - vectorA.y*vectorB.x); 94 } 95 96 float DotProduct(const Vector3D &vectorA,const Vector3D &vectorB) { 97 return vectorA.x*vectorB.x + vectorA.y*vectorB.y+ vectorA.z*vectorB.z; 98 } 99 100 Vector3D operator+ (const Vector3D &vectorA,const Vector3D &vectorB) { 101 return Vector3D(vectorA.x + vectorB.x, 102 vectorA.y + vectorB.y, 103 vectorA.z + vectorB.z); 104 } 105 106 Vector3D operator- (const Vector3D &vectorA,const Vector3D &vectorB) { 107 return Vector3D(vectorA.x - vectorB.x, 108 vectorA.y - vectorB.y, 109 vectorA.z - vectorB.z); 110 } 111 112 Vector3D operator-(const Vector3D &vector) { 113 return Vector3D(-vector.x,-vector.y,-vector.z); 114 } 115 116 Vector3D operator * (const Vector3D &vectorA,const Vector3D &vectorB) { 117 return Vector3D(vectorA.x* vectorB.x, 118 vectorA.y* vectorB.y, 119 vectorA.z* vectorB.z); 120 } 121 122 Vector3D operator * (const Vector3D &vector, float coeff) { 123 return Vector3D(vector.x* coeff, 124 vector.y* coeff, 125 vector.z* coeff); 126 } 127 128 Vector3D operator * (float coeff,const Vector3D &vector) { 129 return Vector3D(vector.x* coeff, 130 vector.y* coeff, 131 vector.z* coeff); 132 } 133 134 Vector3D operator/ (const Vector3D &vector, float coeff) { 135 if(coeff!=0) { 136 return Vector3D(vector.x/ coeff, 137 vector.y/ coeff, 138 vector.z/ coeff); 139 } else { 140 printf("Vector3D: err divinding by 0\n"); 141 return Vector3D(0,0,0); 142 } 143 } 144 145 void Vector3D::RotateX(float value) { 146 float y_tmp; 147 y_tmp=y*cosf(value)-z*sinf(value); 148 z=y*sinf(value)+z*cosf(value); 149 y=y_tmp; 150 } 151 152 void Vector3D::RotateXDeg(float value) { 153 RotateX(Euler::ToRadian(value)); 154 } 155 156 void Vector3D::RotateY(float value) { 157 float x_tmp; 158 x_tmp=x*cosf(value)+z*sinf(value); 159 z=-x*sinf(value)+z*cosf(value); 160 x=x_tmp; 161 } 162 163 void Vector3D::RotateYDeg(float value) { 164 RotateY(Euler::ToRadian(value)); 165 } 166 167 void Vector3D::RotateZ(float value) { 168 float x_tmp; 169 x_tmp=x*cosf(value)-y*sinf(value); 170 y=x*sinf(value)+y*cosf(value); 171 x=x_tmp; 172 } 173 174 void Vector3D::RotateZDeg(float value) { 175 RotateZ(Euler::ToRadian(value)); 176 } 177 178 void Vector3D::Rotate(const RotationMatrix &matrix) { 179 float a[3]= {0,0,0}; 180 float b[3]= {x,y,z}; 181 182 for(int i=0; i<3; i++) { 183 for(int j=0; j<3; j++) { 184 a[i]+=matrix.m[i][j]*b[j]; 185 } 186 } 187 188 x=a[0]; 189 y=a[1]; 190 z=a[2]; 169 } 170 171 x = a[0]; 172 y = a[1]; 173 z = a[2]; 191 174 } 192 175 193 176 void Vector3D::Rotate(const Quaternion &quaternion) { 194 195 196 177 RotationMatrix matrix; 178 quaternion.ToRotationMatrix(matrix); 179 Rotate(matrix); 197 180 } 198 181 199 182 void Vector3D::To2Dxy(Vector2D &vector) const { 200 vector.x=x;201 vector.y=y;183 vector.x = x; 184 vector.y = y; 202 185 } 203 186 204 187 Vector2D Vector3D::To2Dxy(void) const { 205 Vector2D vect; 206 To2Dxy(vect); 207 return vect; 208 } 209 210 float Vector3D::GetNorm(void) const { 211 return sqrt(x*x+y*y+z*z); 212 } 188 Vector2D vect; 189 To2Dxy(vect); 190 return vect; 191 } 192 193 float Vector3D::GetNorm(void) const { return sqrt(x * x + y * y + z * z); } 213 194 214 195 void Vector3D::Normalize(void) { 215 float n=GetNorm(); 216 if(n!=0) { 217 x=x/n; 218 y=y/n; 219 z=z/n; 220 } 221 } 222 223 void Vector3D::Saturate(const Vector3D &min,const Vector3D &max) { 224 if(x<min.x) x=min.x; 225 if(x>max.x) x=max.x; 226 227 if(y<min.y) y=min.y; 228 if(y>max.y) y=max.y; 229 230 if(z<min.z) z=min.z; 231 if(z>max.z) z=max.z; 232 } 233 234 void Vector3D::Saturate(float min,float max) { 235 Saturate(Vector3D(min,min,min),Vector3D(max,max,max)); 196 float n = GetNorm(); 197 if (n != 0) { 198 x = x / n; 199 y = y / n; 200 z = z / n; 201 } 202 } 203 204 void Vector3D::Saturate(const Vector3D &min, const Vector3D &max) { 205 if (x < min.x) 206 x = min.x; 207 if (x > max.x) 208 x = max.x; 209 210 if (y < min.y) 211 y = min.y; 212 if (y > max.y) 213 y = max.y; 214 215 if (z < min.z) 216 z = min.z; 217 if (z > max.z) 218 z = max.z; 219 } 220 221 void Vector3D::Saturate(float min, float max) { 222 Saturate(Vector3D(min, min, min), Vector3D(max, max, max)); 236 223 } 237 224 238 225 void Vector3D::Saturate(const Vector3D &value) { 239 float x=fabs(value.x);240 float y=fabs(value.y);241 float z=fabs(value.z);242 Saturate(Vector3D(-x,-y,-z),Vector3D(x,y,z));226 float x = fabs(value.x); 227 float y = fabs(value.y); 228 float z = fabs(value.z); 229 Saturate(Vector3D(-x, -y, -z), Vector3D(x, y, z)); 243 230 } 244 231 245 232 void Vector3D::Saturate(float value) { 246 float sat=fabs(value);247 Saturate(Vector3D(-sat,-sat,-sat),Vector3D(sat,sat,sat));233 float sat = fabs(value); 234 Saturate(Vector3D(-sat, -sat, -sat), Vector3D(sat, sat, sat)); 248 235 } 249 236 -
trunk/lib/FlairCore/src/Vector3D.h
r2 r15 16 16 #include <stddef.h> 17 17 18 namespace flair { namespace core { 19 class Vector2D; 20 class RotationMatrix; 21 class Quaternion; 22 23 /*! \class Vector3D 24 * 25 * \brief Class defining a 3D vector 26 */ 27 class Vector3D { 28 public: 29 /*! 30 * \brief Constructor 31 * 32 * Construct a Vector3D using specified values. 33 * 34 * \param x 35 * \param y 36 * \param z 37 */ 38 Vector3D(float x=0,float y=0,float z=0); 39 40 /*! 41 * \brief Destructor 42 * 43 */ 44 ~Vector3D(); 45 46 /*! 47 * \brief x 48 */ 49 float x; 50 51 /*! 52 * \brief y 53 */ 54 float y; 55 56 /*! 57 * \brief z 58 */ 59 float z; 60 61 /*! 62 * \brief x axis rotation 63 * 64 * \param value rotation value in radians 65 */ 66 void RotateX(float value); 67 68 /*! 69 * \brief x axis rotation 70 * 71 * \param value rotation value in degrees 72 */ 73 void RotateXDeg(float value); 74 75 /*! 76 * \brief y axis rotation 77 * 78 * \param value rotation value in radians 79 */ 80 void RotateY(float value); 81 82 /*! 83 * \brief y axis rotation 84 * 85 * \param value rotation value in degrees 86 */ 87 void RotateYDeg(float value); 88 89 /*! 90 * \brief z axis rotation 91 * 92 * \param value rotation value in radians 93 */ 94 void RotateZ(float value); 95 96 /*! 97 * \brief z axis rotation 98 * 99 * \param value rotation value in degrees 100 */ 101 void RotateZDeg(float value); 102 103 /*! 104 * \brief rotation 105 * 106 * \param matrix rotation matrix 107 */ 108 void Rotate(const RotationMatrix &matrix); 109 110 /*! 111 * \brief rotation 112 * 113 * Compute a rotation from a quaternion. This method uses a rotation matrix 114 * internaly. 115 * 116 * \param quaternion quaternion 117 */ 118 void Rotate(const Quaternion &quaternion); 119 120 /*! 121 * \brief Convert to a Vector2D 122 * 123 * Uses x and y coordinates. 124 * 125 * \param vector destination 126 */ 127 void To2Dxy(Vector2D &vector) const; 128 129 /*! 130 * \brief Convert to a Vector2D 131 * 132 * Uses x and y coordinates. 133 * 134 * \return destination 135 */ 136 Vector2D To2Dxy(void) const; 137 138 /*! 139 * \brief Norm 140 * 141 * \return value 142 */ 143 float GetNorm(void) const; 144 145 /*! 146 * \brief Normalize 147 */ 148 void Normalize(void); 149 150 /*! 151 * \brief Saturate 152 * 153 * Saturate between min and max 154 * 155 * \param min minimum value 156 * \param max maximum value 157 */ 158 void Saturate(const Vector3D &min,const Vector3D &max); 159 160 /*! 161 * \brief Saturate 162 * 163 * Saturate between min and max 164 * 165 * \param min minimum Vector3D(min,min,min) value 166 * \param max maximum Vector3D(max,max,max) value 167 */ 168 void Saturate(float min,float max); 169 170 /*! 171 * \brief Saturate 172 * 173 * Saturate between -abs(value) and abs(value) 174 * 175 * \param value saturation Vector3D value 176 */ 177 void Saturate(const Vector3D &value); 178 179 /*! 180 * \brief Saturate 181 * 182 * Saturate between -abs(Vector3D(value,value,value)) and abs(Vector3D(value,value,value)) 183 * 184 * \param value saturation Vector3D(value,value,value) 185 */ 186 void Saturate(float value); 187 188 float &operator[](size_t idx); 189 const float &operator[](size_t idx) const; 190 Vector3D &operator=(const Vector3D& vector); 191 Vector3D &operator+=(const Vector3D& vector); 192 Vector3D &operator-=(const Vector3D& vector); 193 194 private: 195 196 }; 197 198 /*! Add 199 * 200 * \brief Add 201 * 202 * \param vectorA vector 203 * \param vectorB vector 204 * 205 * \return vectorA+vectorB 206 */ 207 Vector3D operator + (const Vector3D &vectorA,const Vector3D &vectorB); 208 209 /*! Substract 210 * 211 * \brief Substract 212 * 213 * \param vectorA vector 214 * \param vectorB vector 215 * 216 * \return vectorA-vectorB 217 */ 218 Vector3D operator - (const Vector3D &vectorA,const Vector3D &vectorB); 219 220 /*! Minus 221 * 222 * \brief Minus 223 * 224 * \param vector vector 225 * 226 * \return -vector 227 */ 228 Vector3D operator-(const Vector3D &vector); 229 230 /*! Divid 231 * 232 * \brief Divid 233 * 234 * \param vector vector 235 * \param coeff coefficent 236 * 237 * \return vector/coefficient 238 */ 239 Vector3D operator / (const Vector3D &vector, float coeff); 240 241 /*! Hadamard product 242 * 243 * \brief Hadamard product 244 * 245 * \param vectorA vector 246 * \param vectorBA vector 247 * 248 * \return Hadamard product 249 */ 250 Vector3D operator * (const Vector3D &vectorA, const Vector3D &vectorB); 251 252 /*! Multiply 253 * 254 * \brief Multiply 255 * 256 * \param vector vector 257 * \param coeff coefficent 258 * 259 * \return coefficient*vector 260 */ 261 Vector3D operator * (const Vector3D &vector, float coeff); 262 263 /*! Multiply 264 * 265 * \brief Multiply 266 * 267 * \param coeff coefficent 268 * \param vector vector 269 * 270 * \return coefficient*vector 271 */ 272 Vector3D operator * (float coeff, const Vector3D &vector); 273 274 /*! Cross product 275 * 276 * \brief Cross product 277 * 278 * \param vectorA first vector 279 * \param vectorB second vector 280 * 281 * \return cross product 282 */ 283 Vector3D CrossProduct(const Vector3D &vectorA, const Vector3D &vectorB); 284 285 /*! Dot product 286 * 287 * \brief Dot product 288 * 289 * \param vectorA first vector 290 * \param vectorB second vector 291 * 292 * \return dot product 293 */ 294 float DotProduct(const Vector3D &vectorA, const Vector3D &vectorB); 18 namespace flair { 19 namespace core { 20 class Vector2D; 21 class RotationMatrix; 22 class Quaternion; 23 24 /*! \class Vector3D 25 * 26 * \brief Class defining a 3D vector 27 */ 28 class Vector3D { 29 public: 30 /*! 31 * \brief Constructor 32 * 33 * Construct a Vector3D using specified values. 34 * 35 * \param x 36 * \param y 37 * \param z 38 */ 39 Vector3D(float x = 0, float y = 0, float z = 0); 40 41 /*! 42 * \brief Destructor 43 * 44 */ 45 ~Vector3D(); 46 47 /*! 48 * \brief x 49 */ 50 float x; 51 52 /*! 53 * \brief y 54 */ 55 float y; 56 57 /*! 58 * \brief z 59 */ 60 float z; 61 62 /*! 63 * \brief x axis rotation 64 * 65 * \param value rotation value in radians 66 */ 67 void RotateX(float value); 68 69 /*! 70 * \brief x axis rotation 71 * 72 * \param value rotation value in degrees 73 */ 74 void RotateXDeg(float value); 75 76 /*! 77 * \brief y axis rotation 78 * 79 * \param value rotation value in radians 80 */ 81 void RotateY(float value); 82 83 /*! 84 * \brief y axis rotation 85 * 86 * \param value rotation value in degrees 87 */ 88 void RotateYDeg(float value); 89 90 /*! 91 * \brief z axis rotation 92 * 93 * \param value rotation value in radians 94 */ 95 void RotateZ(float value); 96 97 /*! 98 * \brief z axis rotation 99 * 100 * \param value rotation value in degrees 101 */ 102 void RotateZDeg(float value); 103 104 /*! 105 * \brief rotation 106 * 107 * \param matrix rotation matrix 108 */ 109 void Rotate(const RotationMatrix &matrix); 110 111 /*! 112 * \brief rotation 113 * 114 * Compute a rotation from a quaternion. This method uses a rotation matrix 115 * internaly. 116 * 117 * \param quaternion quaternion 118 */ 119 void Rotate(const Quaternion &quaternion); 120 121 /*! 122 * \brief Convert to a Vector2D 123 * 124 * Uses x and y coordinates. 125 * 126 * \param vector destination 127 */ 128 void To2Dxy(Vector2D &vector) const; 129 130 /*! 131 * \brief Convert to a Vector2D 132 * 133 * Uses x and y coordinates. 134 * 135 * \return destination 136 */ 137 Vector2D To2Dxy(void) const; 138 139 /*! 140 * \brief Norm 141 * 142 * \return value 143 */ 144 float GetNorm(void) const; 145 146 /*! 147 * \brief Normalize 148 */ 149 void Normalize(void); 150 151 /*! 152 * \brief Saturate 153 * 154 * Saturate between min and max 155 * 156 * \param min minimum value 157 * \param max maximum value 158 */ 159 void Saturate(const Vector3D &min, const Vector3D &max); 160 161 /*! 162 * \brief Saturate 163 * 164 * Saturate between min and max 165 * 166 * \param min minimum Vector3D(min,min,min) value 167 * \param max maximum Vector3D(max,max,max) value 168 */ 169 void Saturate(float min, float max); 170 171 /*! 172 * \brief Saturate 173 * 174 * Saturate between -abs(value) and abs(value) 175 * 176 * \param value saturation Vector3D value 177 */ 178 void Saturate(const Vector3D &value); 179 180 /*! 181 * \brief Saturate 182 * 183 * Saturate between -abs(Vector3D(value,value,value)) and 184 *abs(Vector3D(value,value,value)) 185 * 186 * \param value saturation Vector3D(value,value,value) 187 */ 188 void Saturate(float value); 189 190 float &operator[](size_t idx); 191 const float &operator[](size_t idx) const; 192 Vector3D &operator=(const Vector3D &vector); 193 Vector3D &operator+=(const Vector3D &vector); 194 Vector3D &operator-=(const Vector3D &vector); 195 196 private: 197 }; 198 199 /*! Add 200 * 201 * \brief Add 202 * 203 * \param vectorA vector 204 * \param vectorB vector 205 * 206 * \return vectorA+vectorB 207 */ 208 Vector3D operator+(const Vector3D &vectorA, const Vector3D &vectorB); 209 210 /*! Substract 211 * 212 * \brief Substract 213 * 214 * \param vectorA vector 215 * \param vectorB vector 216 * 217 * \return vectorA-vectorB 218 */ 219 Vector3D operator-(const Vector3D &vectorA, const Vector3D &vectorB); 220 221 /*! Minus 222 * 223 * \brief Minus 224 * 225 * \param vector vector 226 * 227 * \return -vector 228 */ 229 Vector3D operator-(const Vector3D &vector); 230 231 /*! Divid 232 * 233 * \brief Divid 234 * 235 * \param vector vector 236 * \param coeff coefficent 237 * 238 * \return vector/coefficient 239 */ 240 Vector3D operator/(const Vector3D &vector, float coeff); 241 242 /*! Hadamard product 243 * 244 * \brief Hadamard product 245 * 246 * \param vectorA vector 247 * \param vectorBA vector 248 * 249 * \return Hadamard product 250 */ 251 Vector3D operator*(const Vector3D &vectorA, const Vector3D &vectorB); 252 253 /*! Multiply 254 * 255 * \brief Multiply 256 * 257 * \param vector vector 258 * \param coeff coefficent 259 * 260 * \return coefficient*vector 261 */ 262 Vector3D operator*(const Vector3D &vector, float coeff); 263 264 /*! Multiply 265 * 266 * \brief Multiply 267 * 268 * \param coeff coefficent 269 * \param vector vector 270 * 271 * \return coefficient*vector 272 */ 273 Vector3D operator*(float coeff, const Vector3D &vector); 274 275 /*! Cross product 276 * 277 * \brief Cross product 278 * 279 * \param vectorA first vector 280 * \param vectorB second vector 281 * 282 * \return cross product 283 */ 284 Vector3D CrossProduct(const Vector3D &vectorA, const Vector3D &vectorB); 285 286 /*! Dot product 287 * 288 * \brief Dot product 289 * 290 * \param vectorA first vector 291 * \param vectorB second vector 292 * 293 * \return dot product 294 */ 295 float DotProduct(const Vector3D &vectorA, const Vector3D &vectorB); 295 296 296 297 } // end namespace core -
trunk/lib/FlairCore/src/Vector3DSpinBox.cpp
r2 r15 11 11 // version: $Id: $ 12 12 // 13 // purpose: Class displaying 3 QDoubleSpinBox for x,y,z on the ground station 13 // purpose: Class displaying 3 QDoubleSpinBox for x,y,z on the ground 14 // station 14 15 // 15 16 // … … 20 21 using std::string; 21 22 22 namespace flair { namespace gui { 23 namespace flair { 24 namespace gui { 23 25 24 Vector3DSpinBox::Vector3DSpinBox(const LayoutPosition* position,string name,double min,double max,double step,int decimals,core::Vector3D default_value):Box(position,name,"Vector3DSpinBox") { 25 //update value from xml file 26 default_value.Saturate(min,max); 27 box_value=default_value; 26 Vector3DSpinBox::Vector3DSpinBox(const LayoutPosition *position, string name, 27 double min, double max, double step, 28 int decimals, core::Vector3D default_value) 29 : Box(position, name, "Vector3DSpinBox") { 30 // update value from xml file 31 default_value.Saturate(min, max); 32 box_value = default_value; 28 33 29 SetVolatileXmlProp("min",min);30 SetVolatileXmlProp("max",max);31 SetVolatileXmlProp("step",step);32 SetVolatileXmlProp("decimals",decimals);33 GetPersistentXmlProp("value_x",box_value.x);34 SetPersistentXmlProp("value_x",box_value.x);35 GetPersistentXmlProp("value_y",box_value.y);36 SetPersistentXmlProp("value_y",box_value.y);37 GetPersistentXmlProp("value_z",box_value.z);38 SetPersistentXmlProp("value_z",box_value.z);34 SetVolatileXmlProp("min", min); 35 SetVolatileXmlProp("max", max); 36 SetVolatileXmlProp("step", step); 37 SetVolatileXmlProp("decimals", decimals); 38 GetPersistentXmlProp("value_x", box_value.x); 39 SetPersistentXmlProp("value_x", box_value.x); 40 GetPersistentXmlProp("value_y", box_value.y); 41 SetPersistentXmlProp("value_y", box_value.y); 42 GetPersistentXmlProp("value_z", box_value.z); 43 SetPersistentXmlProp("value_z", box_value.z); 39 44 40 45 SendXml(); 41 46 } 42 47 43 Vector3DSpinBox::~Vector3DSpinBox() { 44 45 } 48 Vector3DSpinBox::~Vector3DSpinBox() {} 46 49 /* 47 50 Vector3DSpinBox::operator core::Vector3D() const { … … 50 53 */ 51 54 core::Vector3D Vector3DSpinBox::Value(void) const { 52 55 core::Vector3D tmp; 53 56 54 55 tmp=box_value;56 57 GetMutex(); 58 tmp = box_value; 59 ReleaseMutex(); 57 60 58 61 return tmp; 59 62 } 60 63 61 64 void Vector3DSpinBox::XmlEvent(void) { 62 bool changed=false; 63 GetMutex(); 64 if(GetPersistentXmlProp("value_x",box_value.x)) changed=true; 65 if(GetPersistentXmlProp("value_y",box_value.y)) changed=true; 66 if(GetPersistentXmlProp("value_z",box_value.z)) changed=true; 67 if(changed) SetValueChanged(); 68 ReleaseMutex(); 65 bool changed = false; 66 GetMutex(); 67 if (GetPersistentXmlProp("value_x", box_value.x)) 68 changed = true; 69 if (GetPersistentXmlProp("value_y", box_value.y)) 70 changed = true; 71 if (GetPersistentXmlProp("value_z", box_value.z)) 72 changed = true; 73 if (changed) 74 SetValueChanged(); 75 ReleaseMutex(); 69 76 } 70 77 -
trunk/lib/FlairCore/src/Vector3DSpinBox.h
r2 r15 17 17 #include <Vector3D.h> 18 18 19 namespace flair { namespace gui { 20 class Layout; 19 namespace flair { 20 namespace gui { 21 class Layout; 21 22 22 /*! \class Vector3DSpinBox 23 * 24 * \brief Class displaying 3 QDoubleSpinBox for x,y,z on the ground station 25 * 26 */ 27 class Vector3DSpinBox: public Box { 28 public: 29 /*! 30 * \brief Constructor 31 * 32 * Construct a Vector3DSpinBox at given position. \n 33 * Each DoubleSpinBox is saturated to min and max values. 34 * 35 * \param position position to display the Vector3DSpinBox 36 * \param name name 37 * \param min minimum value 38 * \param max maximum value 39 * \param step step 40 * \param decimals number of decimals 41 * \param default_value default value if not in the xml config file 42 */ 43 Vector3DSpinBox(const LayoutPosition* position,std::string name,double min,double max,double step,int decimals=2,core::Vector3D default_value=core::Vector3D(0,0,0)); 23 /*! \class Vector3DSpinBox 24 * 25 * \brief Class displaying 3 QDoubleSpinBox for x,y,z on the ground station 26 * 27 */ 28 class Vector3DSpinBox : public Box { 29 public: 30 /*! 31 * \brief Constructor 32 * 33 * Construct a Vector3DSpinBox at given position. \n 34 * Each DoubleSpinBox is saturated to min and max values. 35 * 36 * \param position position to display the Vector3DSpinBox 37 * \param name name 38 * \param min minimum value 39 * \param max maximum value 40 * \param step step 41 * \param decimals number of decimals 42 * \param default_value default value if not in the xml config file 43 */ 44 Vector3DSpinBox(const LayoutPosition *position, std::string name, double min, 45 double max, double step, int decimals = 2, 46 core::Vector3D default_value = core::Vector3D(0, 0, 0)); 44 47 45 46 47 48 49 48 /*! 49 * \brief Destructor 50 * 51 */ 52 ~Vector3DSpinBox(); 50 53 51 52 53 54 55 56 57 //operator core::Vector3D() const;58 59 60 61 62 63 64 65 54 /*! 55 * \brief Value 56 * 57 * \return value 58 */ 59 core::Vector3D Value(void) const; 60 // operator core::Vector3D() const; 61 private: 62 /*! 63 * \brief XmlEvent from ground station 64 * 65 * Reimplemented from Widget. 66 * 67 */ 68 void XmlEvent(void); 66 69 67 68 70 core::Vector3D box_value; 71 }; 69 72 70 73 } // end namespace gui -
trunk/lib/FlairCore/src/Vector3Ddata.cpp
r2 r15 25 25 using std::string; 26 26 27 namespace flair { namespace core { 27 namespace flair { 28 namespace core { 28 29 29 /*! \class Vector3DdataElement 30 */ 31 class Vector3DdataElement: public IODataElement { 32 public: 33 Vector3DdataElement(const Vector3Ddata *data,string name,uint32_t elem):IODataElement(data,name) { 34 this->data=data; 35 this->elem=elem; 36 size=4; 37 } 30 /*! \class Vector3DdataElement 31 */ 32 class Vector3DdataElement : public IODataElement { 33 public: 34 Vector3DdataElement(const Vector3Ddata *data, string name, uint32_t elem) 35 : IODataElement(data, name) { 36 this->data = data; 37 this->elem = elem; 38 size = 4; 39 } 38 40 39 ~Vector3DdataElement() { 40 } 41 ~Vector3DdataElement() {} 41 42 42 void CopyData(char*dst) const {43 44 45 switch(elem) {46 47 value=data->x;48 49 50 value=data->y;51 52 53 value=data->z;54 55 56 57 value=0;58 59 60 43 void CopyData(char *dst) const { 44 float value; 45 data->GetMutex(); 46 switch (elem) { 47 case X: 48 value = data->x; 49 break; 50 case Y: 51 value = data->y; 52 break; 53 case Z: 54 value = data->z; 55 break; 56 default: 57 data->Err("type not handled\n"); 58 value = 0; 59 break; 60 } 61 data->ReleaseMutex(); 61 62 62 memcpy(dst,&value,sizeof(float));63 63 memcpy(dst, &value, sizeof(float)); 64 } 64 65 65 ScalarType const &GetDataType() const { 66 return dataType; 67 } 66 ScalarType const &GetDataType() const { return dataType; } 68 67 69 70 71 72 73 68 private: 69 const Vector3Ddata *data; 70 uint32_t elem; 71 FloatType dataType; 72 }; 74 73 75 Vector3Ddata::Vector3Ddata(const Object* parent, string name,float x,float y,float z,uint32_t n): io_data(parent,name,n), Vector3D(x,y,z) { 74 Vector3Ddata::Vector3Ddata(const Object *parent, string name, float x, float y, 75 float z, uint32_t n) 76 : io_data(parent, name, n), Vector3D(x, y, z) {} 76 77 78 Vector3Ddata::~Vector3Ddata() {} 79 80 void Vector3Ddata::CopyDatas(char *dst) const { 81 GetMutex(); 82 memcpy(dst, &x, sizeof(float)); 83 memcpy(dst + sizeof(float), &y, sizeof(float)); 84 memcpy(dst + 2 * sizeof(float), &z, sizeof(float)); 85 ReleaseMutex(); 77 86 } 78 87 79 Vector3Ddata::~Vector3Ddata(){80 88 IODataElement *Vector3Ddata::XElement(void) const { 89 return new Vector3DdataElement(this, "x", X); 81 90 } 82 91 83 void Vector3Ddata::CopyDatas(char* dst) const { 84 GetMutex(); 85 memcpy(dst,&x,sizeof(float)); 86 memcpy(dst+sizeof(float),&y,sizeof(float)); 87 memcpy(dst+2*sizeof(float),&z,sizeof(float)); 88 ReleaseMutex(); 92 IODataElement *Vector3Ddata::YElement(void) const { 93 return new Vector3DdataElement(this, "y", Y); 89 94 } 90 95 91 IODataElement* Vector3Ddata::XElement(void) const { 92 return new Vector3DdataElement(this,"x",X); 93 } 94 95 IODataElement* Vector3Ddata::YElement(void) const { 96 return new Vector3DdataElement(this,"y",Y); 97 } 98 99 IODataElement* Vector3Ddata::ZElement(void) const { 100 return new Vector3DdataElement(this,"z",Z); 96 IODataElement *Vector3Ddata::ZElement(void) const { 97 return new Vector3DdataElement(this, "z", Z); 101 98 } 102 99 -
trunk/lib/FlairCore/src/Vector3Ddata.h
r2 r15 18 18 #include <Vector3D.h> 19 19 20 namespace flair 21 { 22 namespace core 23 { 20 namespace flair { 21 namespace core { 24 22 25 26 27 28 29 30 class Vector3Ddata: public io_data, public Vector3D 31 { 32 public:33 /*!34 * \brief Constructor35 *36 * Construct a Vector3D using specified values.37 *38 * \param x39 * \param y40 * \param z41 */42 Vector3Ddata(const Object* parent, std::string name,float x=0,float y=0,float z=0,uint32_t n=1);23 /*! \class Vector3Ddata 24 * 25 * \brief Class defining a 3D vector and a io_data 26 * User must manually use the io_data's Mutex to access to Vector3D values. 27 */ 28 class Vector3Ddata : public io_data, public Vector3D { 29 public: 30 /*! 31 * \brief Constructor 32 * 33 * Construct a Vector3D using specified values. 34 * 35 * \param x 36 * \param y 37 * \param z 38 */ 39 Vector3Ddata(const Object *parent, std::string name, float x = 0, float y = 0, 40 float z = 0, uint32_t n = 1); 43 41 44 45 46 47 48 42 /*! 43 * \brief Destructor 44 * 45 */ 46 ~Vector3Ddata(); 49 47 50 51 52 53 54 55 56 57 IODataElement*XElement(void) const;48 /*! 49 * \brief X Element 50 * 51 * Get a vectorer to x element. This pointer can be used for plotting. 52 * 53 * \return pointer to the element 54 */ 55 IODataElement *XElement(void) const; 58 56 59 60 61 62 63 64 65 66 IODataElement*YElement(void) const;57 /*! 58 * \brief Y Element 59 * 60 * Get a pointer to y element. This pointer can be used for plotting. 61 * 62 * \return pointer to the element 63 */ 64 IODataElement *YElement(void) const; 67 65 68 69 70 71 72 73 74 75 IODataElement*ZElement(void) const;66 /*! 67 * \brief Z Element 68 * 69 * Get a pointer to z element. This pointer can be used for plotting. 70 * 71 * \return pointer to the element 72 */ 73 IODataElement *ZElement(void) const; 76 74 77 78 79 80 81 82 83 84 85 86 void CopyDatas(char*dst) const;87 75 private: 76 /*! 77 * \brief Copy datas 78 * 79 * Reimplemented from io_data. \n 80 * See io_data::CopyDatas. 81 * 82 * \param dst destination buffer 83 */ 84 void CopyDatas(char *dst) const; 85 }; 88 86 89 87 } // end namespace core -
trunk/lib/FlairCore/src/Watchdog.cpp
r2 r15 20 20 namespace core { 21 21 22 Watchdog::Watchdog(const Object* parent,std::function<void()> _expired,Time _timer):Thread(parent,"watchdog",0),expired(_expired),timer(_timer){ 23 } 22 Watchdog::Watchdog(const Object *parent, std::function<void()> _expired, 23 Time _timer) 24 : Thread(parent, "watchdog", 0), expired(_expired), timer(_timer) {} 24 25 25 26 Watchdog::~Watchdog() { 26 27 27 SafeStop(); 28 Join(); 28 29 } 29 30 30 31 void Watchdog::Touch() { 31 if (IsSuspended()) Resume(); 32 if (IsSuspended()) 33 Resume(); 32 34 } 33 35 34 36 void Watchdog::SetTimer(Time _Timer) { 35 timer=_Timer; Touch(); 37 timer = _Timer; 38 Touch(); 36 39 } 37 40 38 41 void Watchdog::Run() { 39 40 Time current=GetTime();41 Time date=current+timer;42 //Printf("watchdog goes to sleep at %llu, scheduled to wake up at %llu\n",current,date);43 if (!SuspendUntil(date)) {44 expired();45 }42 while (!ToBeStopped()) { 43 Time current = GetTime(); 44 Time date = current + timer; 45 // Printf("watchdog goes to sleep at %llu, scheduled to wake up at 46 // %llu\n",current,date); 47 if (!SuspendUntil(date)) { 48 expired(); 46 49 } 50 } 47 51 }; 48 52 -
trunk/lib/FlairCore/src/Watchdog.h
r2 r15 20 20 namespace core { 21 21 22 23 24 25 26 27 28 29 class Watchdog:public Thread {30 31 Watchdog(const Object* parent,std::function<void()> _expired,Time _timer);32 22 /*! \class Watchdog 23 * 24 * \brief Watchdog class 25 * 26 * Calls a given function if not touched within a specified period of time 27 * 28 */ 29 class Watchdog : public Thread { 30 public: 31 Watchdog(const Object *parent, std::function<void()> _expired, Time _timer); 32 ~Watchdog(); 33 33 34 //reset the timer 35 void Touch(); 36 void SetTimer(Time _Timer); 37 private: 38 void Run(); 39 std::function<void()> expired; 40 Time timer; 41 }; 34 // reset the timer 35 void Touch(); 36 void SetTimer(Time _Timer); 37 38 private: 39 void Run(); 40 std::function<void()> expired; 41 Time timer; 42 }; 42 43 43 44 } // end namespace core -
trunk/lib/FlairCore/src/Widget.cpp
r2 r15 21 21 using std::string; 22 22 23 namespace flair 24 { 25 namespace gui 26 { 23 namespace flair { 24 namespace gui { 27 25 28 26 using namespace core; 29 27 30 Widget::Widget(const Widget* parent,string name,string type): Object(parent,name,type) 31 { 32 pimpl_=new Widget_impl(this,parent,name,type); 33 } 34 35 Widget::~Widget() 36 { 37 delete pimpl_; 38 } 39 40 template <> 41 bool Widget::GetPersistentXmlProp(std::string prop,double &value) 42 { 43 xmlChar *result=NULL; 44 result=xmlGetProp(pimpl_->file_node,(xmlChar*)prop.c_str()); 45 46 if(result!=NULL) { 47 value=xmlXPathCastStringToNumber(result); 48 xmlFree(result); 49 return true; 50 } else { 51 return false; 52 } 53 } 54 55 template <> 56 bool Widget::GetPersistentXmlProp(std::string prop,float &value) { 57 double tmp; 58 if(GetPersistentXmlProp<double>(prop,tmp)) { 59 value=tmp; 60 return true; 61 } else { 62 return false; 63 } 64 } 65 66 template <> 67 bool Widget::GetPersistentXmlProp(std::string prop,bool &value) { 68 double tmp; 69 if(GetPersistentXmlProp<double>(prop,tmp)) { 70 value=tmp; 71 return true; 72 } else { 73 return false; 74 } 75 } 76 77 template <> 78 bool Widget::GetPersistentXmlProp(std::string prop,int32_t &value) { 79 double tmp; 80 if(GetPersistentXmlProp<double>(prop,tmp)) { 81 value=tmp; 82 return true; 83 } else { 84 return false; 85 } 86 } 87 88 template <> 89 bool Widget::GetPersistentXmlProp(std::string prop,uint16_t &value) { 90 double tmp; 91 if(GetPersistentXmlProp<double>(prop,tmp)) { 92 value=tmp; 93 return true; 94 } else { 95 return false; 96 } 97 } 98 99 template <> 100 void Widget::SetVolatileXmlProp(string prop,string value,xmlNodePtr node) 101 { 102 if(node==NULL) node=pimpl_->send_node; 103 xmlSetProp(node,(xmlChar*)prop.c_str(),(xmlChar*)value.c_str()); 104 } 105 106 template <> 107 void Widget::SetVolatileXmlProp(string prop,char* value,xmlNodePtr node) 108 { 109 if(node==NULL) node=pimpl_->send_node; 110 xmlSetProp(node,(xmlChar*)prop.c_str(),(xmlChar*)value); 111 } 112 113 template <> 114 void Widget::SetVolatileXmlProp(string prop,double value,xmlNodePtr node) 115 { 116 xmlChar* xmlChar_value=xmlXPathCastNumberToString(value); 117 118 if(node==NULL) node=pimpl_->send_node; 119 xmlSetProp(node,(xmlChar*)prop.c_str(),xmlChar_value); 120 xmlFree(xmlChar_value); 121 } 122 123 template <> 124 void Widget::SetVolatileXmlProp(string prop,float value,xmlNodePtr node) 125 { 126 SetVolatileXmlProp<double>(prop,value,node); 127 } 128 129 template <> 130 void Widget::SetVolatileXmlProp(string prop,int32_t value,xmlNodePtr node) 131 { 132 SetVolatileXmlProp<double>(prop,value,node); 133 } 134 135 template <> 136 void Widget::SetVolatileXmlProp(string prop,uint32_t value,xmlNodePtr node) 137 { 138 SetVolatileXmlProp<double>(prop,value,node); 139 } 140 141 template <> 142 void Widget::SetVolatileXmlProp(string prop,int16_t value,xmlNodePtr node) 143 { 144 SetVolatileXmlProp<double>(prop,value,node); 145 } 146 147 template <> 148 void Widget::SetVolatileXmlProp(string prop,uint16_t value,xmlNodePtr node) 149 { 150 SetVolatileXmlProp<double>(prop,value,node); 151 } 152 153 template <> 154 void Widget::SetVolatileXmlProp(string prop,int8_t value,xmlNodePtr node) 155 { 156 SetVolatileXmlProp<double>(prop,value,node); 157 } 158 159 template <> 160 void Widget::SetVolatileXmlProp(string prop,uint8_t value,xmlNodePtr node) 161 { 162 SetVolatileXmlProp<double>(prop,value,node); 163 } 164 165 template <> 166 void Widget::SetVolatileXmlProp(string prop,bool value,xmlNodePtr node) 167 { 168 SetVolatileXmlProp<double>(prop,value,node); 169 } 170 171 template <> 172 void Widget::SetVolatileXmlProp(string prop,xmlChar* value,xmlNodePtr node) { 173 if(node==NULL) node=pimpl_->send_node; 174 xmlSetProp(node,(xmlChar*)prop.c_str(),value); 175 } 176 177 template <> 178 void Widget::SetVolatileXmlProp(string prop,DataType const &dataType,xmlNodePtr node) { 179 if(node==NULL) node=pimpl_->send_node; 180 xmlSetProp(node,(xmlChar*)prop.c_str(),(xmlChar*)dataType.GetDescription().c_str()); 181 /* 182 switch(dataType) 183 { 184 case io_data::Float: 185 xmlSetProp(node,(xmlChar*)prop.c_str(),(xmlChar*)"float"); 186 break; 187 case io_data::Int8_t: 188 xmlSetProp(node,(xmlChar*)prop.c_str(),(xmlChar*)"int8_t"); 189 break; 190 case io_data::Int16_t: 191 xmlSetProp(node,(xmlChar*)prop.c_str(),(xmlChar*)"int16_t"); 192 break; 193 } 194 */ 195 } 196 197 template <> 198 void Widget::SetPersistentXmlProp(std::string prop,double value) { 199 SetVolatileXmlProp(prop,value); 200 SetVolatileXmlProp(prop,value,pimpl_->file_node); 201 } 202 203 template <> 204 void Widget::SetPersistentXmlProp(std::string prop,float value) 205 { 206 SetVolatileXmlProp(prop,value); 207 SetVolatileXmlProp(prop,value,pimpl_->file_node); 208 } 209 210 template <> 211 void Widget::SetPersistentXmlProp(std::string prop,int32_t value) 212 { 213 SetVolatileXmlProp(prop,value); 214 SetVolatileXmlProp(prop,value,pimpl_->file_node); 215 } 216 217 template <> 218 void Widget::SetPersistentXmlProp(std::string prop,uint16_t value) 219 { 220 SetVolatileXmlProp(prop,value); 221 SetVolatileXmlProp(prop,value,pimpl_->file_node); 222 } 223 224 template <> 225 void Widget::SetPersistentXmlProp(std::string prop,bool value) 226 { 227 SetVolatileXmlProp(prop,value); 228 SetVolatileXmlProp(prop,value,pimpl_->file_node); 229 } 230 231 void Widget::SendXml(void) 232 { 233 pimpl_->SendXml(); 234 } 235 236 void Widget::setEnabled(bool status) 237 { 238 pimpl_->setEnabled(status); 239 } 240 241 bool Widget::isEnabled(void) const 242 { 243 return pimpl_->isenabled; 244 245 } 28 Widget::Widget(const Widget *parent, string name, string type) 29 : Object(parent, name, type) { 30 pimpl_ = new Widget_impl(this, parent, name, type); 31 } 32 33 Widget::~Widget() { delete pimpl_; } 34 35 template <> bool Widget::GetPersistentXmlProp(std::string prop, double &value) { 36 xmlChar *result = NULL; 37 result = xmlGetProp(pimpl_->file_node, (xmlChar *)prop.c_str()); 38 39 if (result != NULL) { 40 value = xmlXPathCastStringToNumber(result); 41 xmlFree(result); 42 return true; 43 } else { 44 return false; 45 } 46 } 47 48 template <> bool Widget::GetPersistentXmlProp(std::string prop, float &value) { 49 double tmp; 50 if (GetPersistentXmlProp<double>(prop, tmp)) { 51 value = tmp; 52 return true; 53 } else { 54 return false; 55 } 56 } 57 58 template <> bool Widget::GetPersistentXmlProp(std::string prop, bool &value) { 59 double tmp; 60 if (GetPersistentXmlProp<double>(prop, tmp)) { 61 value = tmp; 62 return true; 63 } else { 64 return false; 65 } 66 } 67 68 template <> 69 bool Widget::GetPersistentXmlProp(std::string prop, int32_t &value) { 70 double tmp; 71 if (GetPersistentXmlProp<double>(prop, tmp)) { 72 value = tmp; 73 return true; 74 } else { 75 return false; 76 } 77 } 78 79 template <> 80 bool Widget::GetPersistentXmlProp(std::string prop, uint16_t &value) { 81 double tmp; 82 if (GetPersistentXmlProp<double>(prop, tmp)) { 83 value = tmp; 84 return true; 85 } else { 86 return false; 87 } 88 } 89 90 template <> 91 void Widget::SetVolatileXmlProp(string prop, string value, xmlNodePtr node) { 92 if (node == NULL) 93 node = pimpl_->send_node; 94 xmlSetProp(node, (xmlChar *)prop.c_str(), (xmlChar *)value.c_str()); 95 } 96 97 template <> 98 void Widget::SetVolatileXmlProp(string prop, char *value, xmlNodePtr node) { 99 if (node == NULL) 100 node = pimpl_->send_node; 101 xmlSetProp(node, (xmlChar *)prop.c_str(), (xmlChar *)value); 102 } 103 104 template <> 105 void Widget::SetVolatileXmlProp(string prop, double value, xmlNodePtr node) { 106 xmlChar *xmlChar_value = xmlXPathCastNumberToString(value); 107 108 if (node == NULL) 109 node = pimpl_->send_node; 110 xmlSetProp(node, (xmlChar *)prop.c_str(), xmlChar_value); 111 xmlFree(xmlChar_value); 112 } 113 114 template <> 115 void Widget::SetVolatileXmlProp(string prop, float value, xmlNodePtr node) { 116 SetVolatileXmlProp<double>(prop, value, node); 117 } 118 119 template <> 120 void Widget::SetVolatileXmlProp(string prop, int32_t value, xmlNodePtr node) { 121 SetVolatileXmlProp<double>(prop, value, node); 122 } 123 124 template <> 125 void Widget::SetVolatileXmlProp(string prop, uint32_t value, xmlNodePtr node) { 126 SetVolatileXmlProp<double>(prop, value, node); 127 } 128 129 template <> 130 void Widget::SetVolatileXmlProp(string prop, int16_t value, xmlNodePtr node) { 131 SetVolatileXmlProp<double>(prop, value, node); 132 } 133 134 template <> 135 void Widget::SetVolatileXmlProp(string prop, uint16_t value, xmlNodePtr node) { 136 SetVolatileXmlProp<double>(prop, value, node); 137 } 138 139 template <> 140 void Widget::SetVolatileXmlProp(string prop, int8_t value, xmlNodePtr node) { 141 SetVolatileXmlProp<double>(prop, value, node); 142 } 143 144 template <> 145 void Widget::SetVolatileXmlProp(string prop, uint8_t value, xmlNodePtr node) { 146 SetVolatileXmlProp<double>(prop, value, node); 147 } 148 149 template <> 150 void Widget::SetVolatileXmlProp(string prop, bool value, xmlNodePtr node) { 151 SetVolatileXmlProp<double>(prop, value, node); 152 } 153 154 template <> 155 void Widget::SetVolatileXmlProp(string prop, xmlChar *value, xmlNodePtr node) { 156 if (node == NULL) 157 node = pimpl_->send_node; 158 xmlSetProp(node, (xmlChar *)prop.c_str(), value); 159 } 160 161 template <> 162 void Widget::SetVolatileXmlProp(string prop, DataType const &dataType, 163 xmlNodePtr node) { 164 if (node == NULL) 165 node = pimpl_->send_node; 166 xmlSetProp(node, (xmlChar *)prop.c_str(), 167 (xmlChar *)dataType.GetDescription().c_str()); 168 /* 169 switch(dataType) 170 { 171 case io_data::Float: 172 xmlSetProp(node,(xmlChar*)prop.c_str(),(xmlChar*)"float"); 173 break; 174 case io_data::Int8_t: 175 xmlSetProp(node,(xmlChar*)prop.c_str(),(xmlChar*)"int8_t"); 176 break; 177 case io_data::Int16_t: 178 xmlSetProp(node,(xmlChar*)prop.c_str(),(xmlChar*)"int16_t"); 179 break; 180 } 181 */ 182 } 183 184 template <> void Widget::SetPersistentXmlProp(std::string prop, double value) { 185 SetVolatileXmlProp(prop, value); 186 SetVolatileXmlProp(prop, value, pimpl_->file_node); 187 } 188 189 template <> void Widget::SetPersistentXmlProp(std::string prop, float value) { 190 SetVolatileXmlProp(prop, value); 191 SetVolatileXmlProp(prop, value, pimpl_->file_node); 192 } 193 194 template <> void Widget::SetPersistentXmlProp(std::string prop, int32_t value) { 195 SetVolatileXmlProp(prop, value); 196 SetVolatileXmlProp(prop, value, pimpl_->file_node); 197 } 198 199 template <> 200 void Widget::SetPersistentXmlProp(std::string prop, uint16_t value) { 201 SetVolatileXmlProp(prop, value); 202 SetVolatileXmlProp(prop, value, pimpl_->file_node); 203 } 204 205 template <> void Widget::SetPersistentXmlProp(std::string prop, bool value) { 206 SetVolatileXmlProp(prop, value); 207 SetVolatileXmlProp(prop, value, pimpl_->file_node); 208 } 209 210 void Widget::SendXml(void) { pimpl_->SendXml(); } 211 212 void Widget::setEnabled(bool status) { pimpl_->setEnabled(status); } 213 214 bool Widget::isEnabled(void) const { return pimpl_->isenabled; } 246 215 247 216 } // end namespace gui -
trunk/lib/FlairCore/src/Widget.h
r2 r15 21 21 class FrameworkManager_impl; 22 22 23 namespace flair 24 { 25 namespace gui 26 { 23 namespace flair { 24 namespace gui { 27 25 28 /*! \class Widget 29 * 30 * \brief Abstract class for all Framework's widget classes 31 * 32 * A widget is an object to display on the ground station. \n 33 * Communication with ground station is done through xml files; properties of theses files 34 * are modified through appropriate method. \n 35 * A xml file is used for default values of the Widget, if it has been specified in the 36 * constructor of the FrameworkManager. 37 */ 38 class Widget: public core::Object 39 { 40 friend class core::FrameworkManager; 41 friend class ::Widget_impl; 42 friend class ::FrameworkManager_impl; 26 /*! \class Widget 27 * 28 * \brief Abstract class for all Framework's widget classes 29 * 30 * A widget is an object to display on the ground station. \n 31 * Communication with ground station is done through xml files; properties of 32 *theses files 33 * are modified through appropriate method. \n 34 * A xml file is used for default values of the Widget, if it has been specified 35 *in the 36 * constructor of the FrameworkManager. 37 */ 38 class Widget : public core::Object { 39 friend class core::FrameworkManager; 40 friend class ::Widget_impl; 41 friend class ::FrameworkManager_impl; 43 42 44 public: 45 /*! 46 * \brief Constructor 47 * 48 * Construct a Widget, the xml file specified to the FrameworkManager's 49 * constructor is sued for default values. \n 50 * Two Widget with same parent must have different names. If a brother Widget already 51 * has the same name, the name of the new one will be automatically changed. \n 52 * Type must agree with predifined (hard coded) types 53 * in ground station code. 54 * 55 * \param parent parent 56 * \param name name 57 * \param type type 58 */ 59 Widget(const Widget* parent,std::string name,std::string type); 43 public: 44 /*! 45 * \brief Constructor 46 * 47 * Construct a Widget, the xml file specified to the FrameworkManager's 48 * constructor is sued for default values. \n 49 * Two Widget with same parent must have different names. If a brother Widget 50 *already 51 * has the same name, the name of the new one will be automatically changed. \n 52 * Type must agree with predifined (hard coded) types 53 * in ground station code. 54 * 55 * \param parent parent 56 * \param name name 57 * \param type type 58 */ 59 Widget(const Widget *parent, std::string name, std::string type); 60 60 61 62 63 64 65 61 /*! 62 * \brief Destructor 63 * 64 */ 65 virtual ~Widget(); 66 66 67 68 69 70 71 72 73 74 75 76 67 /*! 68 * \brief Set enabled 69 * 70 * Enable or disable the Widget on the ground station. \n 71 * A disabled widget is greyed out on the ground station 72 * and in unmodifiable. 73 * 74 * \param status 75 */ 76 void setEnabled(bool status); 77 77 78 79 80 81 82 83 78 /*! 79 * \brief Is enabled? 80 * 81 * \return true if widget is enabled 82 */ 83 bool isEnabled(void) const; 84 84 85 86 87 88 89 * The property will be saved in the configuration xml and also used to configure the ground station.90 *91 * \param prop property to set and save92 * \param value valueto set and save93 */94 template <typename T>95 void SetPersistentXmlProp(std::string prop,T value);85 protected: 86 /*! 87 * \brief Set a persistent xml property 88 * 89 * The property will be saved in the configuration xml and also used to 90 *configure the ground station. 91 * 92 * \param prop property to set and save 93 * \param value value to set and save 94 */ 95 template <typename T> void SetPersistentXmlProp(std::string prop, T value); 96 96 97 /*! 98 * \brief Get a persistent xml property 99 * 100 * Get the property from the xml file. If no corresponding property is found in the xml, value remains unchanged. \n 101 * Thus value can be initialized with a default value before calling this method. 102 * 103 * \param prop property to get 104 * \param value value to store the result 105 * \return true if value was changed 106 */ 107 template <typename T> 108 bool GetPersistentXmlProp(std::string prop,T &value); 97 /*! 98 * \brief Get a persistent xml property 99 * 100 * Get the property from the xml file. If no corresponding property is found in 101 *the xml, value remains unchanged. \n 102 * Thus value can be initialized with a default value before calling this 103 *method. 104 * 105 * \param prop property to get 106 * \param value value to store the result 107 * \return true if value was changed 108 */ 109 template <typename T> bool GetPersistentXmlProp(std::string prop, T &value); 109 110 110 /*! 111 * \brief Set a volatile xml property 112 * 113 * This property should be used to configure the ground station (one time init). \n 114 * The property will be destroyed after calling SendXml() as it should no be used anymore. 115 * 116 * \param prop property to set 117 * \param value value to set 118 * \param node if sepcified, node to set; otherwise use the node of the Widget 119 */ 120 template <typename T> 121 void SetVolatileXmlProp(std::string prop,T value,xmlNodePtr node=NULL); 111 /*! 112 * \brief Set a volatile xml property 113 * 114 * This property should be used to configure the ground station (one time 115 *init). \n 116 * The property will be destroyed after calling SendXml() as it should no be 117 *used anymore. 118 * 119 * \param prop property to set 120 * \param value value to set 121 * \param node if sepcified, node to set; otherwise use the node of the Widget 122 */ 123 template <typename T> 124 void SetVolatileXmlProp(std::string prop, T value, xmlNodePtr node = NULL); 122 125 123 /*! 124 * \brief Send xml 125 * 126 * Send Widget's xml to ground station. \n 127 * New changes will be taken into account by ground station. \n 128 * All volatile properties will be erased after calling ths method, as they should not be used anymore. 129 */ 130 void SendXml(void); 126 /*! 127 * \brief Send xml 128 * 129 * Send Widget's xml to ground station. \n 130 * New changes will be taken into account by ground station. \n 131 * All volatile properties will be erased after calling ths method, as they 132 *should not be used anymore. 133 */ 134 void SendXml(void); 131 135 132 133 134 135 136 137 138 139 136 /*! 137 * \brief Xml event 138 * 139 * This method must be reimplemented to handle a xml event. \n 140 * It is automatically called when something changed from 141 * ground station. \n 142 */ 143 virtual void XmlEvent(void){}; 140 144 141 142 class Widget_impl*pimpl_;143 145 private: 146 class Widget_impl *pimpl_; 147 }; 144 148 145 149 } // end namespace gui -
trunk/lib/FlairCore/src/Widget_impl.cpp
r2 r15 34 34 using namespace flair::gui; 35 35 36 namespace {36 namespace { 37 37 #ifdef __XENO__ 38 RT_HEAP xml_heap; 39 40 void xml2_free(void *mem) 41 { 42 //Printf("free %x\n",mem); 43 if(mem==NULL) return; 44 int status=rt_heap_free(&xml_heap,mem); 45 46 if(status!=0) 47 { 48 printf("libxml2: rt_heap_free error (%s)\n",strerror(-status)); 49 } 50 } 51 52 void *xml2_alloc(size_t sz) 53 { 54 void *ptr; 55 //printf("alloc %i\n",sz); 56 int status=rt_heap_alloc(&xml_heap,sz,TM_NONBLOCK ,&ptr); 57 if(status!=0) 58 { 59 printf("libxml2: rt_heap_alloc error (%s)\n",strerror(-status)); 60 } 61 //Printf("alloc %x %i\n",ptr,sz); 62 63 return ptr; 64 65 } 66 67 void *xml2_realloc(void *emem,size_t sz) 68 { 69 //Printf("realloc %x %i -> %i\n",emem,sz,sz); 70 void *mem_re; 71 72 73 if (emem == NULL) 74 { 75 return xml2_alloc(sz); 76 } 77 else if (sz == 0) 78 { 79 xml2_free(emem); 80 } 81 82 mem_re = xml2_alloc(sz); 83 84 memcpy(mem_re, emem, sz); 85 86 xml2_free(emem); 87 88 return mem_re; 89 } 90 91 char *xml2_strdup(const char * str) 92 { 93 // printf("strdup %s\n",str); 94 char *s = (char*)xml2_alloc(strlen(str) + 1); 95 if (s == NULL) 96 return NULL; 97 98 strcpy(s, str); 99 return s; 100 101 } 38 RT_HEAP xml_heap; 39 40 void xml2_free(void *mem) { 41 // Printf("free %x\n",mem); 42 if (mem == NULL) 43 return; 44 int status = rt_heap_free(&xml_heap, mem); 45 46 if (status != 0) { 47 printf("libxml2: rt_heap_free error (%s)\n", strerror(-status)); 48 } 49 } 50 51 void *xml2_alloc(size_t sz) { 52 void *ptr; 53 // printf("alloc %i\n",sz); 54 int status = rt_heap_alloc(&xml_heap, sz, TM_NONBLOCK, &ptr); 55 if (status != 0) { 56 printf("libxml2: rt_heap_alloc error (%s)\n", strerror(-status)); 57 } 58 // Printf("alloc %x %i\n",ptr,sz); 59 60 return ptr; 61 } 62 63 void *xml2_realloc(void *emem, size_t sz) { 64 // Printf("realloc %x %i -> %i\n",emem,sz,sz); 65 void *mem_re; 66 67 if (emem == NULL) { 68 return xml2_alloc(sz); 69 } else if (sz == 0) { 70 xml2_free(emem); 71 } 72 73 mem_re = xml2_alloc(sz); 74 75 memcpy(mem_re, emem, sz); 76 77 xml2_free(emem); 78 79 return mem_re; 80 } 81 82 char *xml2_strdup(const char *str) { 83 // printf("strdup %s\n",str); 84 char *s = (char *)xml2_alloc(strlen(str) + 1); 85 if (s == NULL) 86 return NULL; 87 88 strcpy(s, str); 89 return s; 90 } 102 91 #endif //__XENO__ 103 92 } 104 93 105 Widget_impl::Widget_impl(Widget* self,const Widget* parent,string name,string type) 106 { 107 //Printf("Widget %s\n",name.c_str()); 108 isenabled=true; 109 file_node=NULL; 110 this->self=self; 111 112 //n'est execute qu'une fois lorsqu'on construit le FrameworkManager 113 if(parent==NULL) 114 { 94 Widget_impl::Widget_impl(Widget *self, const Widget *parent, string name, 95 string type) { 96 // Printf("Widget %s\n",name.c_str()); 97 isenabled = true; 98 file_node = NULL; 99 this->self = self; 100 101 // n'est execute qu'une fois lorsqu'on construit le FrameworkManager 102 if (parent == NULL) { 115 103 #ifdef __XENO__ 116 string tmp_name; 117 tmp_name=name + "-xml"; 118 int status=rt_heap_create(&xml_heap,tmp_name.c_str(),XML_HEAP,H_FIFO); 119 if(status!=0) 120 { 121 self->Err("rt_heap_create error (%s)\n",strerror(-status)); 122 } 123 124 xmlMemSetup(xml2_free,xml2_alloc, xml2_realloc,xml2_strdup); 104 string tmp_name; 105 tmp_name = name + "-xml"; 106 int status = rt_heap_create(&xml_heap, tmp_name.c_str(), XML_HEAP, H_FIFO); 107 if (status != 0) { 108 self->Err("rt_heap_create error (%s)\n", strerror(-status)); 109 } 110 111 xmlMemSetup(xml2_free, xml2_alloc, xml2_realloc, xml2_strdup); 125 112 #endif //__XENO__ 126 } 127 128 //xml init 129 if(parent==NULL) 130 { 131 //create local doc 132 send_doc = xmlNewDoc((xmlChar*)"1.0"); 133 send_node = xmlNewNode(NULL, (xmlChar*)type.c_str()); 134 xmlDocSetRootElement(send_doc, send_node); 135 xmlSetProp(send_node,(xmlChar*)"name",(xmlChar*)self->ObjectName().c_str()); 136 } 137 else 138 { 139 parent->pimpl_->AddChild(self); 140 141 //get node corresponding to this widget in the xml file 142 if(parent->pimpl_->file_node!=NULL) 143 { 144 xmlChar* search=xmlCharStrdup(type.c_str()); 145 file_node=GetNodeByProp(parent->pimpl_->file_node->xmlChildrenNode,search,(xmlChar*)"name",(xmlChar*)name.c_str()); 146 xmlFree(search); 147 } 148 else 149 { 150 self->Err("parent->file_node is NULL\n"); 151 } 152 153 if(file_node==NULL) 154 { 155 self->Warn("%s, no match found in xml file\n",type.c_str()); 156 xmlNode *node; 157 node=xmlNewNode(NULL, (xmlChar*)type.c_str()); 158 xmlSetProp(node,(xmlChar*)"name",(xmlChar*)name.c_str()); 159 file_node=xmlAddChild(parent->pimpl_->file_node,node); 160 //((Widget*)getFrameworkManager())->pimpl_->PrintXml(); 161 } 162 163 send_doc=parent->pimpl_->CopyDoc(); 164 165 //on recupere le dernier node 166 xmlNodePtr node=xmlDocGetRootElement(send_doc); 167 while(node->children!=NULL) node=node->children; 168 169 //on ajoute le node du widget 170 send_node = xmlNewNode(NULL, (xmlChar*)type.c_str()); 171 xmlSetProp(send_node,(xmlChar*)"name",(xmlChar*)name.c_str()); 172 xmlAddChild(node,send_node); 173 } 174 175 //Printf("Widget ok %s\n",name.c_str()); 176 } 177 178 Widget_impl::~Widget_impl() 179 { 180 //Printf("destruction widget %s\n",self->ObjectName().c_str()); 181 182 if(self->Parent()!=NULL) ((Widget*)(self->Parent()))->pimpl_->RemoveChild(self); 183 184 //on efface les widgets enfants avant d'envoyer son propre delete au sol 185 //dans le delete child on modifie le child du parent, donc on se refere toujours au premier 186 while(childs.size()!=0) 187 { 188 //Printf("child %i %s\n",childs.size(),childs.front()->ObjectName().c_str()); 189 if(childs.front()!=NULL) delete childs.front(); 190 } 191 childs.clear(); 192 193 self->SetVolatileXmlProp("Delete",true); 194 195 if(self->Parent()!=NULL) SendXml(); 196 197 xmlFreeDoc(send_doc); 198 199 if(self->Parent()==NULL) 200 { 201 xmlCleanupParser(); 113 } 114 115 // xml init 116 if (parent == NULL) { 117 // create local doc 118 send_doc = xmlNewDoc((xmlChar *)"1.0"); 119 send_node = xmlNewNode(NULL, (xmlChar *)type.c_str()); 120 xmlDocSetRootElement(send_doc, send_node); 121 xmlSetProp(send_node, (xmlChar *)"name", 122 (xmlChar *)self->ObjectName().c_str()); 123 } else { 124 parent->pimpl_->AddChild(self); 125 126 // get node corresponding to this widget in the xml file 127 if (parent->pimpl_->file_node != NULL) { 128 xmlChar *search = xmlCharStrdup(type.c_str()); 129 file_node = 130 GetNodeByProp(parent->pimpl_->file_node->xmlChildrenNode, search, 131 (xmlChar *)"name", (xmlChar *)name.c_str()); 132 xmlFree(search); 133 } else { 134 self->Err("parent->file_node is NULL\n"); 135 } 136 137 if (file_node == NULL) { 138 self->Warn("%s, no match found in xml file\n", type.c_str()); 139 xmlNode *node; 140 node = xmlNewNode(NULL, (xmlChar *)type.c_str()); 141 xmlSetProp(node, (xmlChar *)"name", (xmlChar *)name.c_str()); 142 file_node = xmlAddChild(parent->pimpl_->file_node, node); 143 //((Widget*)getFrameworkManager())->pimpl_->PrintXml(); 144 } 145 146 send_doc = parent->pimpl_->CopyDoc(); 147 148 // on recupere le dernier node 149 xmlNodePtr node = xmlDocGetRootElement(send_doc); 150 while (node->children != NULL) 151 node = node->children; 152 153 // on ajoute le node du widget 154 send_node = xmlNewNode(NULL, (xmlChar *)type.c_str()); 155 xmlSetProp(send_node, (xmlChar *)"name", (xmlChar *)name.c_str()); 156 xmlAddChild(node, send_node); 157 } 158 159 // Printf("Widget ok %s\n",name.c_str()); 160 } 161 162 Widget_impl::~Widget_impl() { 163 // Printf("destruction widget %s\n",self->ObjectName().c_str()); 164 165 if (self->Parent() != NULL) 166 ((Widget *)(self->Parent()))->pimpl_->RemoveChild(self); 167 168 // on efface les widgets enfants avant d'envoyer son propre delete au sol 169 // dans le delete child on modifie le child du parent, donc on se refere 170 // toujours au premier 171 while (childs.size() != 0) { 172 // Printf("child %i 173 // %s\n",childs.size(),childs.front()->ObjectName().c_str()); 174 if (childs.front() != NULL) 175 delete childs.front(); 176 } 177 childs.clear(); 178 179 self->SetVolatileXmlProp("Delete", true); 180 181 if (self->Parent() != NULL) 182 SendXml(); 183 184 xmlFreeDoc(send_doc); 185 186 if (self->Parent() == NULL) { 187 xmlCleanupParser(); 202 188 #ifdef __XENO__ 203 int status; 204 RT_HEAP_INFO info; 205 status=rt_heap_inquire(&xml_heap,&info); 206 if(status!=0) 207 { 208 self->Err("rt_heap_inquire error (%s)\n",strerror(-status)); 209 } 210 if(info.usedmem!=0) self->Err("fuite memoire xml heap (%ld)\n",info.usedmem); 211 //Printf("fin heap xml\n"); 212 status=rt_heap_delete(&xml_heap); 213 if(status!=0) 214 { 215 self->Err("rt_heap_delete error (%s)\n",strerror(-status)); 216 } 189 int status; 190 RT_HEAP_INFO info; 191 status = rt_heap_inquire(&xml_heap, &info); 192 if (status != 0) { 193 self->Err("rt_heap_inquire error (%s)\n", strerror(-status)); 194 } 195 if (info.usedmem != 0) 196 self->Err("fuite memoire xml heap (%ld)\n", info.usedmem); 197 // Printf("fin heap xml\n"); 198 status = rt_heap_delete(&xml_heap); 199 if (status != 0) { 200 self->Err("rt_heap_delete error (%s)\n", strerror(-status)); 201 } 217 202 #endif 218 } 219 //Printf("destruction widget %s ok\n",self->ObjectName().c_str()); 220 } 221 222 void Widget_impl::AddChild(const Widget* child) 223 { 224 childs.push_back((Widget*)child); 225 } 226 227 void Widget_impl::RemoveChild(const Widget* child) 228 { 229 for(vector<Widget*>::iterator it=childs.begin() ; it < childs.end(); it++ ) 230 { 231 if(*it==child) 232 { 233 childs.erase(it); 234 break; 235 } 236 } 237 } 238 239 xmlDocPtr Widget_impl::CopyDoc(void) 240 { 241 return xmlCopyDoc(send_doc,1); 242 } 203 } 204 // Printf("destruction widget %s ok\n",self->ObjectName().c_str()); 205 } 206 207 void Widget_impl::AddChild(const Widget *child) { 208 childs.push_back((Widget *)child); 209 } 210 211 void Widget_impl::RemoveChild(const Widget *child) { 212 for (vector<Widget *>::iterator it = childs.begin(); it < childs.end(); 213 it++) { 214 if (*it == child) { 215 childs.erase(it); 216 break; 217 } 218 } 219 } 220 221 xmlDocPtr Widget_impl::CopyDoc(void) { return xmlCopyDoc(send_doc, 1); } 243 222 244 223 void Widget_impl::ClearXmlProps(void) { 245 xmlUnlinkNode(send_node); 246 xmlFreeNode(send_node); 247 248 xmlNodePtr node; 249 node=xmlDocGetRootElement(send_doc); 250 251 if(node==NULL) {//il ne reste plus rien, on refait le rootelement 252 send_node = xmlNewNode(NULL, (xmlChar*)XML_ROOT_TYPE); 253 xmlSetProp(send_node,(xmlChar*)"name",(xmlChar*)self->ObjectName().c_str()); 254 xmlDocSetRootElement(send_doc, send_node); 255 } else { 256 while(node->children!=NULL) node=node->children; 257 send_node = xmlNewNode(NULL, (xmlChar*)self->ObjectType().c_str()); 258 xmlSetProp(send_node,(xmlChar*)"name",(xmlChar*)self->ObjectName().c_str()); 259 xmlAddChild(node,send_node); 260 } 224 xmlUnlinkNode(send_node); 225 xmlFreeNode(send_node); 226 227 xmlNodePtr node; 228 node = xmlDocGetRootElement(send_doc); 229 230 if (node == NULL) { // il ne reste plus rien, on refait le rootelement 231 send_node = xmlNewNode(NULL, (xmlChar *)XML_ROOT_TYPE); 232 xmlSetProp(send_node, (xmlChar *)"name", 233 (xmlChar *)self->ObjectName().c_str()); 234 xmlDocSetRootElement(send_doc, send_node); 235 } else { 236 while (node->children != NULL) 237 node = node->children; 238 send_node = xmlNewNode(NULL, (xmlChar *)self->ObjectType().c_str()); 239 xmlSetProp(send_node, (xmlChar *)"name", 240 (xmlChar *)self->ObjectName().c_str()); 241 xmlAddChild(node, send_node); 242 } 261 243 } 262 244 263 245 void Widget_impl::printSendNode() { 264 246 247 xmlChar *xmlbuff; 248 int buffersize; 249 xmlDocDumpFormatMemory(send_doc, &xmlbuff, &buffersize, 1); 250 Printf("xml:\n%s\n", xmlbuff); 251 xmlFree(xmlbuff); 252 } 253 254 void Widget_impl::SendXml(void) { 255 if (getUiCom() != NULL) { 265 256 xmlChar *xmlbuff; 266 257 int buffersize; 267 xmlDocDumpFormatMemory(send_doc, &xmlbuff, &buffersize, 1);268 Printf("xml:\n%s\n",xmlbuff);258 xmlDocDumpFormatMemory(send_doc, &xmlbuff, &buffersize, 0); 259 getUiCom()->Send((char *)xmlbuff, buffersize); 269 260 xmlFree(xmlbuff); 270 } 271 272 void Widget_impl::SendXml(void) 273 { 274 if(getUiCom()!=NULL) { 275 xmlChar *xmlbuff; 276 int buffersize; 277 xmlDocDumpFormatMemory(send_doc, &xmlbuff, &buffersize, 0); 278 getUiCom()->Send((char*)xmlbuff,buffersize); 279 xmlFree(xmlbuff); 280 281 ClearXmlProps(); 282 } 261 262 ClearXmlProps(); 263 } 283 264 } 284 265 285 266 void Widget_impl::setEnabled(bool status) { 286 self->SetVolatileXmlProp("IsEnabled",status); 287 SendXml(); 288 } 289 290 291 void Widget_impl::ProcessXML(xmlNode *node) 292 { 293 //Printf("ProcessXML %s %s\n",xmlGetProp(send_node, (xmlChar*)"name"),send_node->name); 294 xmlNode *cur_node = NULL; 295 296 for(size_t i=0;i<childs.size();i++) 297 { 298 for (cur_node = node; cur_node; cur_node = cur_node->next) 299 { 300 if (cur_node->type == XML_ELEMENT_NODE) 301 { 302 //Printf("recherche %s\n", xmlGetProp(cur_node, (xmlChar*)"name")); 303 xmlChar* name=NULL; 304 name=xmlGetProp(cur_node, (xmlChar*)"name"); 305 if (!xmlStrcmp((xmlChar *)childs[i]->ObjectName().c_str(), name)) 306 { 307 //Printf("correspond %s\n",childs[i]->ObjectName().c_str()); 308 xmlChar* new_name=NULL; 309 new_name=xmlGetProp(cur_node, (xmlChar*)"new_name"); 310 if(new_name!=NULL) 311 { 312 unsigned char* ren_name=new_name;//xmlGetProp(cur_node, (xmlChar*)"new_name"); 313 self->Warn("%s existe deja, renommage en %s; possiblite de problemes!!\n",childs[i]->ObjectName().c_str(),new_name); 314 childs[i]->Object::pimpl_->name=((const char*)ren_name); 315 xmlSetProp(childs[i]->pimpl_->send_node,(xmlChar*)"name",xmlGetProp(cur_node, (xmlChar*)"new_name")); 316 xmlFree(new_name); 317 if(name!=NULL) xmlFree(name); 318 break; 319 } 320 321 if(name!=NULL) xmlFree(name); 322 323 //update file node 324 xmlAttr *cur_prop = NULL; 325 //xmlAttr *file_prop = NULL; 326 for (cur_prop = cur_node->properties; cur_prop; cur_prop = cur_prop->next) 327 { 328 //Printf("rcv prop %s %s\n",cur_prop->name,cur_prop->children->content); 329 xmlSetProp(childs[i]->pimpl_->file_node,cur_prop->name,cur_prop->children->content); 330 } 331 332 childs[i]->XmlEvent(); 333 334 childs[i]->pimpl_->ProcessXML(cur_node->children); 335 break; 336 337 } 338 if(name!=NULL) xmlFree(name); 339 } 267 self->SetVolatileXmlProp("IsEnabled", status); 268 SendXml(); 269 } 270 271 void Widget_impl::ProcessXML(xmlNode *node) { 272 // Printf("ProcessXML %s %s\n",xmlGetProp(send_node, 273 // (xmlChar*)"name"),send_node->name); 274 xmlNode *cur_node = NULL; 275 276 for (size_t i = 0; i < childs.size(); i++) { 277 for (cur_node = node; cur_node; cur_node = cur_node->next) { 278 if (cur_node->type == XML_ELEMENT_NODE) { 279 // Printf("recherche %s\n", xmlGetProp(cur_node, (xmlChar*)"name")); 280 xmlChar *name = NULL; 281 name = xmlGetProp(cur_node, (xmlChar *)"name"); 282 if (!xmlStrcmp((xmlChar *)childs[i]->ObjectName().c_str(), name)) { 283 // Printf("correspond %s\n",childs[i]->ObjectName().c_str()); 284 xmlChar *new_name = NULL; 285 new_name = xmlGetProp(cur_node, (xmlChar *)"new_name"); 286 if (new_name != NULL) { 287 unsigned char *ren_name = 288 new_name; // xmlGetProp(cur_node, (xmlChar*)"new_name"); 289 self->Warn( 290 "%s existe deja, renommage en %s; possiblite de problemes!!\n", 291 childs[i]->ObjectName().c_str(), new_name); 292 childs[i]->Object::pimpl_->name = ((const char *)ren_name); 293 xmlSetProp(childs[i]->pimpl_->send_node, (xmlChar *)"name", 294 xmlGetProp(cur_node, (xmlChar *)"new_name")); 295 xmlFree(new_name); 296 if (name != NULL) 297 xmlFree(name); 298 break; 299 } 300 301 if (name != NULL) 302 xmlFree(name); 303 304 // update file node 305 xmlAttr *cur_prop = NULL; 306 // xmlAttr *file_prop = NULL; 307 for (cur_prop = cur_node->properties; cur_prop; 308 cur_prop = cur_prop->next) { 309 // Printf("rcv prop %s 310 // %s\n",cur_prop->name,cur_prop->children->content); 311 xmlSetProp(childs[i]->pimpl_->file_node, cur_prop->name, 312 cur_prop->children->content); 313 } 314 315 childs[i]->XmlEvent(); 316 317 childs[i]->pimpl_->ProcessXML(cur_node->children); 318 break; 340 319 } 341 } 342 343 //printf("fin ProcessXML %s %s\n",xmlGetProp(send_node, (xmlChar*)"name"),send_node->name); 344 } 345 346 347 xmlNodePtr Widget_impl::GetNodeByProp(xmlNodePtr doc,xmlChar *type,xmlChar *prop,xmlChar *value) 348 { 349 //printf("cherche keyword: %s %s %s\n", type,prop,value); 350 xmlNode *cur_node = NULL; 351 for (cur_node = doc; cur_node; cur_node = cur_node->next) 352 { 353 if (cur_node->type == XML_ELEMENT_NODE) 354 { 355 //printf("node %s %s\n",xmlGetProp(cur_node, (xmlChar*)"name"),cur_node->name); 356 xmlChar *test = NULL; 357 test=xmlGetProp(cur_node, prop); 358 if(!xmlStrcmp(test,value) && !xmlStrcmp(cur_node->name,type )) 359 { 360 //printf("ok\n"); 361 if(test!=NULL) xmlFree(test); 362 return cur_node; 363 } 364 if(test!=NULL) xmlFree(test); 365 } 366 } 367 368 return NULL; 369 } 320 if (name != NULL) 321 xmlFree(name); 322 } 323 } 324 } 325 326 // printf("fin ProcessXML %s %s\n",xmlGetProp(send_node, 327 // (xmlChar*)"name"),send_node->name); 328 } 329 330 xmlNodePtr Widget_impl::GetNodeByProp(xmlNodePtr doc, xmlChar *type, 331 xmlChar *prop, xmlChar *value) { 332 // printf("cherche keyword: %s %s %s\n", type,prop,value); 333 xmlNode *cur_node = NULL; 334 for (cur_node = doc; cur_node; cur_node = cur_node->next) { 335 if (cur_node->type == XML_ELEMENT_NODE) { 336 // printf("node %s %s\n",xmlGetProp(cur_node, 337 // (xmlChar*)"name"),cur_node->name); 338 xmlChar *test = NULL; 339 test = xmlGetProp(cur_node, prop); 340 if (!xmlStrcmp(test, value) && !xmlStrcmp(cur_node->name, type)) { 341 // printf("ok\n"); 342 if (test != NULL) 343 xmlFree(test); 344 return cur_node; 345 } 346 if (test != NULL) 347 xmlFree(test); 348 } 349 } 350 351 return NULL; 352 } -
trunk/lib/FlairCore/src/cvimage.cpp
r2 r15 19 19 using std::string; 20 20 21 namespace flair { namespace core { 21 namespace flair { 22 namespace core { 22 23 23 cvimage::cvimage(const Object* parent,uint16_t width,uint16_t height,Type::Format format,string name,bool allocate_data,int n): io_data(parent,name,n),dataType(width,height,format) { 24 this->allocate_data=allocate_data; 24 cvimage::cvimage(const Object *parent, uint16_t width, uint16_t height, 25 Type::Format format, string name, bool allocate_data, int n) 26 : io_data(parent, name, n), dataType(width, height, format) { 27 this->allocate_data = allocate_data; 25 28 26 if(allocate_data) { 27 switch(format) { 28 case Type::Format::YUYV: 29 case Type::Format::UYVY: 30 img=cvCreateImage(cvSize(width,height),IPL_DEPTH_8U,2); 31 break; 32 case Type::Format::BGR: 33 img=cvCreateImage(cvSize(width,height),IPL_DEPTH_8U,3); 34 break; 35 case Type::Format::GRAY: 36 img=cvCreateImage(cvSize(width,height),IPL_DEPTH_8U,1); 37 break; 38 default: 39 Err("format no supported"); 40 break; 41 } 42 } else { 43 if(n>1) Err("number of samples!=1 not possible when not allocating data\n"); 44 n=1; 45 switch(format) { 46 case Type::Format::YUYV: 47 case Type::Format::UYVY: 48 img=cvCreateImageHeader(cvSize(width,height),IPL_DEPTH_8U,2); 49 break; 50 case Type::Format::BGR: 51 img=cvCreateImageHeader(cvSize(width,height),IPL_DEPTH_8U,3); 52 break; 53 case Type::Format::GRAY: 54 img=cvCreateImageHeader(cvSize(width,height),IPL_DEPTH_8U,1); 55 break; 56 default: 57 Err("format no supported"); 58 break; 59 } 29 if (allocate_data) { 30 switch (format) { 31 case Type::Format::YUYV: 32 case Type::Format::UYVY: 33 img = cvCreateImage(cvSize(width, height), IPL_DEPTH_8U, 2); 34 break; 35 case Type::Format::BGR: 36 img = cvCreateImage(cvSize(width, height), IPL_DEPTH_8U, 3); 37 break; 38 case Type::Format::GRAY: 39 img = cvCreateImage(cvSize(width, height), IPL_DEPTH_8U, 1); 40 break; 41 default: 42 Err("format no supported"); 43 break; 60 44 } 45 } else { 46 if (n > 1) 47 Err("number of samples!=1 not possible when not allocating data\n"); 48 n = 1; 49 switch (format) { 50 case Type::Format::YUYV: 51 case Type::Format::UYVY: 52 img = cvCreateImageHeader(cvSize(width, height), IPL_DEPTH_8U, 2); 53 break; 54 case Type::Format::BGR: 55 img = cvCreateImageHeader(cvSize(width, height), IPL_DEPTH_8U, 3); 56 break; 57 case Type::Format::GRAY: 58 img = cvCreateImageHeader(cvSize(width, height), IPL_DEPTH_8U, 1); 59 break; 60 default: 61 Err("format no supported"); 62 break; 63 } 64 } 61 65 62 SetPtrToCircle((void**)&img);66 SetPtrToCircle((void **)&img); 63 67 64 if(n>1) prev=new cvimage(this,width,height,format,name,n-1); 68 if (n > 1) 69 prev = new cvimage(this, width, height, format, name, n - 1); 65 70 } 66 71 67 72 cvimage::~cvimage() { 68 //printf("destructeur cvimage\n");73 // printf("destructeur cvimage\n"); 69 74 70 75 cvReleaseImage(&img); 71 76 } 72 77 73 void cvimage::CopyDatas(char* dst) const { 74 Warn("non implementé\n"); 75 } 78 void cvimage::CopyDatas(char *dst) const { Warn("non implementé\n"); } 76 79 77 80 } // end namespace core -
trunk/lib/FlairCore/src/cvimage.h
r2 r15 18 18 #include <stdint.h> 19 19 20 namespace flair 21 { 22 namespace core 23 { 24 /*! \class cvimage 25 * 26 * \brief Class defining an image of kind IplImage 27 * 28 * IplImage is an image struct defined in OpenCV. 29 * 20 namespace flair { 21 namespace core { 22 /*! \class cvimage 23 * 24 * \brief Class defining an image of kind IplImage 25 * 26 * IplImage is an image struct defined in OpenCV. 27 * 28 */ 29 class cvimage : public io_data { 30 public: 31 class Type : public DataType { 32 public: 33 /*! 34 \enum Format_t 35 \brief Picture formats 30 36 */ 31 class cvimage: public io_data { 32 public: 33 class Type: public DataType { 34 public: 35 /*! 36 \enum Format_t 37 \brief Picture formats 38 */ 39 enum class Format { 40 YUYV,/*!< YUYV 16 bits */ 41 UYVY,/*!< UYVY 16 bits */ 42 BGR,/*!< BGR 24 bits */ 43 GRAY,/*!< gray 8 bits */ 44 } ; 45 Type(uint16_t _width, uint16_t _height, Format _format):width(_width),height(_height),format(_format) {} 37 enum class Format { 38 YUYV, /*!< YUYV 16 bits */ 39 UYVY, /*!< UYVY 16 bits */ 40 BGR, /*!< BGR 24 bits */ 41 GRAY, /*!< gray 8 bits */ 42 }; 43 Type(uint16_t _width, uint16_t _height, Format _format) 44 : width(_width), height(_height), format(_format) {} 46 45 47 48 49 switch(format) {50 51 pixelSize=1;52 53 54 55 pixelSize=2;56 57 58 pixelSize=3;59 60 61 pixelSize=0; //TODO should throw an exception instead62 63 return pixelSize*width*height;64 65 std::string GetDescription() const {return "cv image";};46 size_t GetSize() const { 47 size_t pixelSize; 48 switch (format) { 49 case Format::GRAY: 50 pixelSize = 1; 51 break; 52 case Format::YUYV: 53 case Format::UYVY: 54 pixelSize = 2; 55 break; 56 case Format::BGR: 57 pixelSize = 3; 58 break; 59 default: 60 pixelSize = 0; // TODO should throw an exception instead 61 } 62 return pixelSize * width * height; 63 } 64 std::string GetDescription() const { return "cv image"; }; 66 65 67 Format GetFormat() const {return format;};68 uint16_t GetWidth() const {return width;};69 uint16_t GetHeight() const {return height;};66 Format GetFormat() const { return format; }; 67 uint16_t GetWidth() const { return width; }; 68 uint16_t GetHeight() const { return height; }; 70 69 71 private: 72 uint16_t width; 73 uint16_t height; 74 Format format; 70 private: 71 uint16_t width; 72 uint16_t height; 73 Format format; 74 }; 75 75 76 }; 76 /*! 77 * \brief Constructor 78 * 79 * Construct an io_data representing an IplImage. 80 * 81 * \param parent parent 82 * \param width image width 83 * \param height image height 84 * \param name name 85 * \param allocate_data if true, IplImage image data is allocated; otherwise 86 *img->imagedata must be changed 87 * \param n number of samples 88 */ 89 cvimage(const Object *parent, uint16_t width, uint16_t height, 90 Type::Format format, std::string name = "", bool allocate_data = true, 91 int n = 1); 77 92 78 /*! 79 * \brief Constructor 80 * 81 * Construct an io_data representing an IplImage. 82 * 83 * \param parent parent 84 * \param width image width 85 * \param height image height 86 * \param name name 87 * \param allocate_data if true, IplImage image data is allocated; otherwise img->imagedata must be changed 88 * \param n number of samples 89 */ 90 cvimage(const Object* parent,uint16_t width,uint16_t height,Type::Format format,std::string name="",bool allocate_data=true,int n=1); 93 /*! 94 * \brief Destructor 95 * 96 */ 97 ~cvimage(); 91 98 92 /*! 93 * \brief Destructor 94 * 95 */ 96 ~cvimage(); 99 /*! 100 * \brief IplImage 101 * 102 * \return IplImage 103 */ 104 IplImage *img; 97 105 98 /*! 99 * \brief IplImage 100 * 101 * \return IplImage 102 */ 103 IplImage* img; 106 Type const &GetDataType() const { return dataType; }; 104 107 105 Type const&GetDataType() const {return dataType;}; 108 private: 109 /*! 110 * \brief Copy datas 111 * 112 * Reimplemented from io_data. \n 113 * See io_data::CopyDatas. 114 * 115 * \param dst destination buffer 116 */ 117 void CopyDatas(char *dst) const; 106 118 107 private: 108 /*! 109 * \brief Copy datas 110 * 111 * Reimplemented from io_data. \n 112 * See io_data::CopyDatas. 113 * 114 * \param dst destination buffer 115 */ 116 void CopyDatas(char* dst) const; 117 118 bool allocate_data; 119 Type dataType; 120 }; 119 bool allocate_data; 120 Type dataType; 121 }; 121 122 122 123 } // end namespace core -
trunk/lib/FlairCore/src/cvmatrix.cpp
r2 r15 24 24 using std::string; 25 25 26 namespace flair { namespace core { 27 /*! \class cvmatrixElement 28 */ 29 class cvmatrixElement: public IODataElement { 30 public: 31 cvmatrixElement(const cvmatrix *matrix,string name,uint32_t row, uint32_t col):IODataElement(matrix,name) { 32 this->matrix=matrix; 33 this->row=row; 34 this->col=col; 35 if(row>=matrix->Rows() || col>=matrix->Cols()) { 36 matrix->Err("index (%i,%i) out of bound (%i,%i)\n",row,col,matrix->Rows()-1,matrix->Cols()-1); 37 size=0; 38 } else { 39 try { 40 ScalarType const &scalarType=dynamic_cast<ScalarType const &>(matrix->GetDataType().GetElementDataType()); 41 size=scalarType.GetSize(); 42 } catch (std::bad_cast e) { 43 matrix->Err("type not handled\n"); 44 size=0; 45 } 46 } 47 } 26 namespace flair { 27 namespace core { 28 /*! \class cvmatrixElement 29 */ 30 class cvmatrixElement : public IODataElement { 31 public: 32 cvmatrixElement(const cvmatrix *matrix, string name, uint32_t row, 33 uint32_t col) 34 : IODataElement(matrix, name) { 35 this->matrix = matrix; 36 this->row = row; 37 this->col = col; 38 if (row >= matrix->Rows() || col >= matrix->Cols()) { 39 matrix->Err("index (%i,%i) out of bound (%i,%i)\n", row, col, 40 matrix->Rows() - 1, matrix->Cols() - 1); 41 size = 0; 42 } else { 43 try { 44 ScalarType const &scalarType = dynamic_cast<ScalarType const &>( 45 matrix->GetDataType().GetElementDataType()); 46 size = scalarType.GetSize(); 47 } catch (std::bad_cast e) { 48 matrix->Err("type not handled\n"); 49 size = 0; 50 } 51 } 52 } 48 53 49 ~cvmatrixElement() { 50 } 54 ~cvmatrixElement() {} 51 55 52 void CopyData(char*dst) const {53 if (typeid(matrix->GetDataType().GetElementDataType())==typeid(FloatType)) {54 float value=matrix->Value(row,col);55 memcpy(dst,&value,sizeof(value));56 } else if (typeid(matrix->GetDataType().GetElementDataType())==typeid(SignedIntegerType)) {57 switch(matrix->GetDataType().GetElementDataType().GetSize()) {58 case 1:{59 int8_t int8Value=matrix->Value(row,col);60 memcpy(dst,&int8Value,1);61 }62 break;63 case 2: {64 int16_t int16Value=matrix->Value(row,col);65 memcpy(dst,&int16Value,2);66 }67 68 69 70 56 void CopyData(char *dst) const { 57 if (typeid(matrix->GetDataType().GetElementDataType()) == 58 typeid(FloatType)) { 59 float value = matrix->Value(row, col); 60 memcpy(dst, &value, sizeof(value)); 61 } else if (typeid(matrix->GetDataType().GetElementDataType()) == 62 typeid(SignedIntegerType)) { 63 switch (matrix->GetDataType().GetElementDataType().GetSize()) { 64 case 1: { 65 int8_t int8Value = matrix->Value(row, col); 66 memcpy(dst, &int8Value, 1); 67 } break; 68 case 2: { 69 int16_t int16Value = matrix->Value(row, col); 70 memcpy(dst, &int16Value, 2); 71 } break; 72 } 73 } 74 } 71 75 72 73 74 76 DataType const &GetDataType(void) const { 77 return matrix->GetDataType().GetElementDataType(); 78 } 75 79 76 private: 77 const cvmatrix *matrix; 78 uint32_t row,col; 80 private: 81 const cvmatrix *matrix; 82 uint32_t row, col; 83 }; 79 84 80 }; 85 cvmatrix::cvmatrix(const Object *parent, uint32_t rows, uint32_t cols, 86 ScalarType const &elementDataType, string name, uint32_t n) 87 : io_data(parent, name, n), dataType(rows, cols, elementDataType) { 88 pimpl_ = new cvmatrix_impl(this, rows, cols, elementDataType, n); 81 89 82 cvmatrix::cvmatrix(const Object* parent,uint32_t rows, uint32_t cols, ScalarType const &elementDataType,string name,uint32_t n): io_data(parent,name,n),dataType(rows,cols,elementDataType) { 83 pimpl_=new cvmatrix_impl(this,rows,cols,elementDataType,n); 84 85 for(uint32_t i=0;i<rows;i++) { 86 for(uint32_t j=0;j<cols;j++) { 87 AppendLogDescription(pimpl_->descriptor->ElementName(i,j),elementDataType); 88 SetValue(i,j,0); 89 } 90 for (uint32_t i = 0; i < rows; i++) { 91 for (uint32_t j = 0; j < cols; j++) { 92 AppendLogDescription(pimpl_->descriptor->ElementName(i, j), 93 elementDataType); 94 SetValue(i, j, 0); 90 95 } 96 } 91 97 } 92 98 93 cvmatrix::cvmatrix(const Object* parent,const cvmatrix_descriptor *descriptor, ScalarType const &elementDataType,string name,uint32_t n): io_data(parent,name,n),dataType(descriptor->Rows(),descriptor->Cols(),elementDataType) { 94 pimpl_=new cvmatrix_impl(this,descriptor,elementDataType,n); 99 cvmatrix::cvmatrix(const Object *parent, const cvmatrix_descriptor *descriptor, 100 ScalarType const &elementDataType, string name, uint32_t n) 101 : io_data(parent, name, n), 102 dataType(descriptor->Rows(), descriptor->Cols(), elementDataType) { 103 pimpl_ = new cvmatrix_impl(this, descriptor, elementDataType, n); 95 104 96 for(uint32_t i=0;i<descriptor->Rows();i++) { 97 for(uint32_t j=0;j<descriptor->Cols();j++) { 98 AppendLogDescription(descriptor->ElementName(i,j),elementDataType); 99 SetValue(i,j,0); 100 } 105 for (uint32_t i = 0; i < descriptor->Rows(); i++) { 106 for (uint32_t j = 0; j < descriptor->Cols(); j++) { 107 AppendLogDescription(descriptor->ElementName(i, j), elementDataType); 108 SetValue(i, j, 0); 101 109 } 110 } 102 111 } 103 112 104 cvmatrix::~cvmatrix() { 105 delete pimpl_; 113 cvmatrix::~cvmatrix() { delete pimpl_; } 114 115 IODataElement *cvmatrix::Element(uint32_t row, uint32_t col) const { 116 return new cvmatrixElement(this, Name(row, col), row, col); 106 117 } 107 118 108 IODataElement* cvmatrix::Element(uint32_t row, uint32_t col) const { 109 return new cvmatrixElement(this,Name(row,col),row,col); 110 } 111 112 IODataElement* cvmatrix::Element(uint32_t index) const { 113 if(Rows()==1) { 114 return new cvmatrixElement(this,Name(0,index),0,index); 115 } else if(Cols()==1) { 116 return new cvmatrixElement(this,Name(index,0),index,0); 117 } else { 118 Err("matrix is not 1D\n"); 119 return nullptr; 120 } 119 IODataElement *cvmatrix::Element(uint32_t index) const { 120 if (Rows() == 1) { 121 return new cvmatrixElement(this, Name(0, index), 0, index); 122 } else if (Cols() == 1) { 123 return new cvmatrixElement(this, Name(index, 0), index, 0); 124 } else { 125 Err("matrix is not 1D\n"); 126 return nullptr; 127 } 121 128 } 122 129 123 130 float cvmatrix::Value(uint32_t row, uint32_t col) const { 124 131 float value; 125 132 126 if(row>=(uint32_t)pimpl_->mat->rows || col>=(uint32_t)pimpl_->mat->cols) { 127 Warn("index (%i,%i) out of bound (%i,%i)\n",row,col,pimpl_->mat->rows-1,pimpl_->mat->cols-1); 128 return 0; 129 } 133 if (row >= (uint32_t)pimpl_->mat->rows || 134 col >= (uint32_t)pimpl_->mat->cols) { 135 Warn("index (%i,%i) out of bound (%i,%i)\n", row, col, 136 pimpl_->mat->rows - 1, pimpl_->mat->cols - 1); 137 return 0; 138 } 130 139 131 132 value=cvGetReal2D(pimpl_->mat,row,col);133 140 GetMutex(); 141 value = cvGetReal2D(pimpl_->mat, row, col); 142 ReleaseMutex(); 134 143 135 144 return value; 136 145 } 137 146 138 147 float cvmatrix::ValueNoMutex(uint32_t row, uint32_t col) const { 139 if(row>=(uint32_t)pimpl_->mat->rows || col>=(uint32_t)pimpl_->mat->cols) { 140 Warn("index (%i,%i) out of bound (%i,%i)\n",row,col,pimpl_->mat->rows-1,pimpl_->mat->cols-1); 141 return 0; 142 } 148 if (row >= (uint32_t)pimpl_->mat->rows || 149 col >= (uint32_t)pimpl_->mat->cols) { 150 Warn("index (%i,%i) out of bound (%i,%i)\n", row, col, 151 pimpl_->mat->rows - 1, pimpl_->mat->cols - 1); 152 return 0; 153 } 143 154 144 return cvGetReal2D(pimpl_->mat,row,col);155 return cvGetReal2D(pimpl_->mat, row, col); 145 156 } 146 157 147 void cvmatrix::SetValue(uint32_t row, uint32_t col,float value) { 148 if(row>=(uint32_t)pimpl_->mat->rows || col>=(uint32_t)pimpl_->mat->cols) { 149 Warn("index (%i,%i) out of bound (%i,%i)\n",row,col,pimpl_->mat->rows-1,pimpl_->mat->cols-1); 150 } else { 151 GetMutex(); 152 cvSetReal2D(pimpl_->mat,row,col,value); 153 ReleaseMutex(); 154 } 158 void cvmatrix::SetValue(uint32_t row, uint32_t col, float value) { 159 if (row >= (uint32_t)pimpl_->mat->rows || 160 col >= (uint32_t)pimpl_->mat->cols) { 161 Warn("index (%i,%i) out of bound (%i,%i)\n", row, col, 162 pimpl_->mat->rows - 1, pimpl_->mat->cols - 1); 163 } else { 164 GetMutex(); 165 cvSetReal2D(pimpl_->mat, row, col, value); 166 ReleaseMutex(); 167 } 155 168 } 156 169 157 void cvmatrix::SetValueNoMutex(uint32_t row, uint32_t col,float value) { 158 if(row>=(uint32_t)pimpl_->mat->rows || col>=(uint32_t)pimpl_->mat->cols) { 159 Warn("index (%i,%i) out of bound (%i,%i)\n",row,col,pimpl_->mat->rows-1,pimpl_->mat->cols-1); 160 } else { 161 cvSetReal2D(pimpl_->mat,row,col,value); 162 } 170 void cvmatrix::SetValueNoMutex(uint32_t row, uint32_t col, float value) { 171 if (row >= (uint32_t)pimpl_->mat->rows || 172 col >= (uint32_t)pimpl_->mat->cols) { 173 Warn("index (%i,%i) out of bound (%i,%i)\n", row, col, 174 pimpl_->mat->rows - 1, pimpl_->mat->cols - 1); 175 } else { 176 cvSetReal2D(pimpl_->mat, row, col, value); 177 } 163 178 } 164 179 165 CvMat* cvmatrix::getCvMat(void) const { 166 return pimpl_->mat; 180 CvMat *cvmatrix::getCvMat(void) const { return pimpl_->mat; } 181 182 void cvmatrix::CopyDatas(char *dst) const { 183 GetMutex(); 184 // printf("%f %x %i\n",cvGetReal2D(pimpl_->mat,0,0),dst,Size()); 185 memcpy(dst, pimpl_->mat->data.ptr, dataType.GetSize()); 186 ReleaseMutex(); 167 187 } 168 188 169 void cvmatrix::CopyDatas(char* dst) const { 170 GetMutex(); 171 //printf("%f %x %i\n",cvGetReal2D(pimpl_->mat,0,0),dst,Size()); 172 memcpy(dst,pimpl_->mat->data.ptr,dataType.GetSize()); 173 ReleaseMutex(); 174 } 189 uint32_t cvmatrix::Rows(void) const { return pimpl_->mat->rows; } 175 190 176 uint32_t cvmatrix::Rows(void) const { 177 return pimpl_->mat->rows; 178 } 179 180 uint32_t cvmatrix::Cols(void) const { 181 return pimpl_->mat->cols; 182 } 191 uint32_t cvmatrix::Cols(void) const { return pimpl_->mat->cols; } 183 192 184 193 string cvmatrix::Name(uint32_t row, uint32_t col) const { 185 return pimpl_->descriptor->ElementName(row,col);194 return pimpl_->descriptor->ElementName(row, col); 186 195 } 187 188 196 189 197 } // end namespace core -
trunk/lib/FlairCore/src/cvmatrix.h
r2 r15 21 21 struct CvMat; 22 22 23 namespace flair { namespace core { 24 25 /*! \class cvmatrix 26 * 27 * \brief Class defining a matrix of kind CvMat 28 * 29 * CvMat is a matrix struct defined in OpenCV. 30 * 31 */ 32 class cvmatrix: public io_data { 33 public: 34 class Type: public DataType { 35 public: 36 Type(size_t _nbRows,size_t _nbCols,ScalarType const &_elementDataType):nbRows(_nbRows),nbCols(_nbCols),elementDataType(_elementDataType) {} 37 size_t GetSize() const { 38 return nbRows*nbCols*elementDataType.GetSize(); 39 } 40 std::string GetDescription() const {return "matrix";} 41 size_t GetNbRows() const {return nbRows;} 42 size_t GetNbCols() const {return nbCols;} 43 ScalarType const &GetElementDataType() const {return elementDataType;} 44 45 private: 46 size_t nbRows,nbCols; 47 ScalarType const &elementDataType; 48 }; 49 50 /*! 51 * \brief Constructor 52 * 53 * Construct an io_data representing a CvMat. \n 54 * It uses a cvmatrix_descriptor to get size and elements' names. \n 55 * Names are used for graphs and logs. 56 * 57 * \param parent parent 58 * \param descriptor matrix description 59 * \param type type of matrix elements 60 * \param name name 61 * \param n number of samples 62 */ 63 cvmatrix(const Object* parent,const cvmatrix_descriptor *descriptor, ScalarType const &elementDataType,std::string name="",uint32_t n=1); 64 65 /*! 66 * \brief Constructor 67 * 68 * Construct an io_data representing a CvMat. \n 69 * Elements are unamed. 70 * 71 * \param parent parent 72 * \param rows matrix rows 73 * \param cols matrix cols 74 * \param type type of matrix elements 75 * \param name name 76 * \param n number of samples 77 */ 78 cvmatrix(const Object* parent,uint32_t rows, uint32_t cols, ScalarType const &elementDataType,std::string name="",uint32_t n=1); 79 80 /*! 81 * \brief Destructor 82 * 83 */ 84 ~cvmatrix(); 85 86 /*! 87 * \brief Element value 88 * 89 * Element is accessed by locking and unlocking the io_data Mutex. 90 * 91 * \param row element row 92 * \param col element col 93 * 94 * \return element value 95 */ 96 float Value(uint32_t row, uint32_t col) const; 97 98 /*! 99 * \brief Element value 100 * 101 * Element is not accessed by locking and unlocking the io_data Mutex. \n 102 * Thus, this function should be called with Mutex locked. \n 103 * This function is usefull when multiple successive access are done to the 104 * elments of the matrix. It avoids unnecessary locking and unlocking. 105 * 106 * \param row element row 107 * \param col element col 108 * 109 * \return element value 110 */ 111 float ValueNoMutex(uint32_t row, uint32_t col) const; 112 113 /*! 114 * \brief Set element value 115 * 116 * Element is accessed by locking and unlocking the io_data Mutex. 117 * 118 * \param row element row 119 * \param col element col 120 * \param value element value 121 */ 122 void SetValue(uint32_t row, uint32_t col,float value); 123 124 /*! 125 * \brief Set element value 126 * 127 * Element is not accessed by locking and unlocking the io_data Mutex. \n 128 * Thus, this function should be called with Mutex locked. \n 129 * This function is usefull when multiple successive access are done to the 130 * elments of the matrix. It avoids unnecessary locking and unlocking. 131 * 132 * \param row element row 133 * \param col element col 134 * \param value element value 135 */ 136 void SetValueNoMutex(uint32_t row, uint32_t col,float value); 137 138 /*! 139 * \brief get CvMat 140 * 141 * The io_data Mutex must be used by the user. 142 */ 143 CvMat* getCvMat(void) const; 144 145 /*! 146 * \brief Element name 147 * 148 * If cvmatrix was created without cvmatrix_descriptor, element name is empty. 149 * 150 * \param row element row 151 * \param col element col 152 * 153 * \return element name 154 */ 155 std::string Name(uint32_t row, uint32_t col) const; 156 157 /*! 158 * \brief Element 159 * 160 * Get a pointer to a specific element. This pointer can be used for plotting. 161 * 162 * \param row element row 163 * \param col element col 164 * 165 * \return pointer to the element 166 */ 167 IODataElement* Element(uint32_t row, uint32_t col) const; 168 169 /*! 170 * \brief Element 171 * 172 * Get a pointer to a specific element. This pointer can be used for plotting. \n 173 * This function can be used for a 1D matrix. 174 * 175 * \param index element index 176 * 177 * \return pointer to the element 178 */ 179 IODataElement* Element(uint32_t index) const; 180 181 /*! 182 * \brief Number of rows 183 * 184 * \return rows 185 */ 186 uint32_t Rows(void) const; 187 188 /*! 189 * \brief Number of colomns 190 * 191 * \return colomns 192 */ 193 uint32_t Cols(void) const; 194 195 Type const &GetDataType() const {return dataType;}; 196 197 private: 198 /*! 199 * \brief Copy datas 200 * 201 * Reimplemented from io_data. \n 202 * See io_data::CopyDatas. 203 * 204 * \param dst destination buffer 205 */ 206 void CopyDatas(char* dst) const; 207 208 class cvmatrix_impl* pimpl_; 209 Type dataType; 210 }; 23 namespace flair { 24 namespace core { 25 26 /*! \class cvmatrix 27 * 28 * \brief Class defining a matrix of kind CvMat 29 * 30 * CvMat is a matrix struct defined in OpenCV. 31 * 32 */ 33 class cvmatrix : public io_data { 34 public: 35 class Type : public DataType { 36 public: 37 Type(size_t _nbRows, size_t _nbCols, ScalarType const &_elementDataType) 38 : nbRows(_nbRows), nbCols(_nbCols), elementDataType(_elementDataType) {} 39 size_t GetSize() const { 40 return nbRows * nbCols * elementDataType.GetSize(); 41 } 42 std::string GetDescription() const { return "matrix"; } 43 size_t GetNbRows() const { return nbRows; } 44 size_t GetNbCols() const { return nbCols; } 45 ScalarType const &GetElementDataType() const { return elementDataType; } 46 47 private: 48 size_t nbRows, nbCols; 49 ScalarType const &elementDataType; 50 }; 51 52 /*! 53 * \brief Constructor 54 * 55 * Construct an io_data representing a CvMat. \n 56 * It uses a cvmatrix_descriptor to get size and elements' names. \n 57 * Names are used for graphs and logs. 58 * 59 * \param parent parent 60 * \param descriptor matrix description 61 * \param type type of matrix elements 62 * \param name name 63 * \param n number of samples 64 */ 65 cvmatrix(const Object *parent, const cvmatrix_descriptor *descriptor, 66 ScalarType const &elementDataType, std::string name = "", 67 uint32_t n = 1); 68 69 /*! 70 * \brief Constructor 71 * 72 * Construct an io_data representing a CvMat. \n 73 * Elements are unamed. 74 * 75 * \param parent parent 76 * \param rows matrix rows 77 * \param cols matrix cols 78 * \param type type of matrix elements 79 * \param name name 80 * \param n number of samples 81 */ 82 cvmatrix(const Object *parent, uint32_t rows, uint32_t cols, 83 ScalarType const &elementDataType, std::string name = "", 84 uint32_t n = 1); 85 86 /*! 87 * \brief Destructor 88 * 89 */ 90 ~cvmatrix(); 91 92 /*! 93 * \brief Element value 94 * 95 * Element is accessed by locking and unlocking the io_data Mutex. 96 * 97 * \param row element row 98 * \param col element col 99 * 100 * \return element value 101 */ 102 float Value(uint32_t row, uint32_t col) const; 103 104 /*! 105 * \brief Element value 106 * 107 * Element is not accessed by locking and unlocking the io_data Mutex. \n 108 * Thus, this function should be called with Mutex locked. \n 109 * This function is usefull when multiple successive access are done to the 110 * elments of the matrix. It avoids unnecessary locking and unlocking. 111 * 112 * \param row element row 113 * \param col element col 114 * 115 * \return element value 116 */ 117 float ValueNoMutex(uint32_t row, uint32_t col) const; 118 119 /*! 120 * \brief Set element value 121 * 122 * Element is accessed by locking and unlocking the io_data Mutex. 123 * 124 * \param row element row 125 * \param col element col 126 * \param value element value 127 */ 128 void SetValue(uint32_t row, uint32_t col, float value); 129 130 /*! 131 * \brief Set element value 132 * 133 * Element is not accessed by locking and unlocking the io_data Mutex. \n 134 * Thus, this function should be called with Mutex locked. \n 135 * This function is usefull when multiple successive access are done to the 136 * elments of the matrix. It avoids unnecessary locking and unlocking. 137 * 138 * \param row element row 139 * \param col element col 140 * \param value element value 141 */ 142 void SetValueNoMutex(uint32_t row, uint32_t col, float value); 143 144 /*! 145 * \brief get CvMat 146 * 147 * The io_data Mutex must be used by the user. 148 */ 149 CvMat *getCvMat(void) const; 150 151 /*! 152 * \brief Element name 153 * 154 * If cvmatrix was created without cvmatrix_descriptor, element name is empty. 155 * 156 * \param row element row 157 * \param col element col 158 * 159 * \return element name 160 */ 161 std::string Name(uint32_t row, uint32_t col) const; 162 163 /*! 164 * \brief Element 165 * 166 * Get a pointer to a specific element. This pointer can be used for plotting. 167 * 168 * \param row element row 169 * \param col element col 170 * 171 * \return pointer to the element 172 */ 173 IODataElement *Element(uint32_t row, uint32_t col) const; 174 175 /*! 176 * \brief Element 177 * 178 * Get a pointer to a specific element. This pointer can be used for plotting. 179 *\n 180 * This function can be used for a 1D matrix. 181 * 182 * \param index element index 183 * 184 * \return pointer to the element 185 */ 186 IODataElement *Element(uint32_t index) const; 187 188 /*! 189 * \brief Number of rows 190 * 191 * \return rows 192 */ 193 uint32_t Rows(void) const; 194 195 /*! 196 * \brief Number of colomns 197 * 198 * \return colomns 199 */ 200 uint32_t Cols(void) const; 201 202 Type const &GetDataType() const { return dataType; }; 203 204 private: 205 /*! 206 * \brief Copy datas 207 * 208 * Reimplemented from io_data. \n 209 * See io_data::CopyDatas. 210 * 211 * \param dst destination buffer 212 */ 213 void CopyDatas(char *dst) const; 214 215 class cvmatrix_impl *pimpl_; 216 Type dataType; 217 }; 211 218 212 219 } // end namespace core -
trunk/lib/FlairCore/src/cvmatrix_descriptor.cpp
r2 r15 20 20 using std::string; 21 21 22 namespace flair { namespace core { 22 namespace flair { 23 namespace core { 23 24 24 25 cvmatrix_descriptor::cvmatrix_descriptor(uint32_t rows, uint32_t cols) { 25 this->rows=rows;26 this->cols=cols;26 this->rows = rows; 27 this->cols = cols; 27 28 28 if(rows==0 || cols==0) getFrameworkManager()->Err("rows and cols must be >0\n"); 29 if (rows == 0 || cols == 0) 30 getFrameworkManager()->Err("rows and cols must be >0\n"); 29 31 30 element_names=(string**)malloc(rows*cols*sizeof(string*));31 for(uint32_t i=0; i<rows*cols; i++) {32 element_names[i]=new string();33 32 element_names = (string **)malloc(rows * cols * sizeof(string *)); 33 for (uint32_t i = 0; i < rows * cols; i++) { 34 element_names[i] = new string(); 35 } 34 36 } 35 37 36 38 cvmatrix_descriptor::~cvmatrix_descriptor() { 37 for(uint32_t i=0; i<rows*cols; i++) {38 39 40 39 for (uint32_t i = 0; i < rows * cols; i++) { 40 delete element_names[i]; 41 } 42 free(element_names); 41 43 } 42 44 43 void cvmatrix_descriptor::SetElementName(uint32_t row, uint32_t col,string name) { 44 if(row>=rows || col>=cols) { 45 getFrameworkManager()->Err("index out of bound %s (%i,%i), range (%i,%i)\n",name.c_str(),row,col,rows-1,cols-1); 46 return; 47 } 48 *element_names[row*cols+col]=name; 45 void cvmatrix_descriptor::SetElementName(uint32_t row, uint32_t col, 46 string name) { 47 if (row >= rows || col >= cols) { 48 getFrameworkManager()->Err("index out of bound %s (%i,%i), range (%i,%i)\n", 49 name.c_str(), row, col, rows - 1, cols - 1); 50 return; 51 } 52 *element_names[row * cols + col] = name; 49 53 } 50 54 51 55 string cvmatrix_descriptor::ElementName(uint32_t row, uint32_t col) const { 52 if(row>=rows || col>=cols) { 53 getFrameworkManager()->Err("index out of bound (%i,%i), range (%i,%i)\n",row,col,rows-1,cols-1); 54 return *element_names[0];//safe value... 55 } 56 return *element_names[row*cols+col]; 56 if (row >= rows || col >= cols) { 57 getFrameworkManager()->Err("index out of bound (%i,%i), range (%i,%i)\n", 58 row, col, rows - 1, cols - 1); 59 return *element_names[0]; // safe value... 60 } 61 return *element_names[row * cols + col]; 57 62 } 58 63 59 uint32_t cvmatrix_descriptor::Rows() const { 60 return rows; 61 } 64 uint32_t cvmatrix_descriptor::Rows() const { return rows; } 62 65 63 uint32_t cvmatrix_descriptor::Cols() const { 64 return cols; 65 } 66 uint32_t cvmatrix_descriptor::Cols() const { return cols; } 66 67 67 68 } // end namespace core -
trunk/lib/FlairCore/src/cvmatrix_descriptor.h
r2 r15 16 16 #include <string> 17 17 18 namespace flair { namespace core19 {18 namespace flair { 19 namespace core { 20 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 21 /*! \class cvmatrix_descriptor 22 * 23 * \brief Class describing cvmatrix elements, for log and graphs purpose 24 * 25 * This class allows to give a name to matrix elements. These names 26 * will be used in graphs and logs. 27 */ 28 class cvmatrix_descriptor { 29 public: 30 /*! 31 * \brief Constructor 32 * 33 * Construct a matrix descriptor. 34 * 35 * \param rows matrix rows 36 * \param cols matrix cols 37 */ 38 cvmatrix_descriptor(uint32_t rows, uint32_t cols); 39 39 40 41 42 43 44 40 /*! 41 * \brief Destructor 42 * 43 */ 44 ~cvmatrix_descriptor(); 45 45 46 47 48 49 50 51 52 53 void SetElementName(uint32_t row, uint32_t col,std::string name);46 /*! 47 * \brief Set element name 48 * 49 * \param row element row 50 * \param col element col 51 * \param name element name 52 */ 53 void SetElementName(uint32_t row, uint32_t col, std::string name); 54 54 55 56 57 58 59 60 61 62 63 55 /*! 56 * \brief Element name 57 * 58 * \param row element row 59 * \param col element col 60 * 61 * \return element name 62 */ 63 std::string ElementName(uint32_t row, uint32_t col) const; 64 64 65 66 67 68 69 70 65 /*! 66 * \brief Number of rows 67 * 68 * \return rows 69 */ 70 uint32_t Rows(void) const; 71 71 72 73 74 75 76 77 72 /*! 73 * \brief Number of colomns 74 * 75 * \return colomns 76 */ 77 uint32_t Cols(void) const; 78 78 79 private: 80 uint32_t rows,cols; 81 std::string **element_names; 82 83 }; 79 private: 80 uint32_t rows, cols; 81 std::string **element_names; 82 }; 84 83 85 84 } // end namespace core -
trunk/lib/FlairCore/src/cvmatrix_impl.cpp
r2 r15 24 24 using namespace flair::core; 25 25 26 cvmatrix_impl::cvmatrix_impl(cvmatrix* self,int rows, int cols,flair::core::ScalarType const &_elementDataType,int n):elementDataType(_elementDataType) { 27 descriptor=new cvmatrix_descriptor(rows,cols); 28 Init(self,n); 26 cvmatrix_impl::cvmatrix_impl(cvmatrix *self, int rows, int cols, 27 flair::core::ScalarType const &_elementDataType, 28 int n) 29 : elementDataType(_elementDataType) { 30 descriptor = new cvmatrix_descriptor(rows, cols); 31 Init(self, n); 29 32 } 30 33 31 cvmatrix_impl::cvmatrix_impl(cvmatrix* self,const cvmatrix_descriptor *descriptor,flair::core::ScalarType const &_elementDataType,int n):elementDataType(_elementDataType) { 32 this->descriptor=descriptor; 33 Init(self,n); 34 cvmatrix_impl::cvmatrix_impl(cvmatrix *self, 35 const cvmatrix_descriptor *descriptor, 36 flair::core::ScalarType const &_elementDataType, 37 int n) 38 : elementDataType(_elementDataType) { 39 this->descriptor = descriptor; 40 Init(self, n); 34 41 } 35 42 36 void cvmatrix_impl::Init(cvmatrix * self,int n) {37 this->self=self;43 void cvmatrix_impl::Init(cvmatrix *self, int n) { 44 this->self = self; 38 45 39 mat=nullptr; 40 try { 41 ScalarType const &scalarType=dynamic_cast<ScalarType const &>(elementDataType); 42 if (typeid(scalarType)==typeid(FloatType)) { 43 mat=cvCreateMat(descriptor->Rows(),descriptor->Cols(),CV_32FC1); 44 } else if (typeid(scalarType)==typeid(SignedIntegerType)) { 45 switch(elementDataType.GetSize()) { 46 case 1: 47 mat=cvCreateMat(descriptor->Rows(),descriptor->Cols(),CV_8SC1); 48 break; 49 case 2: 50 mat=cvCreateMat(descriptor->Rows(),descriptor->Cols(),CV_16SC1); 51 break; 52 default: 53 self->Err("unsupported integer scalar type\n"); 54 } 55 } else { 56 self->Err("unsupported scalar type\n"); 57 } 58 } catch(std::bad_cast e) { 59 self->Err("type is not a scalar\n"); 46 mat = nullptr; 47 try { 48 ScalarType const &scalarType = 49 dynamic_cast<ScalarType const &>(elementDataType); 50 if (typeid(scalarType) == typeid(FloatType)) { 51 mat = cvCreateMat(descriptor->Rows(), descriptor->Cols(), CV_32FC1); 52 } else if (typeid(scalarType) == typeid(SignedIntegerType)) { 53 switch (elementDataType.GetSize()) { 54 case 1: 55 mat = cvCreateMat(descriptor->Rows(), descriptor->Cols(), CV_8SC1); 56 break; 57 case 2: 58 mat = cvCreateMat(descriptor->Rows(), descriptor->Cols(), CV_16SC1); 59 break; 60 default: 61 self->Err("unsupported integer scalar type\n"); 62 } 63 } else { 64 self->Err("unsupported scalar type\n"); 60 65 } 66 } catch (std::bad_cast e) { 67 self->Err("type is not a scalar\n"); 68 } 61 69 62 if(mat==nullptr) self->Err("allocating matrix failed\n"); 63 if(n>1) self->Warn("n>1 not supported\n"); 70 if (mat == nullptr) 71 self->Err("allocating matrix failed\n"); 72 if (n > 1) 73 self->Warn("n>1 not supported\n"); 64 74 } 65 75 66 76 cvmatrix_impl::~cvmatrix_impl() { 67 68 77 cvReleaseMat(&mat); 78 delete descriptor; 69 79 } -
trunk/lib/FlairCore/src/io_data.cpp
r2 r15 21 21 using std::string; 22 22 23 namespace flair { namespace core { 23 namespace flair { 24 namespace core { 24 25 25 26 DummyType dummyType; … … 28 29 SignedIntegerType Int16Type(16); 29 30 30 io_data::io_data(const Object* parent,string name,int n): Mutex(parent,name) { 31 pimpl_=new io_data_impl(this,n); 31 io_data::io_data(const Object *parent, string name, int n) 32 : Mutex(parent, name) { 33 pimpl_ = new io_data_impl(this, n); 32 34 } 33 35 34 io_data::~io_data() { 35 delete pimpl_; 36 } 36 io_data::~io_data() { delete pimpl_; } 37 37 38 void io_data::AppendLogDescription(string description,DataType const &datatype) { 39 pimpl_->AppendLogDescription(description,datatype); 38 void io_data::AppendLogDescription(string description, 39 DataType const &datatype) { 40 pimpl_->AppendLogDescription(description, datatype); 40 41 } 41 42 42 43 void io_data::SetDataTime(Time time) { 43 44 pimpl_->time=time;45 44 GetMutex(); 45 pimpl_->time = time; 46 ReleaseMutex(); 46 47 } 47 48 48 49 Time io_data::DataTime(void) const { 49 50 51 tmp=pimpl_->time;52 53 50 Time tmp; 51 GetMutex(); 52 tmp = pimpl_->time; 53 ReleaseMutex(); 54 return tmp; 54 55 } 55 56 56 const io_data *io_data::Prev(int n) const {57 if(n>0)58 return prev->Prev(n-1);59 60 57 const io_data *io_data::Prev(int n) const { 58 if (n > 0) 59 return prev->Prev(n - 1); 60 else 61 return this; 61 62 } 62 63 63 void io_data::SetPtrToCircle(void **ptr) { 64 pimpl_->circle_ptr=ptr; 65 } 64 void io_data::SetPtrToCircle(void **ptr) { pimpl_->circle_ptr = ptr; } 66 65 67 66 } // end namespace core -
trunk/lib/FlairCore/src/io_data.h
r2 r15 19 19 class io_data_impl; 20 20 21 namespace flair { namespace core { 21 namespace flair { 22 namespace core { 22 23 23 24 class Object; 24 25 25 26 27 virtual std::string GetDescription() const =0;28 //size in bytes29 virtual size_t GetSize() const =0;30 26 class DataType { 27 public: 28 virtual std::string GetDescription() const = 0; 29 // size in bytes 30 virtual size_t GetSize() const = 0; 31 }; 31 32 32 class DummyType: public DataType {33 34 size_t GetSize() const {return 0;}35 std::string GetDescription() const {return "dummy";};36 37 33 class DummyType : public DataType { 34 public: 35 size_t GetSize() const { return 0; } 36 std::string GetDescription() const { return "dummy"; }; 37 }; 38 extern DummyType dummyType; 38 39 39 class ScalarType: public DataType { 40 public: 41 ScalarType(size_t _size):size(_size) {} 42 size_t GetSize() const {return size;} 43 virtual std::string GetDescription() const {return "scalar";}; 44 private: 45 size_t size; 46 }; 40 class ScalarType : public DataType { 41 public: 42 ScalarType(size_t _size) : size(_size) {} 43 size_t GetSize() const { return size; } 44 virtual std::string GetDescription() const { return "scalar"; }; 47 45 48 class SignedIntegerType: public ScalarType { 49 public: 50 SignedIntegerType(size_t sizeInBits):ScalarType(sizeInBits/8){} 51 std::string GetDescription() const {return "int"+std::to_string(GetSize()*8)+"_t";}; 52 }; 53 extern SignedIntegerType Int8Type; 54 extern SignedIntegerType Int16Type; 46 private: 47 size_t size; 48 }; 55 49 56 class FloatType: public ScalarType { 57 public: 58 FloatType():ScalarType(4){} 59 std::string GetDescription() const {return "float";}; 60 }; 61 extern FloatType floatType; 50 class SignedIntegerType : public ScalarType { 51 public: 52 SignedIntegerType(size_t sizeInBits) : ScalarType(sizeInBits / 8) {} 53 std::string GetDescription() const { 54 return "int" + std::to_string(GetSize() * 8) + "_t"; 55 }; 56 }; 57 extern SignedIntegerType Int8Type; 58 extern SignedIntegerType Int16Type; 62 59 60 class FloatType : public ScalarType { 61 public: 62 FloatType() : ScalarType(4) {} 63 std::string GetDescription() const { return "float"; }; 64 }; 65 extern FloatType floatType; 63 66 64 /*! \class io_data 65 * 66 * \brief Abstract class for data types. 67 * 68 * Use this class to define a custom data type. Data types ares used for logging and graphs. \n 69 * The reimplemented class must call SetSize() in its constructor. \n 70 * io_data can be constructed with n samples (see io_data::io_data). 71 * In this case, old samples can be accessed throug io_data::Prev. 72 */ 73 class io_data: public Mutex { 74 friend class IODevice; 75 friend class ::IODevice_impl; 76 friend class ::io_data_impl; 67 /*! \class io_data 68 * 69 * \brief Abstract class for data types. 70 * 71 * Use this class to define a custom data type. Data types ares used for logging 72 *and graphs. \n 73 * The reimplemented class must call SetSize() in its constructor. \n 74 * io_data can be constructed with n samples (see io_data::io_data). 75 * In this case, old samples can be accessed throug io_data::Prev. 76 */ 77 class io_data : public Mutex { 78 friend class IODevice; 79 friend class ::IODevice_impl; 80 friend class ::io_data_impl; 77 81 78 79 80 81 82 83 84 85 86 87 88 io_data(const Object* parent,std::string name,int n);82 public: 83 /*! 84 * \brief Constructor 85 * 86 * Construct an io_data. \n 87 * 88 * \param parent parent 89 * \param name name 90 * \param n number of samples 91 */ 92 io_data(const Object *parent, std::string name, int n); 89 93 90 91 92 93 94 94 /*! 95 * \brief Destructor 96 * 97 */ 98 virtual ~io_data(); 95 99 96 97 98 99 100 101 100 /*! 101 * \brief Set data time 102 * 103 * \param time time 104 */ 105 void SetDataTime(Time time); 102 106 103 104 105 106 107 108 107 /*! 108 * \brief Data time 109 * 110 * \return data time 111 */ 112 Time DataTime(void) const; 109 113 110 111 112 113 114 115 116 117 118 119 120 121 const io_data*Prev(int n) const;114 /*! 115 * \brief Previous data 116 * 117 * Access previous data. io_data must have been constructed with 118 * n>1, io_data::SetPtrToCircle must have been set and 119 * io_data::prev must have been allocated. 120 * 121 * \param n previous data number 122 * 123 * \return previous data 124 */ 125 const io_data *Prev(int n) const; 122 126 123 virtual DataType const&GetDataType() const =0;127 virtual DataType const &GetDataType() const = 0; 124 128 125 protected: 126 /*! 127 * \brief Specify the description of the reimplemented class data's 128 * 129 * This method must be called in the constructor of the reimplemented class, once by element. \n 130 * Each element description must be called in the same order as CopyDatas put the datas in the buffer. \n 131 * The description will be used for the log descriptor file. 132 * 133 * \param description description of the element 134 * \param datatype type of the element 135 */ 136 void AppendLogDescription(std::string description, DataType const &datatype); 129 protected: 130 /*! 131 * \brief Specify the description of the reimplemented class data's 132 * 133 * This method must be called in the constructor of the reimplemented class, 134 *once by element. \n 135 * Each element description must be called in the same order as CopyDatas put 136 *the datas in the buffer. \n 137 * The description will be used for the log descriptor file. 138 * 139 * \param description description of the element 140 * \param datatype type of the element 141 */ 142 void AppendLogDescription(std::string description, DataType const &datatype); 137 143 138 139 140 141 142 143 144 /*! 145 * \brief Set the datas to circle 146 * 147 * \param ptr pointer to the data to circle 148 */ 149 void SetPtrToCircle(void **ptr); 144 150 145 146 147 148 149 150 151 io_data*prev;151 /*! 152 * \brief Pointer to previous data 153 * 154 * Reimplemented class must allocate this pointer if n>1. \n 155 * Pointer must be allocated with the same kind of reimplemented class. 156 */ 157 io_data *prev; 152 158 153 private: 154 /*! 155 * \brief Copy datas 156 * 157 * This method is automatically called by IODevice::ProcessUpdate to log io_data datas. \n 158 * This method must be reimplemented, in order to copy the datas to the logs. 159 * Copied datas must be of size io_data::Size. 160 * 161 * \param dst destination buffer 162 */ 163 virtual void CopyDatas(char* dst) const =0; 159 private: 160 /*! 161 * \brief Copy datas 162 * 163 * This method is automatically called by IODevice::ProcessUpdate to log 164 *io_data datas. \n 165 * This method must be reimplemented, in order to copy the datas to the logs. 166 * Copied datas must be of size io_data::Size. 167 * 168 * \param dst destination buffer 169 */ 170 virtual void CopyDatas(char *dst) const = 0; 164 171 165 166 172 io_data_impl *pimpl_; 173 }; 167 174 168 175 } // end namespace core -
trunk/lib/FlairCore/src/io_data_impl.cpp
r2 r15 23 23 using namespace flair::core; 24 24 25 io_data_impl::io_data_impl(io_data* self,int n) { 26 this->self=self; 27 this->n=n; 28 if(n<1) self->Err("n doit être >0\n"); 29 size=0; 30 is_consistent=false; 31 circle_ptr=NULL; 25 io_data_impl::io_data_impl(io_data *self, int n) { 26 this->self = self; 27 this->n = n; 28 if (n < 1) 29 self->Err("n doit être >0\n"); 30 size = 0; 31 is_consistent = false; 32 circle_ptr = NULL; 32 33 } 33 34 34 35 io_data_impl::~io_data_impl() {} 35 36 36 void io_data_impl::AppendLogDescription(string description,DataType const &datatype) { 37 description+=" ("+datatype.GetDescription()+")"; 38 descriptors.push_back(description); 37 void io_data_impl::AppendLogDescription(string description, 38 DataType const &datatype) { 39 description += " (" + datatype.GetDescription() + ")"; 40 descriptors.push_back(description); 39 41 } 40 42 41 void io_data_impl::WriteLogDescriptor(std::fstream& desc_file,int *index) { 42 for(size_t i=0;i<descriptors.size();i++) { 43 desc_file << (*index)++ << ": " << self->ObjectName() << " - " << descriptors.at(i) << "\n"; 44 } 43 void io_data_impl::WriteLogDescriptor(std::fstream &desc_file, int *index) { 44 for (size_t i = 0; i < descriptors.size(); i++) { 45 desc_file << (*index)++ << ": " << self->ObjectName() << " - " 46 << descriptors.at(i) << "\n"; 47 } 45 48 } 46 49 47 50 void io_data_impl::PrintLogDescriptor(void) { 48 for(size_t i=0;i<descriptors.size();i++) {49 Printf(" %s\n",descriptors.at(i).c_str());50 51 for (size_t i = 0; i < descriptors.size(); i++) { 52 Printf(" %s\n", descriptors.at(i).c_str()); 53 } 51 54 } 52 55 53 56 void io_data_impl::Circle(void) { 54 if(n>1) {55 57 if (n > 1) { 58 self->GetMutex(); 56 59 57 void* tmp=*self->Prev(n-1)->pimpl_->circle_ptr;60 void *tmp = *self->Prev(n - 1)->pimpl_->circle_ptr; 58 61 59 for(int i=0;i<n-1;i++) { 60 //printf("%i\n",i); 61 *(self->Prev(n-1-i)->pimpl_->circle_ptr)=*(self->Prev(n-2-i)->pimpl_->circle_ptr); 62 self->Prev(n-1-i)->pimpl_->is_consistent=self->Prev(n-2-i)->pimpl_->is_consistent; 63 self->Prev(n-1-i)->pimpl_->time=self->Prev(n-2-i)->pimpl_->time; 64 } 65 *circle_ptr=tmp; 66 is_consistent=false; 67 self->ReleaseMutex(); 68 62 for (int i = 0; i < n - 1; i++) { 63 // printf("%i\n",i); 64 *(self->Prev(n - 1 - i)->pimpl_->circle_ptr) = 65 *(self->Prev(n - 2 - i)->pimpl_->circle_ptr); 66 self->Prev(n - 1 - i)->pimpl_->is_consistent = 67 self->Prev(n - 2 - i)->pimpl_->is_consistent; 68 self->Prev(n - 1 - i)->pimpl_->time = self->Prev(n - 2 - i)->pimpl_->time; 69 69 } 70 *circle_ptr = tmp; 71 is_consistent = false; 72 self->ReleaseMutex(); 73 } 70 74 } 71 75 72 bool io_data_impl::IsConsistent(void) { 73 return is_consistent; 74 } 76 bool io_data_impl::IsConsistent(void) { return is_consistent; } 75 77 76 void io_data_impl::SetConsistent(bool status) { 77 is_consistent=status; 78 } 78 void io_data_impl::SetConsistent(bool status) { is_consistent = status; } -
trunk/lib/FlairCore/src/ui_com.cpp
r2 r15 39 39 using namespace flair::gui; 40 40 41 ui_com::ui_com(const Object *parent, UDTSOCKET sock): Thread(parent,"send",2)42 {43 //buffer envoi44 send_buffer=(char*)malloc(3);45 send_size=3;//id(1)+period(2)46 47 //mutex48 send_mutex=NULL;49 send_mutex=new Mutex(this,ObjectName());50 51 socket_fd=sock;52 connection_lost=false;41 ui_com::ui_com(const Object *parent, UDTSOCKET sock) 42 : Thread(parent, "send", 2) { 43 // buffer envoi 44 send_buffer = (char *)malloc(3); 45 send_size = 3; // id(1)+period(2) 46 47 // mutex 48 send_mutex = NULL; 49 send_mutex = new Mutex(this, ObjectName()); 50 51 socket_fd = sock; 52 connection_lost = false; 53 53 54 54 #ifdef __XENO__ 55 int status; 56 string tmp_name; 57 58 is_running=true; 59 60 //pipe 61 tmp_name= getFrameworkManager()->ObjectName() + "-" + ObjectName()+ "-pipe"; 62 //xenomai limitation 63 if(tmp_name.size()>31) Err("rt_pipe_create error (%s is too long)\n",tmp_name.c_str()); 55 int status; 56 string tmp_name; 57 58 is_running = true; 59 60 // pipe 61 tmp_name = getFrameworkManager()->ObjectName() + "-" + ObjectName() + "-pipe"; 62 // xenomai limitation 63 if (tmp_name.size() > 31) 64 Err("rt_pipe_create error (%s is too long)\n", tmp_name.c_str()); 64 65 #ifdef RT_PIPE_SIZE 65 status=rt_pipe_create(&pipe, tmp_name.c_str(), P_MINOR_AUTO,RT_PIPE_SIZE);66 status = rt_pipe_create(&pipe, tmp_name.c_str(), P_MINOR_AUTO, RT_PIPE_SIZE); 66 67 #else 67 status=rt_pipe_create(&pipe, tmp_name.c_str(), P_MINOR_AUTO,0); 68 #endif 69 70 if(status!=0) 71 { 72 Err("rt_pipe_create error (%s)\n",strerror(-status)); 73 //return -1; 74 } 75 76 //start user side thread 68 status = rt_pipe_create(&pipe, tmp_name.c_str(), P_MINOR_AUTO, 0); 69 #endif 70 71 if (status != 0) { 72 Err("rt_pipe_create error (%s)\n", strerror(-status)); 73 // return -1; 74 } 75 76 // start user side thread 77 77 #ifdef NRT_STACK_SIZE 78 // Initialize thread creation attributes 79 pthread_attr_t attr; 80 if(pthread_attr_init(&attr) != 0) 81 { 82 Err("pthread_attr_init error\n"); 83 } 84 85 if(pthread_attr_setstacksize(&attr, NRT_STACK_SIZE) != 0) 86 { 87 Err("pthread_attr_setstacksize error\n"); 88 } 89 90 if(pthread_create(&thread, &attr, user_thread, (void*)this) < 0) 91 #else //NRT_STACK_SIZE 92 if(pthread_create(&thread, NULL, user_thread, (void*)this) < 0) 93 #endif //NRT_STACK_SIZE 94 { 95 Err("pthread_create error\n"); 96 //return -1; 97 } 78 // Initialize thread creation attributes 79 pthread_attr_t attr; 80 if (pthread_attr_init(&attr) != 0) { 81 Err("pthread_attr_init error\n"); 82 } 83 84 if (pthread_attr_setstacksize(&attr, NRT_STACK_SIZE) != 0) { 85 Err("pthread_attr_setstacksize error\n"); 86 } 87 88 if (pthread_create(&thread, &attr, user_thread, (void *)this) < 0) 89 #else // NRT_STACK_SIZE 90 if (pthread_create(&thread, NULL, user_thread, (void *)this) < 0) 91 #endif // NRT_STACK_SIZE 92 { 93 Err("pthread_create error\n"); 94 // return -1; 95 } 98 96 #ifdef NRT_STACK_SIZE 99 if(pthread_attr_destroy(&attr) != 0)100 {101 Err("pthread_attr_destroy error\n");102 } 103 #endif 104 105 #endif//__XENO__ 106 int timeout=100;107 if(UDT::setsockopt(socket_fd, 0, UDT_RCVTIMEO, &timeout, sizeof(int))!=0)Err("UDT::setsockopt error (UDT_RCVTIMEO)\n");108 109 110 if(UDT::setsockopt(socket_fd, 0, UDT_SNDSYN, &blocking, sizeof(bool))!=0) Err("UDT::setsockopt error (UDT_SNDSYN)\n");111 112 if(UDT::setsockopt(socket_fd, 0, UDT_RCVSYN, &blocking, sizeof(bool))!=0) Err("UDT::setsockopt error (UDT_RCVSYN)\n"); 113 //#endif //__XENO__ 114 115 Start();116 } 117 118 119 ui_com::~ui_com() 120 {121 //printf("destruction ui_com\n");97 if (pthread_attr_destroy(&attr) != 0) { 98 Err("pthread_attr_destroy error\n"); 99 } 100 #endif 101 102 #endif //__XENO__ 103 int timeout = 100; 104 if (UDT::setsockopt(socket_fd, 0, UDT_RCVTIMEO, &timeout, sizeof(int)) != 0) 105 Err("UDT::setsockopt error (UDT_RCVTIMEO)\n"); 106 107 bool blocking = true; 108 if (UDT::setsockopt(socket_fd, 0, UDT_SNDSYN, &blocking, sizeof(bool)) != 0) 109 Err("UDT::setsockopt error (UDT_SNDSYN)\n"); 110 111 if (UDT::setsockopt(socket_fd, 0, UDT_RCVSYN, &blocking, sizeof(bool)) != 0) 112 Err("UDT::setsockopt error (UDT_RCVSYN)\n"); 113 //#endif //__XENO__ 114 115 Start(); 116 } 117 118 ui_com::~ui_com() { 119 // printf("destruction ui_com\n"); 122 120 123 121 #ifdef __XENO__ 124 is_running=false; 125 126 pthread_join(thread, NULL); 127 128 int status=rt_pipe_delete(&pipe); 129 if(status!=0) Err("rt_pipe_delete error (%s)\n",strerror(-status)); 130 #endif 131 132 SafeStop(); 133 134 if(IsSuspended()==true) Resume(); 135 136 Join(); 137 138 if(send_buffer!=NULL) free(send_buffer); 139 send_buffer=NULL; 140 141 //printf("destruction ui_com ok\n"); 142 } 143 144 void ui_com::Send(char* buf,ssize_t size) { 145 if(connection_lost==true) return; 146 147 char* tosend=buf; 148 ssize_t nb_write; 149 150 if(buf[0]==XML_HEADER) { 151 //cut xml header 152 tosend=strstr(buf,"<root"); 153 size-=tosend-buf; 154 } 122 is_running = false; 123 124 pthread_join(thread, NULL); 125 126 int status = rt_pipe_delete(&pipe); 127 if (status != 0) 128 Err("rt_pipe_delete error (%s)\n", strerror(-status)); 129 #endif 130 131 SafeStop(); 132 133 if (IsSuspended() == true) 134 Resume(); 135 136 Join(); 137 138 if (send_buffer != NULL) 139 free(send_buffer); 140 send_buffer = NULL; 141 142 // printf("destruction ui_com ok\n"); 143 } 144 145 void ui_com::Send(char *buf, ssize_t size) { 146 if (connection_lost == true) 147 return; 148 149 char *tosend = buf; 150 ssize_t nb_write; 151 152 if (buf[0] == XML_HEADER) { 153 // cut xml header 154 tosend = strstr(buf, "<root"); 155 size -= tosend - buf; 156 } 155 157 156 158 #ifdef __XENO__ 157 nb_write=rt_pipe_write(&pipe,tosend,size,P_NORMAL); 158 159 if(nb_write<0) 160 { 161 Err("rt_pipe_write error (%s)\n",strerror(-nb_write)); 162 } 163 else if (nb_write != size) 164 { 165 Err("rt_pipe_write error %i/%i\n",nb_write,size); 166 } 159 nb_write = rt_pipe_write(&pipe, tosend, size, P_NORMAL); 160 161 if (nb_write < 0) { 162 Err("rt_pipe_write error (%s)\n", strerror(-nb_write)); 163 } else if (nb_write != size) { 164 Err("rt_pipe_write error %i/%i\n", nb_write, size); 165 } 167 166 #else //__XENO__ 168 167 169 168 #ifdef COMPRESS_FRAMES 170 bool sendItCompressed=false; 171 if(buf[0]==XML_HEADER) { 172 sendItCompressed=true; 173 } 174 175 if(sendItCompressed) { 176 char *out; 177 ssize_t out_size; 178 if(compressBuffer(tosend, size,&out,&out_size, 9)==Z_OK) { 179 size=out_size; 180 nb_write = UDT::sendmsg(socket_fd,out,size, -1, true); 181 free(out); 169 bool sendItCompressed = false; 170 if (buf[0] == XML_HEADER) { 171 sendItCompressed = true; 172 } 173 174 if (sendItCompressed) { 175 char *out; 176 ssize_t out_size; 177 if (compressBuffer(tosend, size, &out, &out_size, 9) == Z_OK) { 178 size = out_size; 179 nb_write = UDT::sendmsg(socket_fd, out, size, -1, true); 180 free(out); 181 } else { 182 Warn("Compress error, sending it uncompressed\n"); 183 sendItCompressed = false; 184 } 185 } 186 187 if (!sendItCompressed) { 188 nb_write = UDT::sendmsg(socket_fd, tosend, size, -1, true); 189 } 190 191 #else // COMPRESS_FRAMES 192 nb_write = UDT::sendmsg(socket_fd, tosend, size, -1, true); 193 #endif // COMPRESS_FRAMES 194 // Printf("write %i %i\n",nb_write,size); 195 if (nb_write < 0) { 196 Err("UDT::sendmsg error (%s)\n", UDT::getlasterror().getErrorMessage()); 197 if (UDT::getlasterror().getErrorCode() == CUDTException::ECONNLOST || 198 UDT::getlasterror().getErrorCode() == CUDTException::EINVSOCK) { 199 connection_lost = true; 200 } 201 } else if (nb_write != size) { 202 Err("%s, code %i (%ld/%ld)\n", UDT::getlasterror().getErrorMessage(), 203 UDT::getlasterror().getErrorCode(), nb_write, size); 204 } 205 #endif //__XENO__ 206 } 207 208 ssize_t ui_com::Receive(char *buf, ssize_t buf_size) { 209 ssize_t bytesRead = UDT::recvmsg(socket_fd, buf, buf_size); 210 211 if (bytesRead < 0) { 212 if (UDT::getlasterror().getErrorCode() == CUDTException::ECONNLOST) { 213 Err("UDT::recvmsg error (%s)\n", UDT::getlasterror().getErrorMessage()); 214 connection_lost = true; 215 } 216 } 217 218 return bytesRead; 219 } 220 221 void ui_com::Run(void) { 222 // check endianness 223 char header; 224 if (IsBigEndian()) { 225 header = DATAS_BIG_ENDIAN; 226 Printf("System is big endian\n"); 227 } else { 228 header = DATAS_LITTLE_ENDIAN; 229 Printf("System is little endian\n"); 230 } 231 232 #ifdef __XENO__ 233 WarnUponSwitches(true); 234 printf("\n"); // a revoir pourquoi?? 235 // sans ce printf, dans le simu_roll, le suspend ne fonctionne pas... 236 #endif 237 // on attend d'avoir des choses à faire 238 Suspend(); 239 240 while (!ToBeStopped()) { 241 size_t resume_id; 242 Time min = 0xffffffffffffffffULL; 243 244 // on recpuere l'id de la prochaine execution 245 send_mutex->GetMutex(); 246 resume_id = resume_time.size(); 247 for (size_t i = 0; i < resume_time.size(); i++) { 248 if (resume_time.at(i) < min && data_to_send.at(i)->IsEnabled() == true) { 249 min = resume_time.at(i); 250 resume_id = i; 251 } 252 } 253 254 // attente 255 if (resume_id < resume_time.size()) { 256 Time time = resume_time.at(resume_id); 257 uint16_t resume_period = data_to_send.at(resume_id)->SendPeriod(); 258 send_mutex->ReleaseMutex(); 259 // on dort jusqu'a la prochaine execution 260 SleepUntil(time); 261 262 // envoi des donnees 263 int offset = 3; 264 send_buffer[0] = header; 265 send_mutex->GetMutex(); 266 267 for (size_t i = 0; i < data_to_send.size(); i++) { 268 if (data_to_send.at(i)->SendPeriod() == resume_period && 269 data_to_send.at(i)->IsEnabled() == true) { 270 data_to_send.at(i)->CopyDatas(send_buffer + offset); 271 offset += data_to_send.at(i)->SendSize(); 272 } 273 } 274 if (offset != 3) { 275 memcpy(&send_buffer[1], &resume_period, sizeof(uint16_t)); 276 // printf("send %i %i %i %x 277 // %x\n",resume_period,offset,sizeof(uint16_t),send_buffer,&send_buffer[1]); 278 // for(int i=0;i<offset;i++) printf("%x ",send_buffer[i]); 279 // printf("\n"); 280 Send(send_buffer, offset); 281 } 282 283 // on planifie la prochaine execution 284 for (size_t i = 0; i < data_to_send.size(); i++) { 285 if (data_to_send.at(i)->SendPeriod() == resume_period) { 286 resume_time.at(i) += data_to_send.at(i)->SendPeriod() * 1000000; 287 } 288 } 289 send_mutex->ReleaseMutex(); 290 // Printf("%i %lld\n",resume_period,GetTime()/1000000); 291 } else { 292 send_mutex->ReleaseMutex(); 293 // rien a faire, suspend 294 // Printf("rien a faire suspend\n"); 295 Suspend(); 296 // Printf("wake\n"); 297 // on planifie la prochaine execution 298 Time time = GetTime(); 299 send_mutex->GetMutex(); 300 for (size_t i = 0; i < data_to_send.size(); i++) { 301 resume_time.at(i) = 302 time + (Time)data_to_send.at(i)->SendPeriod() * 1000000; 303 } 304 send_mutex->ReleaseMutex(); 305 } 306 } 307 } 308 #ifdef __XENO__ 309 void *ui_com::user_thread(void *arg) { 310 int pipe_fd = -1; 311 string devname; 312 char *buf = NULL; 313 ui_com *caller = (ui_com *)arg; 314 int rv; 315 fd_set set; 316 struct timeval timeout; 317 ssize_t nb_read, nb_write; 318 319 buf = (char *)malloc(NRT_PIPE_SIZE); 320 if (buf == NULL) { 321 caller->Err("malloc error\n"); 322 } 323 324 devname = NRT_PIPE_PATH + getFrameworkManager()->ObjectName() + "-" + 325 caller->ObjectName() + "-pipe"; 326 while (pipe_fd < 0) { 327 pipe_fd = open(devname.c_str(), O_RDWR); 328 if (pipe_fd < 0 && errno != ENOENT) 329 caller->Err("open pipe_fd error (%s)\n", strerror(-errno)); 330 usleep(1000); 331 } 332 333 while (1) { 334 FD_ZERO(&set); // clear the set 335 FD_SET(pipe_fd, &set); // add our file descriptor to the set 336 337 timeout.tv_sec = 0; 338 timeout.tv_usec = SELECT_TIMEOUT_MS * 1000; 339 340 rv = select(FD_SETSIZE, &set, NULL, NULL, &timeout); 341 342 if (rv == -1) { 343 if (caller->is_running == false && 344 UDT::getlasterror().getErrorCode() == CUDTException::ETIMEOUT) 345 break; // timeout 346 if (UDT::getlasterror().getErrorCode() != CUDTException::ETIMEOUT) 347 caller->Err("epoll_wait, %s, code %i\n", 348 UDT::getlasterror().getErrorMessage(), 349 UDT::getlasterror().getErrorCode()); 350 } else if (rv == 0) { 351 // printf("timeout\n"); // a timeout occured 352 if (caller->is_running == false) 353 break; 354 355 } else { 356 nb_read = read(pipe_fd, buf, NRT_PIPE_SIZE); 357 buf[nb_read] = 0; 358 // printf("envoi\n%s\n",buf); 359 360 #ifdef COMPRESS_FRAMES 361 char *out; 362 ssize_t out_size; 363 364 if (buf[0] == XML_HEADER) { 365 if (compressBuffer(buf, nb_read, &out, &out_size, 9) == Z_OK) { 366 nb_read = out_size; 367 nb_write = UDT::sendmsg(caller->socket_fd, out, out_size, -1, true); 368 free(out); 182 369 } else { 183 184 sendItCompressed=false;370 caller->Warn("Compress error, sending it uncompressed\n"); 371 nb_write = UDT::sendmsg(caller->socket_fd, buf, nb_read, -1, true); 185 372 } 186 } 187 188 if(!sendItCompressed) { 189 nb_write = UDT::sendmsg(socket_fd,tosend,size, -1, true); 190 } 191 192 #else //COMPRESS_FRAMES 193 nb_write = UDT::sendmsg(socket_fd,tosend,size, -1, true); 194 #endif //COMPRESS_FRAMES 195 //Printf("write %i %i\n",nb_write,size); 196 if(nb_write<0) { 197 Err("UDT::sendmsg error (%s)\n",UDT::getlasterror().getErrorMessage()); 198 if(UDT::getlasterror().getErrorCode()==CUDTException::ECONNLOST || UDT::getlasterror().getErrorCode()==CUDTException::EINVSOCK) { 199 connection_lost=true; 373 } else { 374 nb_write = UDT::sendmsg(caller->socket_fd, buf, nb_read, -1, true); 375 } 376 #else 377 nb_write = UDT::sendmsg(caller->socket_fd, buf, nb_read, -1, true); 378 #endif 379 380 if (nb_write < 0) { 381 caller->Err("UDT::sendmsg error (%s)\n", 382 UDT::getlasterror().getErrorMessage()); 383 if (UDT::getlasterror().getErrorCode() == CUDTException::ECONNLOST || 384 UDT::getlasterror().getErrorCode() == CUDTException::EINVSOCK) { 385 caller->connection_lost = true; 200 386 } 201 } else if (nb_write != size) { 202 Err("%s, code %i (%ld/%ld)\n",UDT::getlasterror().getErrorMessage(),UDT::getlasterror().getErrorCode(),nb_write,size); 203 } 204 #endif //__XENO__ 205 } 206 207 ssize_t ui_com::Receive(char* buf,ssize_t buf_size) { 208 ssize_t bytesRead= UDT::recvmsg(socket_fd,buf,buf_size); 209 210 if(bytesRead<0) { 211 if(UDT::getlasterror().getErrorCode()==CUDTException::ECONNLOST) { 212 Err("UDT::recvmsg error (%s)\n",UDT::getlasterror().getErrorMessage()); 213 connection_lost=true; 214 } 215 } 216 217 return bytesRead; 218 } 219 220 void ui_com::Run(void) 221 { 222 //check endianness 223 char header; 224 if(IsBigEndian()) 225 { 226 header=DATAS_BIG_ENDIAN; 227 Printf("System is big endian\n"); 228 } 229 else 230 { 231 header=DATAS_LITTLE_ENDIAN; 232 Printf("System is little endian\n"); 233 } 234 235 #ifdef __XENO__ 236 WarnUponSwitches(true); 237 printf("\n");//a revoir pourquoi?? 238 //sans ce printf, dans le simu_roll, le suspend ne fonctionne pas... 239 #endif 240 //on attend d'avoir des choses à faire 241 Suspend(); 242 243 while(!ToBeStopped()) 244 { 245 size_t resume_id; 246 Time min=0xffffffffffffffffULL; 247 248 //on recpuere l'id de la prochaine execution 249 send_mutex->GetMutex(); 250 resume_id=resume_time.size(); 251 for(size_t i=0;i<resume_time.size();i++) 252 { 253 if(resume_time.at(i)<min && data_to_send.at(i)->IsEnabled()==true) 254 { 255 min=resume_time.at(i); 256 resume_id=i; 257 } 258 } 259 260 //attente 261 if(resume_id<resume_time.size()) 262 { 263 Time time=resume_time.at(resume_id); 264 uint16_t resume_period=data_to_send.at(resume_id)->SendPeriod(); 265 send_mutex->ReleaseMutex(); 266 //on dort jusqu'a la prochaine execution 267 SleepUntil(time); 268 269 //envoi des donnees 270 int offset=3; 271 send_buffer[0]=header; 272 send_mutex->GetMutex(); 273 274 for(size_t i=0;i<data_to_send.size();i++) { 275 if(data_to_send.at(i)->SendPeriod()==resume_period && data_to_send.at(i)->IsEnabled()==true) { 276 data_to_send.at(i)->CopyDatas(send_buffer+offset); 277 offset+=data_to_send.at(i)->SendSize(); 278 } 279 } 280 if(offset!=3) { 281 memcpy(&send_buffer[1],&resume_period,sizeof(uint16_t)); 282 //printf("send %i %i %i %x %x\n",resume_period,offset,sizeof(uint16_t),send_buffer,&send_buffer[1]); 283 //for(int i=0;i<offset;i++) printf("%x ",send_buffer[i]); 284 //printf("\n"); 285 Send(send_buffer,offset); 286 } 287 288 //on planifie la prochaine execution 289 for(size_t i=0;i<data_to_send.size();i++) 290 { 291 if(data_to_send.at(i)->SendPeriod()==resume_period) 292 { 293 resume_time.at(i)+=data_to_send.at(i)->SendPeriod()*1000000; 294 } 295 } 296 send_mutex->ReleaseMutex(); 297 //Printf("%i %lld\n",resume_period,GetTime()/1000000); 298 } 299 else 300 { 301 send_mutex->ReleaseMutex(); 302 //rien a faire, suspend 303 //Printf("rien a faire suspend\n"); 304 Suspend(); 305 //Printf("wake\n"); 306 //on planifie la prochaine execution 307 Time time=GetTime(); 308 send_mutex->GetMutex(); 309 for(size_t i=0;i<data_to_send.size();i++) 310 { 311 resume_time.at(i)=time+(Time)data_to_send.at(i)->SendPeriod()*1000000; 312 } 313 send_mutex->ReleaseMutex(); 314 } 315 } 316 } 317 #ifdef __XENO__ 318 void* ui_com::user_thread(void * arg) 319 { 320 int pipe_fd=-1; 321 string devname; 322 char* buf=NULL; 323 ui_com *caller = (ui_com*)arg; 324 int rv; 325 fd_set set; 326 struct timeval timeout; 327 ssize_t nb_read,nb_write; 328 329 buf=(char*)malloc(NRT_PIPE_SIZE); 330 if(buf==NULL) 331 { 332 caller->Err("malloc error\n"); 333 } 334 335 devname= NRT_PIPE_PATH + getFrameworkManager()->ObjectName() + "-" + caller->ObjectName()+ "-pipe"; 336 while(pipe_fd<0) 337 { 338 pipe_fd = open(devname.c_str(), O_RDWR); 339 if (pipe_fd < 0 && errno!=ENOENT) caller->Err("open pipe_fd error (%s)\n",strerror(-errno)); 340 usleep(1000); 341 } 342 343 while(1) 344 { 345 FD_ZERO(&set); // clear the set 346 FD_SET(pipe_fd, &set); // add our file descriptor to the set 347 348 timeout.tv_sec = 0; 349 timeout.tv_usec = SELECT_TIMEOUT_MS*1000; 350 351 rv = select(FD_SETSIZE, &set, NULL, NULL, &timeout); 352 353 if(rv == -1) 354 { 355 if(caller->is_running==false && UDT::getlasterror().getErrorCode()==CUDTException::ETIMEOUT) break;//timeout 356 if(UDT::getlasterror().getErrorCode()!=CUDTException::ETIMEOUT) caller->Err("epoll_wait, %s, code %i\n",UDT::getlasterror().getErrorMessage(),UDT::getlasterror().getErrorCode()); 357 } 358 else if(rv == 0) 359 { 360 //printf("timeout\n"); // a timeout occured 361 if(caller->is_running==false) break; 362 363 } 364 else 365 { 366 nb_read=read(pipe_fd,buf,NRT_PIPE_SIZE); 367 buf[nb_read]=0; 368 //printf("envoi\n%s\n",buf); 369 370 #ifdef COMPRESS_FRAMES 371 char *out; 372 ssize_t out_size; 373 374 if(buf[0]==XML_HEADER) { 375 if(compressBuffer(buf, nb_read,&out,&out_size, 9)==Z_OK) { 376 nb_read=out_size; 377 nb_write = UDT::sendmsg(caller->socket_fd,out,out_size, -1, true); 378 free(out); 379 } else { 380 caller->Warn("Compress error, sending it uncompressed\n"); 381 nb_write = UDT::sendmsg(caller->socket_fd, buf,nb_read, -1, true); 382 } 383 } else { 384 nb_write = UDT::sendmsg(caller->socket_fd, buf,nb_read, -1, true); 385 } 386 #else 387 nb_write = UDT::sendmsg(caller->socket_fd, buf,nb_read, -1, true); 388 #endif 389 390 if(nb_write<0) 391 { 392 caller->Err("UDT::sendmsg error (%s)\n",UDT::getlasterror().getErrorMessage()); 393 if(UDT::getlasterror().getErrorCode()==CUDTException::ECONNLOST || UDT::getlasterror().getErrorCode()==CUDTException::EINVSOCK) 394 { 395 caller->connection_lost=true; 396 } 397 } 398 else if (nb_write != nb_read) 399 { 400 caller->Err("UDT::sendmsg error %i/%i\n",nb_write,nb_read); 401 } 402 } 403 } 404 405 close(pipe_fd); 406 if(buf!=NULL) free(buf); 407 pthread_exit(0); 408 } 409 #endif 410 411 int ui_com::compressBuffer(char *in, ssize_t in_size,char **out,ssize_t *out_size, int level) 412 { 413 int ret, flush; 414 unsigned have; 415 z_stream strm; 416 417 /* allocate deflate state */ 418 strm.zalloc = Z_NULL; 419 strm.zfree = Z_NULL; 420 strm.opaque = Z_NULL; 421 ret = deflateInit(&strm, level); 422 if (ret != Z_OK) 423 return ret; 424 425 *out=(char*)malloc(COMPRESS_CHUNK); 426 if(!(*out)) 427 return Z_BUF_ERROR; 428 429 strm.next_in = (unsigned char*)in; 430 strm.avail_out = COMPRESS_CHUNK; 431 strm.next_out = (unsigned char*)*out; 432 strm.avail_in=in_size; 433 flush=Z_FINISH; 434 435 ret = deflate(&strm, flush); /* no bad return value */ 436 if (ret == Z_STREAM_ERROR) { 437 free(*out); 438 return ret; 439 } 440 441 have = COMPRESS_CHUNK - strm.avail_out; 442 *out_size=have; 443 //printf("%i -> %i\n",in_size,have); 444 /* clean up and return */ 445 (void)deflateEnd(&strm); 446 447 if(strm.avail_out!=0) { 448 return Z_OK; 449 } else { 450 return Z_STREAM_ERROR; 451 } 452 } 453 454 int ui_com::uncompressBuffer(unsigned char *in, ssize_t in_size,unsigned char **out,ssize_t *out_size) 455 { 456 int ret; 457 //unsigned have; 458 z_stream strm; 459 460 /* allocate inflate state */ 461 strm.zalloc = Z_NULL; 462 strm.zfree = Z_NULL; 463 strm.opaque = Z_NULL; 464 strm.avail_in = 0; 465 strm.next_in = Z_NULL; 466 ret = inflateInit(&strm); 467 if (ret != Z_OK) 468 return ret; 469 470 *out=(unsigned char*)malloc(COMPRESS_CHUNK); 471 if(!(*out)) 472 return Z_BUF_ERROR; 473 474 strm.avail_in = in_size; 475 strm.next_in = in; 476 strm.avail_out = COMPRESS_CHUNK; 477 strm.next_out = *out; 478 479 ret = inflate(&strm, Z_NO_FLUSH); 480 assert(ret != Z_STREAM_ERROR); /* state not clobbered */ 481 switch (ret) { 482 case Z_NEED_DICT: 483 ret = Z_DATA_ERROR; /* and fall through */ 484 case Z_DATA_ERROR: 485 case Z_MEM_ERROR: 486 (void)inflateEnd(&strm); 487 return ret; 488 } 489 //have = COMPRESS_CHUNK - strm.avail_out; 490 491 /* clean up and return */ 387 } else if (nb_write != nb_read) { 388 caller->Err("UDT::sendmsg error %i/%i\n", nb_write, nb_read); 389 } 390 } 391 } 392 393 close(pipe_fd); 394 if (buf != NULL) 395 free(buf); 396 pthread_exit(0); 397 } 398 #endif 399 400 int ui_com::compressBuffer(char *in, ssize_t in_size, char **out, 401 ssize_t *out_size, int level) { 402 int ret, flush; 403 unsigned have; 404 z_stream strm; 405 406 /* allocate deflate state */ 407 strm.zalloc = Z_NULL; 408 strm.zfree = Z_NULL; 409 strm.opaque = Z_NULL; 410 ret = deflateInit(&strm, level); 411 if (ret != Z_OK) 412 return ret; 413 414 *out = (char *)malloc(COMPRESS_CHUNK); 415 if (!(*out)) 416 return Z_BUF_ERROR; 417 418 strm.next_in = (unsigned char *)in; 419 strm.avail_out = COMPRESS_CHUNK; 420 strm.next_out = (unsigned char *)*out; 421 strm.avail_in = in_size; 422 flush = Z_FINISH; 423 424 ret = deflate(&strm, flush); /* no bad return value */ 425 if (ret == Z_STREAM_ERROR) { 426 free(*out); 427 return ret; 428 } 429 430 have = COMPRESS_CHUNK - strm.avail_out; 431 *out_size = have; 432 // printf("%i -> %i\n",in_size,have); 433 /* clean up and return */ 434 (void)deflateEnd(&strm); 435 436 if (strm.avail_out != 0) { 437 return Z_OK; 438 } else { 439 return Z_STREAM_ERROR; 440 } 441 } 442 443 int ui_com::uncompressBuffer(unsigned char *in, ssize_t in_size, 444 unsigned char **out, ssize_t *out_size) { 445 int ret; 446 // unsigned have; 447 z_stream strm; 448 449 /* allocate inflate state */ 450 strm.zalloc = Z_NULL; 451 strm.zfree = Z_NULL; 452 strm.opaque = Z_NULL; 453 strm.avail_in = 0; 454 strm.next_in = Z_NULL; 455 ret = inflateInit(&strm); 456 if (ret != Z_OK) 457 return ret; 458 459 *out = (unsigned char *)malloc(COMPRESS_CHUNK); 460 if (!(*out)) 461 return Z_BUF_ERROR; 462 463 strm.avail_in = in_size; 464 strm.next_in = in; 465 strm.avail_out = COMPRESS_CHUNK; 466 strm.next_out = *out; 467 468 ret = inflate(&strm, Z_NO_FLUSH); 469 assert(ret != Z_STREAM_ERROR); /* state not clobbered */ 470 switch (ret) { 471 case Z_NEED_DICT: 472 ret = Z_DATA_ERROR; /* and fall through */ 473 case Z_DATA_ERROR: 474 case Z_MEM_ERROR: 492 475 (void)inflateEnd(&strm); 493 return ret == Z_STREAM_END ? Z_OK : Z_DATA_ERROR; 494 } 495 496 bool ui_com::ConnectionLost() 497 { 498 return connection_lost; 499 } 500 501 void ui_com::AddSendData(const SendData *obj) 502 { 503 send_mutex->GetMutex(); 504 505 resume_time.push_back(GetTime()+(Time)obj->SendPeriod()*1000000); 506 507 //on resume en meme temps tout ceux qui ont la meme periode 508 for(size_t i=0;i<data_to_send.size();i++) 509 { 510 if(data_to_send.at(i)->SendPeriod()==obj->SendPeriod()) 511 { 512 resume_time.at(resume_time.size()-1)=resume_time.at(i); 513 break; 514 } 515 } 516 517 data_to_send.push_back(obj); 518 519 send_mutex->ReleaseMutex(); 520 } 521 522 void ui_com::UpdateSendData(const SendData *obj) 523 { 524 //le mutex est deja pris par l'appellant 525 size_t id,i; 526 527 //on recupere l'id 528 for(i=0;i<data_to_send.size();i++) 529 { 530 if(data_to_send.at(i)==obj) 531 { 532 id=i; 533 break; 534 } 535 } 536 537 //on resume en meme temps tout ceux qui ont la meme periode 538 for(i=0;i<data_to_send.size();i++) 539 { 540 if(i==id) continue; 541 if(data_to_send.at(i)->IsEnabled()==true && data_to_send.at(i)->SendPeriod()==obj->SendPeriod()) 542 { 543 resume_time.at(id)=resume_time.at(i); 544 break; 545 } 546 } 547 548 //si aucun match, on planifie l'execution 549 if(i==data_to_send.size()) resume_time.at(id)=GetTime()+(Time)obj->SendPeriod()*1000000; 550 551 if(IsSuspended()==true) Resume(); 552 553 return; 554 } 555 556 void ui_com::UpdateDataToSendSize(void) 557 { 558 send_mutex->GetMutex(); 559 send_size=3;//id(1)+period(2) 560 for(size_t i=0;i<data_to_send.size();i++) 561 { 562 if(data_to_send[i]!=NULL) send_size+=data_to_send[i]->SendSize(); 563 } 564 565 //send_buffer=(char*)realloc((void*)send_buffer,send_size*sizeof(char)); 566 if(send_buffer!=NULL) free(send_buffer); 567 send_buffer=(char*)malloc(send_size*sizeof(char)); 568 send_mutex->ReleaseMutex(); 569 } 570 571 void ui_com::RemoveSendData(const SendData *obj) 572 { 573 //printf("remove_data_to_send %i\n",data_to_send.size()); 574 575 send_mutex->GetMutex(); 576 //on recupere l'id 577 for(size_t i=0;i<data_to_send.size();i++) 578 { 579 if(data_to_send.at(i)==obj) 580 { 581 data_to_send.erase (data_to_send.begin()+i); 582 resume_time.erase (resume_time.begin()+i); 583 //printf("remove_data_to_send %i ok\n",data_to_send.size()); 584 break; 585 } 586 } 587 send_mutex->ReleaseMutex(); 588 589 return; 590 } 591 592 void ui_com::Block(void) 593 { 594 send_mutex->GetMutex(); 595 } 596 597 void ui_com::UnBlock(void) 598 { 599 send_mutex->ReleaseMutex(); 600 } 476 return ret; 477 } 478 // have = COMPRESS_CHUNK - strm.avail_out; 479 480 /* clean up and return */ 481 (void)inflateEnd(&strm); 482 return ret == Z_STREAM_END ? Z_OK : Z_DATA_ERROR; 483 } 484 485 bool ui_com::ConnectionLost() { return connection_lost; } 486 487 void ui_com::AddSendData(const SendData *obj) { 488 send_mutex->GetMutex(); 489 490 resume_time.push_back(GetTime() + (Time)obj->SendPeriod() * 1000000); 491 492 // on resume en meme temps tout ceux qui ont la meme periode 493 for (size_t i = 0; i < data_to_send.size(); i++) { 494 if (data_to_send.at(i)->SendPeriod() == obj->SendPeriod()) { 495 resume_time.at(resume_time.size() - 1) = resume_time.at(i); 496 break; 497 } 498 } 499 500 data_to_send.push_back(obj); 501 502 send_mutex->ReleaseMutex(); 503 } 504 505 void ui_com::UpdateSendData(const SendData *obj) { 506 // le mutex est deja pris par l'appellant 507 size_t id, i; 508 509 // on recupere l'id 510 for (i = 0; i < data_to_send.size(); i++) { 511 if (data_to_send.at(i) == obj) { 512 id = i; 513 break; 514 } 515 } 516 517 // on resume en meme temps tout ceux qui ont la meme periode 518 for (i = 0; i < data_to_send.size(); i++) { 519 if (i == id) 520 continue; 521 if (data_to_send.at(i)->IsEnabled() == true && 522 data_to_send.at(i)->SendPeriod() == obj->SendPeriod()) { 523 resume_time.at(id) = resume_time.at(i); 524 break; 525 } 526 } 527 528 // si aucun match, on planifie l'execution 529 if (i == data_to_send.size()) 530 resume_time.at(id) = GetTime() + (Time)obj->SendPeriod() * 1000000; 531 532 if (IsSuspended() == true) 533 Resume(); 534 535 return; 536 } 537 538 void ui_com::UpdateDataToSendSize(void) { 539 send_mutex->GetMutex(); 540 send_size = 3; // id(1)+period(2) 541 for (size_t i = 0; i < data_to_send.size(); i++) { 542 if (data_to_send[i] != NULL) 543 send_size += data_to_send[i]->SendSize(); 544 } 545 546 // send_buffer=(char*)realloc((void*)send_buffer,send_size*sizeof(char)); 547 if (send_buffer != NULL) 548 free(send_buffer); 549 send_buffer = (char *)malloc(send_size * sizeof(char)); 550 send_mutex->ReleaseMutex(); 551 } 552 553 void ui_com::RemoveSendData(const SendData *obj) { 554 // printf("remove_data_to_send %i\n",data_to_send.size()); 555 556 send_mutex->GetMutex(); 557 // on recupere l'id 558 for (size_t i = 0; i < data_to_send.size(); i++) { 559 if (data_to_send.at(i) == obj) { 560 data_to_send.erase(data_to_send.begin() + i); 561 resume_time.erase(resume_time.begin() + i); 562 // printf("remove_data_to_send %i ok\n",data_to_send.size()); 563 break; 564 } 565 } 566 send_mutex->ReleaseMutex(); 567 568 return; 569 } 570 571 void ui_com::Block(void) { send_mutex->GetMutex(); } 572 573 void ui_com::UnBlock(void) { send_mutex->ReleaseMutex(); } -
trunk/lib/FlairCore/src/unexported/ConditionVariable_impl.h
r2 r15 23 23 24 24 namespace flair { 25 26 27 25 namespace core { 26 class ConditionVariable; 27 } 28 28 } 29 29 … … 32 32 * 33 33 */ 34 class ConditionVariable_impl 35 { 34 class ConditionVariable_impl { 36 35 37 38 ConditionVariable_impl(flair::core::ConditionVariable*self);39 40 41 42 36 public: 37 ConditionVariable_impl(flair::core::ConditionVariable *self); 38 ~ConditionVariable_impl(); 39 void CondWait(void); 40 bool CondWaitUntil(flair::core::Time date); 41 void CondSignal(void); 43 42 44 45 flair::core::ConditionVariable*self;43 private: 44 flair::core::ConditionVariable *self; 46 45 #ifdef __XENO__ 47 46 RT_COND m_ResumeCond; 48 47 #else 49 48 pthread_cond_t m_ResumeCond; 50 49 #endif 51 50 }; -
trunk/lib/FlairCore/src/unexported/DataPlot_impl.h
r2 r15 16 16 #include <vector> 17 17 18 namespace flair 19 { 20 namespace core 21 { 22 class IODataElement; 23 } 18 namespace flair { 19 namespace core { 20 class IODataElement; 21 } 24 22 } 25 23 … … 28 26 * 29 27 */ 30 class DataPlot_impl 31 { 32 public: 33 DataPlot_impl(); 34 ~DataPlot_impl(); 28 class DataPlot_impl { 29 public: 30 DataPlot_impl(); 31 ~DataPlot_impl(); 35 32 36 std::vector<const flair::core::IODataElement*> tosend;33 std::vector<const flair::core::IODataElement *> tosend; 37 34 }; 38 35 -
trunk/lib/FlairCore/src/unexported/FrameworkManager_impl.h
r2 r15 24 24 #endif 25 25 26 namespace flair 27 { 28 namespace core 29 { 30 class FrameworkManager; 31 class IODevice; 32 class Watchdog; 33 } 34 namespace gui 35 { 36 class TabWidget; 37 class PushButton; 38 class Layout; 39 } 26 namespace flair { 27 namespace core { 28 class FrameworkManager; 29 class IODevice; 30 class Watchdog; 31 } 32 namespace gui { 33 class TabWidget; 34 class PushButton; 35 class Layout; 36 } 40 37 } 41 38 42 39 class ui_com; 43 40 44 class FrameworkManager_impl : public flair::core::Thread45 { 46 public:47 FrameworkManager_impl(flair::core::FrameworkManager *self,std::string name);48 ~FrameworkManager_impl();49 void SetupConnection(std::string address,uint16_t port,size_t rcv_buf_size=10000);50 51 52 53 54 55 char*GetBuffer(size_t sz);56 void ReleaseBuffer(char*buf);57 void WriteLog(const char* buf,size_t size);41 class FrameworkManager_impl : public flair::core::Thread { 42 public: 43 FrameworkManager_impl(flair::core::FrameworkManager *self, std::string name); 44 ~FrameworkManager_impl(); 45 void SetupConnection(std::string address, uint16_t port, 46 size_t rcv_buf_size = 10000); 47 void SetupUserInterface(std::string xml_file); 48 void SetupLogger(std::string log_path); 49 void AddDeviceToLog(flair::core::IODevice *device); 50 void StartLog(); 51 void StopLog(); 52 char *GetBuffer(size_t sz); 53 void ReleaseBuffer(char *buf); 54 void WriteLog(const char *buf, size_t size); 58 55 59 60 61 62 63 64 56 /*! 57 * \brief Affiche le xml 58 * 59 * Pour debug. 60 */ 61 void PrintXml(void) const; 65 62 66 67 68 69 70 71 63 bool is_logging; 64 bool disable_errors; 65 bool connection_lost; 66 static ui_com *com; 67 static FrameworkManager_impl *_this; 68 std::string log_path; 72 69 73 flair::gui::TabWidget*tabwidget;74 flair::gui::PushButton *save_button;//,*load_button;70 flair::gui::TabWidget *tabwidget; 71 flair::gui::PushButton *save_button; //,*load_button; 75 72 76 73 xmlDocPtr file_doc; 77 74 78 79 const flair::core::IODevice*device;80 81 82 75 typedef struct { 76 const flair::core::IODevice *device; 77 size_t size; 78 flair::core::Time time; 79 } log_header_t; 83 80 84 85 86 UDTSOCKET file_sock,com_sock;87 UDTSOCKET GetSocket(std::string address,uint16_t port);88 89 void SendFile(std::string path,std::string name);90 91 std::string FileName(flair::core::IODevice*device);92 void SaveXmlChange(char*buf);93 94 95 81 private: 82 flair::core::FrameworkManager *self; 83 UDTSOCKET file_sock, com_sock; 84 UDTSOCKET GetSocket(std::string address, uint16_t port); 85 void Run(); 86 void SendFile(std::string path, std::string name); 87 void FinishSending(void); 88 std::string FileName(flair::core::IODevice *device); 89 void SaveXmlChange(char *buf); 90 void SaveXml(void); 91 size_t rcv_buf_size; 92 char *rcv_buf; 96 93 #ifdef __XENO__ 97 int CreatePipe(RT_PIPE* fd,std::string name);98 int DeletePipe(RT_PIPE*fd);99 100 101 94 int CreatePipe(RT_PIPE *fd, std::string name); 95 int DeletePipe(RT_PIPE *fd); 96 RT_PIPE cmd_pipe; 97 RT_PIPE data_pipe; 98 RT_HEAP log_heap; 102 99 #else 103 int CreatePipe(int (*fd)[2],std::string name);104 105 106 100 int CreatePipe(int (*fd)[2], std::string name); 101 int DeletePipe(int (*fd)[2]); 102 int cmd_pipe[2]; 103 int data_pipe[2]; 107 104 #endif 108 //logger109 bool continuer;//a enlever, avoir un seul bool pour toutes les taches110 static void* write_log_user(void *arg);111 112 113 114 115 flair::gui::Layout*top_layout;105 // logger 106 bool continuer; // a enlever, avoir un seul bool pour toutes les taches 107 static void *write_log_user(void *arg); 108 pthread_t log_th; 109 std::string xml_file; 110 bool logger_defined; 111 bool ui_defined; 112 flair::gui::Layout *top_layout; 116 113 117 118 flair::core::IODevice*device;119 120 121 122 114 typedef struct { 115 flair::core::IODevice *device; 116 size_t size; 117 hdfile_t *dbtFile; 118 bool running; 119 } log_desc_t; 123 120 124 125 126 flair::core::Watchdog*gcs_watchdog;127 121 std::vector<log_desc_t> logs; 122 std::vector<std::string> xml_changes; 123 flair::core::Watchdog *gcs_watchdog; 124 void ConnectionLost(void); 128 125 }; 129 126 130 namespace 131 { 132 inline ui_com* getUiCom(void) { 133 return FrameworkManager_impl::com; 134 } 127 namespace { 128 inline ui_com *getUiCom(void) { return FrameworkManager_impl::com; } 135 129 136 inline FrameworkManager_impl*getFrameworkManagerImpl(void) {137 138 130 inline FrameworkManager_impl *getFrameworkManagerImpl(void) { 131 return FrameworkManager_impl::_this; 132 } 139 133 } 140 134 -
trunk/lib/FlairCore/src/unexported/IODevice_impl.h
r2 r15 17 17 #include <Object.h> 18 18 19 namespace flair 20 { 21 namespace core 22 { 23 class io_data; 24 class IODevice; 25 class Thread; 26 class Mutex; 27 class FrameworkManager; 28 class SharedMem; 29 } 19 namespace flair { 20 namespace core { 21 class io_data; 22 class IODevice; 23 class Thread; 24 class Mutex; 25 class FrameworkManager; 26 class SharedMem; 27 } 30 28 } 31 29 32 30 class FrameworkManager_impl; 33 31 34 class IODevice_impl 35 { 36 public: 37 IODevice_impl(const flair::core::IODevice* self); 38 ~IODevice_impl(); 39 void ResumeThread(void); 40 size_t LogSize(void) const; 41 void AppendLog(char** ptr); 42 void AddDataToLog(const flair::core::io_data* data); 43 void WriteLogsDescriptors(std::fstream& desc_file,int *index); 44 int SetToWake(const flair::core::Thread* thread); 45 void WriteLog(flair::core::Time time); 46 void AddDeviceToLog(const flair::core::IODevice* device); 47 bool SetToBeLogged(void);//return true if possible 48 void OutputToShMem(bool enabled); 49 void WriteToShMem(void); 50 void PrintLogsDescriptors(void); 32 class IODevice_impl { 33 public: 34 IODevice_impl(const flair::core::IODevice *self); 35 ~IODevice_impl(); 36 void ResumeThread(void); 37 size_t LogSize(void) const; 38 void AppendLog(char **ptr); 39 void AddDataToLog(const flair::core::io_data *data); 40 void WriteLogsDescriptors(std::fstream &desc_file, int *index); 41 int SetToWake(const flair::core::Thread *thread); 42 void WriteLog(flair::core::Time time); 43 void AddDeviceToLog(const flair::core::IODevice *device); 44 bool SetToBeLogged(void); // return true if possible 45 void OutputToShMem(bool enabled); 46 void WriteToShMem(void); 47 void PrintLogsDescriptors(void); 51 48 52 53 std::vector<const flair::core::IODevice*> devicesToLog;54 const flair::core::IODevice*self;55 const flair::core::FrameworkManager*framework;56 FrameworkManager_impl*framework_impl;57 std::vector<const flair::core::io_data*> datasToLog;58 flair::core::Thread*thread_to_wake;59 flair::core::Mutex*wake_mutex;60 61 62 49 private: 50 std::vector<const flair::core::IODevice *> devicesToLog; 51 const flair::core::IODevice *self; 52 const flair::core::FrameworkManager *framework; 53 FrameworkManager_impl *framework_impl; 54 std::vector<const flair::core::io_data *> datasToLog; 55 flair::core::Thread *thread_to_wake; 56 flair::core::Mutex *wake_mutex; 57 bool tobelogged; 58 bool outputtoshm; 59 flair::core::SharedMem *shmem; 63 60 }; 64 61 -
trunk/lib/FlairCore/src/unexported/Mutex_impl.h
r2 r15 20 20 #endif 21 21 22 namespace flair 23 { 24 namespace core 25 { 26 class Mutex; 27 } 22 namespace flair { 23 namespace core { 24 class Mutex; 25 } 28 26 } 29 27 30 class Mutex_impl 31 { 32 public: 33 Mutex_impl(flair::core::Mutex *self); 34 ~Mutex_impl(); 35 void GetMutex(void); 36 void ReleaseMutex(void); 28 class Mutex_impl { 29 public: 30 Mutex_impl(flair::core::Mutex *self); 31 ~Mutex_impl(); 32 void GetMutex(void); 33 void ReleaseMutex(void); 37 34 // bool IsLocked(void); 38 35 #ifdef __XENO__ 39 36 RT_MUTEX mutex; 40 37 #else 41 42 //bool flag_locked;38 pthread_mutex_t mutex; 39 // bool flag_locked; 43 40 #endif 44 41 45 private: 46 flair::core::Mutex *self; 47 42 private: 43 flair::core::Mutex *self; 48 44 }; 49 45 -
trunk/lib/FlairCore/src/unexported/Object_impl.h
r2 r15 19 19 #define OBJECT_IMPL_H 20 20 21 class Object_impl 22 { 23 public: 24 Object_impl(const flair::core::Object* self,const flair::core::Object* parent=NULL,std::string name="",std::string type=""); 25 ~Object_impl(); 26 std::string name,type; 27 std::vector<const flair::core::Object*> childs; 28 std::vector<const flair::core::Object*> type_childs; 29 void AddChild(const flair::core::Object* child); 30 void RemoveChild(const flair::core::Object* child); 31 bool ErrorOccured(bool recursive); 32 bool error_occured; 33 const flair::core::Object* parent; 21 class Object_impl { 22 public: 23 Object_impl(const flair::core::Object *self, 24 const flair::core::Object *parent = NULL, std::string name = "", 25 std::string type = ""); 26 ~Object_impl(); 27 std::string name, type; 28 std::vector<const flair::core::Object *> childs; 29 std::vector<const flair::core::Object *> type_childs; 30 void AddChild(const flair::core::Object *child); 31 void RemoveChild(const flair::core::Object *child); 32 bool ErrorOccured(bool recursive); 33 bool error_occured; 34 const flair::core::Object *parent; 34 35 35 36 const flair::core::Object*self;36 private: 37 const flair::core::Object *self; 37 38 }; 38 39 -
trunk/lib/FlairCore/src/unexported/OneAxisRotation_impl.h
r2 r15 14 14 #define ONEAXISROTATION_IMPL_H 15 15 16 namespace flair 17 { 18 namespace core 19 { 20 class Vector3D; 21 class Euler; 22 class Quaternion; 23 class RotationMatrix; 24 } 25 namespace gui 26 { 27 class GroupBox; 28 class ComboBox; 29 class DoubleSpinBox; 30 } 16 namespace flair { 17 namespace core { 18 class Vector3D; 19 class Euler; 20 class Quaternion; 21 class RotationMatrix; 22 } 23 namespace gui { 24 class GroupBox; 25 class ComboBox; 26 class DoubleSpinBox; 27 } 31 28 } 32 29 … … 35 32 * 36 33 */ 37 class OneAxisRotation_impl 38 { 39 public: 40 OneAxisRotation_impl(flair::gui::GroupBox* box); 41 ~OneAxisRotation_impl(); 42 void ComputeRotation(flair::core::Vector3D& point) const; 43 void ComputeRotation(flair::core::Quaternion& quat) const; 44 void ComputeRotation(flair::core::RotationMatrix& matrix) const; 45 void ComputeRotation(flair::core::Euler& euler) const; 34 class OneAxisRotation_impl { 35 public: 36 OneAxisRotation_impl(flair::gui::GroupBox *box); 37 ~OneAxisRotation_impl(); 38 void ComputeRotation(flair::core::Vector3D &point) const; 39 void ComputeRotation(flair::core::Quaternion &quat) const; 40 void ComputeRotation(flair::core::RotationMatrix &matrix) const; 41 void ComputeRotation(flair::core::Euler &euler) const; 46 42 47 48 49 flair::gui::DoubleSpinBox*rot_value;43 private: 44 flair::gui::ComboBox *rot_axe; 45 flair::gui::DoubleSpinBox *rot_value; 50 46 }; 51 47 -
trunk/lib/FlairCore/src/unexported/SendData_impl.h
r2 r15 23 23 * 24 24 */ 25 class SendData_impl 26 { 27 public: 28 SendData_impl(); 29 ~SendData_impl(); 30 bool is_enabled; 31 size_t send_size; 32 uint16_t send_period; 25 class SendData_impl { 26 public: 27 SendData_impl(); 28 ~SendData_impl(); 29 bool is_enabled; 30 size_t send_size; 31 uint16_t send_period; 33 32 }; 34 33 -
trunk/lib/FlairCore/src/unexported/SharedMem_impl.h
r2 r15 23 23 #endif 24 24 25 namespace flair 26 { 27 namespace core 28 { 29 class SharedMem; 30 } 25 namespace flair { 26 namespace core { 27 class SharedMem; 28 } 31 29 } 32 30 … … 36 34 */ 37 35 38 class SharedMem_impl 39 { 40 public:41 SharedMem_impl(const flair::core::SharedMem* self,std::string name,size_t size);42 36 class SharedMem_impl { 37 public: 38 SharedMem_impl(const flair::core::SharedMem *self, std::string name, 39 size_t size); 40 ~SharedMem_impl(); 43 41 44 void Write(const char* buf,size_t size);45 void Read(char* buf,size_t size);42 void Write(const char *buf, size_t size); 43 void Read(char *buf, size_t size); 46 44 47 48 const flair::core::SharedMem*self;49 50 45 private: 46 const flair::core::SharedMem *self; 47 size_t size; 48 char *mem_segment; 51 49 #ifdef __XENO__ 52 53 54 55 50 RT_HEAP heap; 51 RT_MUTEX mutex; 52 bool heap_binded; 53 bool mutex_binded; 56 54 #else 57 58 59 std::string sem_name,shm_name;55 int fd; 56 sem_t *sem; 57 std::string sem_name, shm_name; 60 58 #endif 61 59 }; -
trunk/lib/FlairCore/src/unexported/Socket_impl.h
r2 r15 21 21 #endif 22 22 23 namespace flair 24 { 25 namespace core 26 { 27 class Socket; 28 } 23 namespace flair { 24 namespace core { 25 class Socket; 26 } 29 27 } 30 28 31 class Socket_impl 32 { 33 public:34 Socket_impl(const flair::core::Socket* self, std::string name,std::string address,bool broadcast=false);35 Socket_impl(const flair::core::Socket* self, std::string name,uint16_t port);36 29 class Socket_impl { 30 public: 31 Socket_impl(const flair::core::Socket *self, std::string name, 32 std::string address, bool broadcast = false); 33 Socket_impl(const flair::core::Socket *self, std::string name, uint16_t port); 34 ~Socket_impl(); 37 35 38 void SendMessage(std::string message); 39 void SendMessage(const char* src,size_t src_len); 40 ssize_t RecvMessage(char* msg,size_t msg_len,flair::core::Time timeout,char* src=NULL,size_t* src_len=NULL); 36 void SendMessage(std::string message); 37 void SendMessage(const char *src, size_t src_len); 38 ssize_t RecvMessage(char *msg, size_t msg_len, flair::core::Time timeout, 39 char *src = NULL, size_t *src_len = NULL); 41 40 42 43 44 45 46 47 48 const flair::core::Socket*self;49 41 private: 42 int fd; 43 uint16_t port; 44 std::string address; 45 bool broadcast; 46 void Init(void); 47 const flair::core::Socket *self; 48 struct sockaddr_in sock_in; 50 49 #ifdef __XENO__ 51 52 static void* user(void *arg);53 54 50 bool is_running; 51 static void *user(void *arg); 52 pthread_t user_thread; 53 RT_PIPE pipe; 55 54 #endif 56 55 }; -
trunk/lib/FlairCore/src/unexported/Thread_impl.h
r2 r15 22 22 #endif 23 23 24 namespace flair 25 { 26 namespace core 27 { 28 class Thread; 29 class IODevice; 30 class ConditionVariable; 31 } 24 namespace flair { 25 namespace core { 26 class Thread; 27 class IODevice; 28 class ConditionVariable; 29 } 32 30 } 33 31 34 class Thread_impl 35 { 36 public: 37 Thread_impl(flair::core::Thread* self,uint8_t priority); 38 ~Thread_impl(); 39 void Start(void); 40 void Join(void); 41 void SafeStop(void); 42 bool ToBeStopped(void); 43 void SetPeriodUS(uint32_t period); 44 uint32_t GetPeriodUS(void) const; 45 void SetPeriodMS(uint32_t period); 46 uint32_t GetPeriodMS(void) const; 47 void WaitPeriod(void); 48 void Suspend(void); 49 bool SuspendUntil (flair::core::Time date); 50 void Resume(void); 51 bool IsSuspended(void); 52 int WaitUpdate(const flair::core::IODevice* device); 53 bool period_set; 32 class Thread_impl { 33 public: 34 Thread_impl(flair::core::Thread *self, uint8_t priority); 35 ~Thread_impl(); 36 void Start(void); 37 void Join(void); 38 void SafeStop(void); 39 bool ToBeStopped(void); 40 void SetPeriodUS(uint32_t period); 41 uint32_t GetPeriodUS(void) const; 42 void SetPeriodMS(uint32_t period); 43 uint32_t GetPeriodMS(void) const; 44 void WaitPeriod(void); 45 void Suspend(void); 46 bool SuspendUntil(flair::core::Time date); 47 void Resume(void); 48 bool IsSuspended(void); 49 int WaitUpdate(const flair::core::IODevice *device); 50 bool period_set; 54 51 55 56 flair::core::Thread*self;57 flair::core::ConditionVariable*cond;58 59 flair::core::Time max_jitter,min_jitter,mean_jitter;60 61 62 63 64 65 66 67 52 private: 53 flair::core::Thread *self; 54 flair::core::ConditionVariable *cond; 55 uint8_t priority; 56 flair::core::Time max_jitter, min_jitter, mean_jitter; 57 flair::core::Time last; 58 uint64_t cpt; 59 flair::core::Time period; 60 bool isRunning; 61 bool tobestopped; 62 bool is_suspended; 63 void PrintStats(void); 64 void ComputeJitter(flair::core::Time time); 68 65 #ifdef __XENO__ 69 70 static void main_rt(void *arg);66 RT_TASK task_rt; 67 static void main_rt(void *arg); 71 68 #else 72 73 static void* main_nrt(void *arg);74 69 pthread_t task_nrt; 70 static void *main_nrt(void *arg); 71 flair::core::Time next_time; 75 72 #endif 76 73 }; -
trunk/lib/FlairCore/src/unexported/Widget_impl.h
r2 r15 17 17 #include <io_data.h> 18 18 19 namespace flair 20 { 21 namespace gui 22 { 23 class Widget; 24 } 19 namespace flair { 20 namespace gui { 21 class Widget; 22 } 25 23 } 26 24 … … 28 26 * \brief Classe representant un Widget 29 27 * 30 * C'est une classe de base. Tout comme l'Object elle permet de gérer les liens de parenté 31 * et de détruire automatiquement les enfants. Elle permet en plus de gérer une communication 28 * C'est une classe de base. Tout comme l'Object elle permet de gérer les liens 29 *de parenté 30 * et de détruire automatiquement les enfants. Elle permet en plus de gérer une 31 *communication 32 32 * avec la station sol, et donc d'y afficher un QWidget. \n 33 * La comunication avec la station sol se fait par l'échange de fichiers xml. Les propriétés xml du Widget sont 33 * La comunication avec la station sol se fait par l'échange de fichiers xml. 34 *Les propriétés xml du Widget sont 34 35 * modifiables par les fonctions appropriées. \n 35 * Un fichier xml de réglages par défaut du Widget est utilisé s'il a été spécifié à la construction du FrameworkManager. 36 * Un fichier xml de réglages par défaut du Widget est utilisé s'il a été 37 *spécifié à la construction du FrameworkManager. 36 38 */ 37 class Widget_impl 38 { 39 friend class flair::core::FrameworkManager; 40 friend class FrameworkManager_impl; 39 class Widget_impl { 40 friend class flair::core::FrameworkManager; 41 friend class FrameworkManager_impl; 41 42 42 public: 43 /*! 44 * \brief Constructeur 45 * 46 * Construit un Widget, qui est automatiquement enfant du parent. Le fichier xml 47 * spécifié au constructeur du FrameworkManager est utilisé pour les réglages par 48 * défaut. \n 49 * Sauf pour le FrameworkManager, ce constructeur doit être apellé depuis une tache temps réel 50 * lorsque l'on utilise la librairie framework_rt. 51 * 52 * \param parent parent 53 * \param name nom 54 * \param type type 55 */ 56 Widget_impl(flair::gui::Widget* self,const flair::gui::Widget* parent,std::string name,std::string type); 43 public: 44 /*! 45 * \brief Constructeur 46 * 47 * Construit un Widget, qui est automatiquement enfant du parent. Le fichier 48 *xml 49 * spécifié au constructeur du FrameworkManager est utilisé pour les réglages 50 *par 51 * défaut. \n 52 * Sauf pour le FrameworkManager, ce constructeur doit être apellé depuis une 53 *tache temps réel 54 * lorsque l'on utilise la librairie framework_rt. 55 * 56 * \param parent parent 57 * \param name nom 58 * \param type type 59 */ 60 Widget_impl(flair::gui::Widget *self, const flair::gui::Widget *parent, 61 std::string name, std::string type); 57 62 58 /*! 59 * \brief Déstructeur 60 * 61 * Détruit automatiquement les enfants. 62 * La destruction implique la destruction du QWidget associé sur la station sol.\n 63 * Sauf pour le FrameworkManager, ce déstructeur doit être apellé depuis une tache temps réel 64 * lorsque l'on utilise la librairie framework_rt. 65 * 66 */ 67 ~Widget_impl(); 63 /*! 64 * \brief Déstructeur 65 * 66 * Détruit automatiquement les enfants. 67 * La destruction implique la destruction du QWidget associé sur la station 68 *sol.\n 69 * Sauf pour le FrameworkManager, ce déstructeur doit être apellé depuis une 70 *tache temps réel 71 * lorsque l'on utilise la librairie framework_rt. 72 * 73 */ 74 ~Widget_impl(); 68 75 69 70 71 72 73 74 75 76 77 76 /*! 77 * \brief Activer 78 * 79 * Active le QWidget associé sur la station sol. \n 80 * Un QWdiget désactivé apparait grisé et n'est pas modifiable. 81 * 82 * \param status 83 */ 84 void setEnabled(bool status); 78 85 79 80 81 82 83 84 86 /*! 87 * \brief Envoi le xml 88 * 89 * Envoi le xml à la station sol pour prendre en compte les changements. 90 */ 91 void SendXml(void); 85 92 86 87 88 93 xmlNodePtr file_node; 94 xmlNodePtr send_node; 95 bool isenabled; 89 96 90 91 flair::gui::Widget*self;97 private: 98 flair::gui::Widget *self; 92 99 93 std::vector<flair::gui::Widget*> childs;100 std::vector<flair::gui::Widget *> childs; 94 101 95 void AddChild(const flair::gui::Widget*child);96 void RemoveChild(const flair::gui::Widget*child);102 void AddChild(const flair::gui::Widget *child); 103 void RemoveChild(const flair::gui::Widget *child); 97 104 98 99 100 101 102 103 104 105 105 /*! 106 * \brief Efface les proriétés xml 107 * 108 * Permet d'effacer toutes les propriétés XML fixées par SetVolatileXmlProp. 109 * A utliser lorsque l'on a plus besoin d'utiliser ces propriétés. Utile 110 * pour réduire la taille des fichiers XML écangés avec la station sol. 111 */ 112 void ClearXmlProps(void); 106 113 107 //xml 108 void ProcessXML(xmlNode *node); 109 xmlDocPtr CopyDoc(void); 110 static xmlNodePtr GetNodeByProp(xmlNodePtr doc,xmlChar *type,xmlChar *prop,xmlChar *value); 111 void printSendNode(); 112 xmlDocPtr send_doc; 114 // xml 115 void ProcessXML(xmlNode *node); 116 xmlDocPtr CopyDoc(void); 117 static xmlNodePtr GetNodeByProp(xmlNodePtr doc, xmlChar *type, xmlChar *prop, 118 xmlChar *value); 119 void printSendNode(); 120 xmlDocPtr send_doc; 113 121 }; 114 122 -
trunk/lib/FlairCore/src/unexported/communication.h
r2 r15 6 6 #define COMMUNICATION_H 7 7 8 9 //messages file socket 8 // messages file socket 10 9 #define FILE_INFO_LITTLE_ENDIAN 0x01 11 10 #define FILE_INFO_BIG_ENDIAN 0x02 … … 19 18 #define DATAS_BIG_ENDIAN 0xfe 20 19 21 22 20 #endif // COMMUNICATION_H -
trunk/lib/FlairCore/src/unexported/config.h
r2 r15 19 19 #define CONFIG_H 20 20 21 // stack size of nrt threads, comment it to use default value22 #define NRT_STACK_SIZE 1024 *1024*121 // stack size of nrt threads, comment it to use default value 22 #define NRT_STACK_SIZE 1024 * 1024 * 1 23 23 24 // stack size of rt threads, comment it to use default value25 #define RT_STACK_SIZE 1024 *10024 // stack size of rt threads, comment it to use default value 25 #define RT_STACK_SIZE 1024 * 100 26 26 27 // rt pipe size, comment it to use system heap28 #define RT_PIPE_SIZE 1024 *102427 // rt pipe size, comment it to use system heap 28 #define RT_PIPE_SIZE 1024 * 1024 29 29 30 // nrt pipe size31 #define NRT_PIPE_SIZE 1024 *10030 // nrt pipe size 31 #define NRT_PIPE_SIZE 1024 * 100 32 32 33 // rt log heap size34 #define LOG_HEAP 1024 *10033 // rt log heap size 34 #define LOG_HEAP 1024 * 100 35 35 36 // xml heap size37 #define XML_HEAP 5 *1024*102436 // xml heap size 37 #define XML_HEAP 5 * 1024 * 1024 38 38 39 // nrt pipe path39 // nrt pipe path 40 40 #define NRT_PIPE_PATH "/proc/xenomai/registry/native/pipes/" 41 41 42 // min priority for Threads42 // min priority for Threads 43 43 #define MIN_THREAD_PRIORITY 20 44 44 45 // max priority for Threads45 // max priority for Threads 46 46 #define MAX_THREAD_PRIORITY 99 47 47 48 // priority of the FrameworkManager task (manages udt connection)48 // priority of the FrameworkManager task (manages udt connection) 49 49 #define FRAMEWORK_TASK_PRIORITY 1 50 50 51 // timeout in ms for select51 // timeout in ms for select 52 52 #define SELECT_TIMEOUT_MS 200 53 53 54 // type of xml root element54 // type of xml root element 55 55 #define XML_ROOT_TYPE "root" 56 56 57 // name of xml root element57 // name of xml root element 58 58 //#define XML_ROOT_ELEMENT "Manager" 59 59 60 // name of main tabwidget60 // name of main tabwidget 61 61 #define XML_MAIN_TABWIDGET "Main_TabWidget" 62 62 63 // name of app tabwidget63 // name of app tabwidget 64 64 #define XML_APP_TABWIDGET "App_TabWidget" 65 65 66 // use compression for messages with ground station66 // use compression for messages with ground station 67 67 #define COMPRESS_FRAMES 68 68 69 // size of buffer shunck69 // size of buffer shunck 70 70 #define COMPRESS_CHUNK 1024 71 71 -
trunk/lib/FlairCore/src/unexported/cvmatrix_impl.h
r2 r15 14 14 #define CVMATRIX_IMPL_H 15 15 16 17 16 #include <io_data.h> 18 17 #include <cvmatrix.h> … … 24 23 * 25 24 */ 26 class cvmatrix_impl 27 { 28 public: 29 cvmatrix_impl(flair::core::cvmatrix* self,int rows,int cols,flair::core::ScalarType const &elementDataType,int n); 30 cvmatrix_impl(flair::core::cvmatrix* self,const flair::core::cvmatrix_descriptor *descriptor, flair::core::ScalarType const &elementDataType,int n); 31 ~cvmatrix_impl(); 25 class cvmatrix_impl { 26 public: 27 cvmatrix_impl(flair::core::cvmatrix *self, int rows, int cols, 28 flair::core::ScalarType const &elementDataType, int n); 29 cvmatrix_impl(flair::core::cvmatrix *self, 30 const flair::core::cvmatrix_descriptor *descriptor, 31 flair::core::ScalarType const &elementDataType, int n); 32 ~cvmatrix_impl(); 32 33 33 CvMat* mat; 34 flair::core::ScalarType const &elementDataType; 35 // const since if element description is modified it would be a mess in the log 36 const flair::core::cvmatrix_descriptor *descriptor; 34 CvMat *mat; 35 flair::core::ScalarType const &elementDataType; 36 // const since if element description is modified it would be a mess in the 37 // log 38 const flair::core::cvmatrix_descriptor *descriptor; 37 39 38 39 flair::core::cvmatrix*self;40 void Init(flair::core::cvmatrix* self,int n);40 private: 41 flair::core::cvmatrix *self; 42 void Init(flair::core::cvmatrix *self, int n); 41 43 }; 42 44 -
trunk/lib/FlairCore/src/unexported/io_data_impl.h
r2 r15 19 19 * \brief Abstract class for data types. 20 20 * 21 * Use this class to define a custom data type. Data types ares used for logging and graphs. \n 21 * Use this class to define a custom data type. Data types ares used for logging 22 *and graphs. \n 22 23 * The reimplemented class must call SetSize() in its constructor. \n 23 24 * io_data can be constructed with n samples (see io_data::io_data). 24 25 * In this case, old samples can be accessed throug io_data::Prev. 25 26 */ 26 class io_data_impl 27 { 28 public:29 io_data_impl(flair::core::io_data* self,int n);30 ~io_data_impl();31 void Circle(void);32 bool IsConsistent(void);33 void SetConsistent(bool status);34 void WriteLogDescriptor(std::fstream& desc_file,int *index);35 void PrintLogDescriptor(void); 36 void AppendLogDescription(std::string description,flair::core::DataType const &datatype);37 38 39 void**circle_ptr;27 class io_data_impl { 28 public: 29 io_data_impl(flair::core::io_data *self, int n); 30 ~io_data_impl(); 31 void Circle(void); 32 bool IsConsistent(void); 33 void SetConsistent(bool status); 34 void WriteLogDescriptor(std::fstream &desc_file, int *index); 35 void PrintLogDescriptor(void); 36 void AppendLogDescription(std::string description, 37 flair::core::DataType const &datatype); 38 size_t size; 39 flair::core::Time time; 40 void **circle_ptr; 40 41 41 42 flair::core::io_data*self;43 44 45 42 private: 43 flair::core::io_data *self; 44 int n; 45 bool is_consistent; 46 std::vector<std::string> descriptors; 46 47 }; 47 48 -
trunk/lib/FlairCore/src/unexported/ui_com.h
r2 r15 25 25 #endif 26 26 27 namespace flair 28 { 29 namespace core 30 { 31 class Mutex; 32 class Object; 33 } 34 namespace gui 35 { 36 class SendData; 37 } 27 namespace flair { 28 namespace core { 29 class Mutex; 30 class Object; 31 } 32 namespace gui { 33 class SendData; 34 } 38 35 } 39 36 40 class ui_com: public flair::core::Thread 41 { 42 public: 43 ui_com(const flair::core::Object *parent,UDTSOCKET sock); 44 ~ui_com(); 45 void Send(char* buf,ssize_t size); 46 ssize_t Receive(char* buf,ssize_t buf_size); 47 void AddSendData(const flair::gui::SendData *obj); 48 void UpdateSendData(const flair::gui::SendData *obj); 49 void RemoveSendData(const flair::gui::SendData *obj); 50 void UpdateDataToSendSize(void); 51 void Block(void); 52 void UnBlock(void); 53 bool ConnectionLost(void); 37 class ui_com : public flair::core::Thread { 38 public: 39 ui_com(const flair::core::Object *parent, UDTSOCKET sock); 40 ~ui_com(); 41 void Send(char *buf, ssize_t size); 42 ssize_t Receive(char *buf, ssize_t buf_size); 43 void AddSendData(const flair::gui::SendData *obj); 44 void UpdateSendData(const flair::gui::SendData *obj); 45 void RemoveSendData(const flair::gui::SendData *obj); 46 void UpdateDataToSendSize(void); 47 void Block(void); 48 void UnBlock(void); 49 bool ConnectionLost(void); 54 50 55 private: 56 ssize_t send_size; 57 char *send_buffer; 58 std::vector<const flair::gui::SendData*> data_to_send; 59 std::vector<flair::core::Time> resume_time; 60 flair::core::Mutex *send_mutex; 61 UDTSOCKET socket_fd; 62 bool connection_lost; 63 void Run(void); 64 void SendDatas(void); 65 static int compressBuffer(char *in, ssize_t in_size,char **out,ssize_t *out_size, int level); 66 static int uncompressBuffer(unsigned char *in, ssize_t in_size,unsigned char **out,ssize_t *out_size); 51 private: 52 ssize_t send_size; 53 char *send_buffer; 54 std::vector<const flair::gui::SendData *> data_to_send; 55 std::vector<flair::core::Time> resume_time; 56 flair::core::Mutex *send_mutex; 57 UDTSOCKET socket_fd; 58 bool connection_lost; 59 void Run(void); 60 void SendDatas(void); 61 static int compressBuffer(char *in, ssize_t in_size, char **out, 62 ssize_t *out_size, int level); 63 static int uncompressBuffer(unsigned char *in, ssize_t in_size, 64 unsigned char **out, ssize_t *out_size); 67 65 #ifdef __XENO__ 68 69 static void* user_thread(void *arg);70 71 66 bool is_running; 67 static void *user_thread(void *arg); 68 pthread_t thread; 69 RT_PIPE pipe; 72 70 #endif 73 74 71 }; 75 72
Note:
See TracChangeset
for help on using the changeset viewer.