Changeset 122 in flair-src for trunk/lib/FlairMeta/src
- Timestamp:
- Jan 6, 2017, 1:56:26 PM (8 years ago)
- Location:
- trunk/lib/FlairMeta/src
- Files:
-
- 16 edited
Legend:
- Unmodified
- Added
- Removed
-
trunk/lib/FlairMeta/src/HdsX8.cpp
r107 r122 35 35 namespace meta { 36 36 37 HdsX8::HdsX8( FrameworkManager *parent, string uav_name,37 HdsX8::HdsX8(string name, 38 38 filter::UavMultiplex *multiplex) 39 : Uav( parent, uav_name, multiplex) {40 RTDM_I2cPort *i2cport = new RTDM_I2cPort( parent, "rtdm_i2c", "rti2c3");41 RTDM_SerialPort *imu_port = new RTDM_SerialPort( parent, "imu_port", "rtser1");39 : Uav(name, multiplex) { 40 RTDM_I2cPort *i2cport = new RTDM_I2cPort(getFrameworkManager(), "rtdm_i2c", "rti2c3"); 41 RTDM_SerialPort *imu_port = new RTDM_SerialPort(getFrameworkManager(), "imu_port", "rtser1"); 42 42 43 43 if (multiplex == NULL) 44 SetMultiplex(new X4X8Multiplex( parent, "motors", X4X8Multiplex::X8));44 SetMultiplex(new X4X8Multiplex(getFrameworkManager(), "motors", X4X8Multiplex::X8)); 45 45 46 46 SetBldc(new BlCtrlV2(GetUavMultiplex(), GetUavMultiplex()->GetLayout(), 47 47 "motors", GetUavMultiplex()->MotorsCount(), i2cport)); 48 SetUsRangeFinder(new Srf08( parent, "SRF08", i2cport, 0x70, 60));49 SetAhrs(new Gx3_25_ahrs( parent, "imu", imu_port,48 SetUsRangeFinder(new Srf08(getFrameworkManager(), "SRF08", i2cport, 0x70, 60)); 49 SetAhrs(new Gx3_25_ahrs(getFrameworkManager(), "imu", imu_port, 50 50 Gx3_25_imu::AccelerationAngularRateAndOrientationMatrix, 70)); 51 51 SetBatteryMonitor(((BlCtrlV2 *)GetBldc())->GetBatteryMonitor()); 52 53 /* 54 if(VRPNType==Auto || VRPNType==AutoSerialPort) 55 { 56 RTDM_SerialPort* vrpn_port=new 57 RTDM_SerialPort(parent,"vrpn_port","rtser3"); 58 59 vrpnclient=new VrpnClient(parent,"vrpn",vrpn_port,10000,80); 60 uav_vrpn=new 61 MetaVrpnObject(vrpnclient,uav_name,VRPNSerialObjectId); 62 } 63 */ 64 SetVerticalCamera(new Ps3Eye(parent, "camv", 0, 50)); 52 SetVerticalCamera(new Ps3Eye(getFrameworkManager(), "camv", 0, 50)); 65 53 } 66 54 … … 71 59 ((Srf08 *)GetUsRangeFinder())->Start(); 72 60 ((Ps3Eye *)GetVerticalCamera())->Start(); 73 Uav::StartSensors();74 61 } 75 62 -
trunk/lib/FlairMeta/src/HdsX8.h
r22 r122 24 24 class HdsX8 : public Uav { 25 25 public: 26 HdsX8( core::FrameworkManager *parent, std::string uav_name,26 HdsX8(std::string name, 27 27 filter::UavMultiplex *multiplex = NULL); 28 28 ~HdsX8(); 29 29 void StartSensors(void); 30 std::string GetDefaultVrpnAddress(void) const{return "192.168.147.197:3883";} 30 31 31 32 private: -
trunk/lib/FlairMeta/src/MetaVrpnObject.cpp
r15 r122 39 39 namespace meta { 40 40 41 MetaVrpnObject::MetaVrpnObject( const VrpnClient *parent,string name)42 : VrpnObject( parent, name, parent->GetTabWidget()) {43 ConstructorCommon( parent,name);41 MetaVrpnObject::MetaVrpnObject(string name) 42 : VrpnObject( name, GetVrpnClient()->GetTabWidget()) { 43 ConstructorCommon(name); 44 44 } 45 45 46 MetaVrpnObject::MetaVrpnObject( const VrpnClient *parent,std::string name,46 MetaVrpnObject::MetaVrpnObject(std::string name, 47 47 uint8_t id) 48 : VrpnObject( parent, name, id, parent->GetTabWidget()) {49 ConstructorCommon( parent,name);48 : VrpnObject(name, id, GetVrpnClient()->GetTabWidget()) { 49 ConstructorCommon( name); 50 50 } 51 51 52 void MetaVrpnObject::ConstructorCommon( const VrpnClient *parent,string name) {52 void MetaVrpnObject::ConstructorCommon(string name) { 53 53 cvmatrix_descriptor *desc = new cvmatrix_descriptor(6, 1); 54 54 for (int i = 0; i < 6; i++) { … … 60 60 } 61 61 62 pbas = new LowPassFilter(this, parent->GetLayout()->NewRow(),62 pbas = new LowPassFilter(this, GetVrpnClient()->GetLayout()->NewRow(), 63 63 name + " Passe bas", prev_value); 64 64 … … 72 72 } 73 73 74 euler = new EulerDerivative(pbas, parent->GetLayout()->NewRow(),74 euler = new EulerDerivative(pbas, GetVrpnClient()->GetLayout()->NewRow(), 75 75 name + "_euler", prev_value); 76 76 … … 82 82 vz_opti_plot->AddCurve(euler->Matrix()->Element(5)); 83 83 84 plot_tab = new Tab( parent->GetTabWidget(), "Mesures (xy) " + name);84 plot_tab = new Tab(GetVrpnClient()->GetTabWidget(), "Mesures (xy) " + name); 85 85 xy_plot = new DataPlot2D(plot_tab->NewRow(), "xy", "y", -5, 5, "x", -5, 5); 86 86 xy_plot->AddCurve(Output()->Element(4, 0), Output()->Element(3, 0)); -
trunk/lib/FlairMeta/src/MetaVrpnObject.h
r15 r122 18 18 19 19 namespace flair { 20 namespace core { 21 class Vector3D; 22 class FloatType; 23 } 24 namespace gui { 25 class DataPlot1D; 26 class DataPlot2D; 27 class Tab; 28 } 29 namespace filter { 30 class EulerDerivative; 31 class LowPassFilter; 32 } 33 namespace sensor { 34 class VrpnClient; 35 } 20 namespace core { 21 class Vector3D; 22 class FloatType; 23 } 24 namespace gui { 25 class DataPlot1D; 26 class DataPlot2D; 27 class Tab; 28 } 29 namespace filter { 30 class EulerDerivative; 31 class LowPassFilter; 32 } 36 33 } 37 34 … … 47 44 class MetaVrpnObject : public sensor::VrpnObject { 48 45 public: 49 MetaVrpnObject(const sensor::VrpnClient *parent, std::string name); 50 MetaVrpnObject(const sensor::VrpnClient *parent, std::string name, 51 uint8_t id); 46 MetaVrpnObject(std::string name); 47 MetaVrpnObject(std::string name,uint8_t id); 52 48 ~MetaVrpnObject(); 53 49 gui::DataPlot1D *VxPlot(void) const; // 1,0 … … 58 54 59 55 private: 60 void ConstructorCommon( const sensor::VrpnClient *parent,std::string name);56 void ConstructorCommon(std::string name); 61 57 filter::LowPassFilter *pbas; 62 58 filter::EulerDerivative *euler; -
trunk/lib/FlairMeta/src/SimuX4.cpp
r22 r122 37 37 namespace meta { 38 38 39 SimuX4::SimuX4( FrameworkManager *parent, string uav_name, int simu_id,39 SimuX4::SimuX4(string name, int simu_id, 40 40 filter::UavMultiplex *multiplex) 41 : Uav( parent, uav_name, multiplex) {41 : Uav(name, multiplex) { 42 42 43 43 if (multiplex == NULL) 44 SetMultiplex(new X4X8Multiplex( parent, "motors", X4X8Multiplex::X4));44 SetMultiplex(new X4X8Multiplex(getFrameworkManager(), "motors", X4X8Multiplex::X4)); 45 45 46 46 SetBldc(new SimuBldc(GetUavMultiplex(), GetUavMultiplex()->GetLayout(), 47 47 "motors", GetUavMultiplex()->MotorsCount(), simu_id)); 48 SetUsRangeFinder(new SimuUs( parent, "us", simu_id, 60));49 SetAhrs(new SimuAhrs( parent, "imu", simu_id, 70));50 Tab *bat_tab = new Tab( parent->GetTabWidget(), "battery");48 SetUsRangeFinder(new SimuUs(getFrameworkManager(), "us", simu_id, 60)); 49 SetAhrs(new SimuAhrs(getFrameworkManager(), "imu", simu_id, 70)); 50 Tab *bat_tab = new Tab(getFrameworkManager()->GetTabWidget(), "battery"); 51 51 SetBatteryMonitor(new BatteryMonitor(bat_tab->NewRow(), "battery")); 52 52 GetBatteryMonitor()->SetBatteryValue(12); 53 53 SetVerticalCamera( 54 new SimuCamera( parent, "simu_cam_v", 320, 240, 3, simu_id, 10));54 new SimuCamera(getFrameworkManager(), "simu_cam_v", 320, 240, 3, simu_id, 10)); 55 55 } 56 56 … … 61 61 ((SimuUs *)GetUsRangeFinder())->Start(); 62 62 ((SimuCamera *)GetVerticalCamera())->Start(); 63 Uav::StartSensors();64 63 } 65 66 void SimuX4::SetupVRPNAutoIP(string name) { SetupVRPN("127.0.0.1:3883", name); }67 64 68 65 } // end namespace meta -
trunk/lib/FlairMeta/src/SimuX4.h
r22 r122 26 26 // simu_id: 0 if simulating only one UAV 27 27 //>0 otherwise 28 SimuX4( core::FrameworkManager *parent, std::string uav_name, int simu_id = 0,28 SimuX4(std::string name, int simu_id = 0, 29 29 filter::UavMultiplex *multiplex = NULL); 30 30 ~SimuX4(); 31 31 void StartSensors(void); 32 void SetupVRPNAutoIP(std::string name);33 32 }; 34 33 } // end namespace meta -
trunk/lib/FlairMeta/src/SimuX8.cpp
r22 r122 37 37 namespace meta { 38 38 39 SimuX8::SimuX8( FrameworkManager *parent, string uav_name, int simu_id,39 SimuX8::SimuX8(string name, int simu_id, 40 40 filter::UavMultiplex *multiplex) 41 : Uav( parent, uav_name, multiplex) {41 : Uav(name, multiplex) { 42 42 43 43 if (multiplex == NULL) 44 SetMultiplex(new X4X8Multiplex( parent, "motors", X4X8Multiplex::X8));44 SetMultiplex(new X4X8Multiplex(getFrameworkManager(), "motors", X4X8Multiplex::X8)); 45 45 46 46 SetBldc(new SimuBldc(GetUavMultiplex(), GetUavMultiplex()->GetLayout(), 47 47 "motors", GetUavMultiplex()->MotorsCount(), simu_id)); 48 SetUsRangeFinder(new SimuUs( parent, "us", simu_id, 60));49 SetAhrs(new SimuAhrs( parent, "imu", simu_id, 70));50 Tab *bat_tab = new Tab( parent->GetTabWidget(), "battery");48 SetUsRangeFinder(new SimuUs(getFrameworkManager(), "us", simu_id, 60)); 49 SetAhrs(new SimuAhrs(getFrameworkManager(), "imu", simu_id, 70)); 50 Tab *bat_tab = new Tab(getFrameworkManager()->GetTabWidget(), "battery"); 51 51 SetBatteryMonitor(new BatteryMonitor(bat_tab->NewRow(), "battery")); 52 52 GetBatteryMonitor()->SetBatteryValue(12); 53 53 SetVerticalCamera( 54 new SimuCamera( parent, "simu_cam_v", 320, 240, 3, simu_id, 10));54 new SimuCamera(getFrameworkManager(), "simu_cam_v", 320, 240, 3, simu_id, 10)); 55 55 } 56 56 … … 61 61 ((SimuUs *)GetUsRangeFinder())->Start(); 62 62 ((SimuCamera *)GetVerticalCamera())->Start(); 63 Uav::StartSensors();64 63 } 65 66 void SimuX8::SetupVRPNAutoIP(string name) { SetupVRPN("127.0.0.1:3883", name); }67 64 68 65 } // end namespace meta -
trunk/lib/FlairMeta/src/SimuX8.h
r22 r122 26 26 // simu_id: 0 if simulating only one UAV 27 27 //>0 otherwise 28 SimuX8( core::FrameworkManager *parent, std::string uav_name, int simu_id = 0,28 SimuX8(std::string name, int simu_id = 0, 29 29 filter::UavMultiplex *multiplex = NULL); 30 30 ~SimuX8(); 31 31 void StartSensors(void); 32 void SetupVRPNAutoIP(std::string name);33 32 }; 34 33 } // end namespace meta -
trunk/lib/FlairMeta/src/Uav.cpp
r121 r122 38 38 using namespace flair::actuator; 39 39 40 namespace { 41 flair::meta::Uav *uavSingleton = NULL; 42 } 43 40 44 namespace flair { 41 45 namespace meta { 42 46 43 Uav::Uav(FrameworkManager *parent, string name, UavMultiplex *multiplex) 44 : Object(parent, name) { 45 vrpnclient = NULL; 46 uav_vrpn = NULL; 47 Uav *GetUav(void) { return uavSingleton; } 48 49 Uav::Uav(string name, UavMultiplex *multiplex) 50 : Object(getFrameworkManager(), name) { 51 if (uavSingleton != NULL) { 52 Err("Uav must be instanced only one time\n"); 53 return; 54 } 55 56 uavSingleton = this; 47 57 verticalCamera = NULL; 48 58 horizontalCamera = NULL; … … 82 92 horizontalCamera = (Camera *)inHorizontalCamera; 83 93 } 84 /*85 void Uav::SetupVRPNSerial(SerialPort *vrpn_port,string name,int86 VRPNSerialObjectId) {87 vrpnclient=new VrpnClient(getFrameworkManager(),"vrpn",vrpn_port,10000,80);88 uav_vrpn=new MetaVrpnObject(vrpnclient,name,VRPNSerialObjectId);89 94 90 getFrameworkManager()->AddDeviceToLog(uav_vrpn);91 }92 */93 void Uav::SetupVRPNAutoIP(string name) {94 SetupVRPN("192.168.147.197:3883", name);95 }96 97 void Uav::SetupVRPN(string optitrack_address, string name) {98 vrpnclient = new VrpnClient(getFrameworkManager(), "vrpn", optitrack_address,99 10000, 80);100 uav_vrpn = new MetaVrpnObject(vrpnclient, name);101 102 getFrameworkManager()->AddDeviceToLog(uav_vrpn);103 104 GetAhrs()->YawPlot()->AddCurve(uav_vrpn->State()->Element(2),105 DataPlot::Green);106 // GetAhrs()->RollPlot()->AddCurve(uav_vrpn->State()->Element(0),DataPlot::Green);107 // GetAhrs()->PitchPlot()->AddCurve(uav_vrpn->State()->Element(1),DataPlot::Green);108 }109 110 void Uav::StartSensors(void) {111 if (vrpnclient != NULL) {112 vrpnclient->Start();113 }114 }115 95 void Uav::UseDefaultPlot(void) { 116 96 multiplex->UseDefaultPlot(); … … 184 164 BatteryMonitor *Uav::GetBatteryMonitor(void) const { return battery; } 185 165 186 VrpnClient *Uav::GetVrpnClient(void) const {187 if (vrpnclient == NULL)188 Err("vrpn is not setup, call SetupVRPN before\n");189 return vrpnclient;190 }191 192 MetaVrpnObject *Uav::GetVrpnObject(void) const { return uav_vrpn; }193 194 166 Camera *Uav::GetVerticalCamera(void) const { return verticalCamera; } 195 167 -
trunk/lib/FlairMeta/src/Uav.h
r121 r122 17 17 18 18 namespace flair { 19 namespace core { 20 class FrameworkManager; 21 } 22 namespace filter { 23 class Ahrs; 24 class UavMultiplex; 25 } 26 namespace actuator { 27 class Bldc; 28 } 29 namespace sensor { 30 class UsRangeFinder; 31 class BatteryMonitor; 32 class VrpnClient; 33 class Imu; 34 class Camera; 35 } 19 namespace filter { 20 class Ahrs; 21 class UavMultiplex; 22 } 23 namespace actuator { 24 class Bldc; 25 } 26 namespace sensor { 27 class UsRangeFinder; 28 class BatteryMonitor; 29 class Imu; 30 class Camera; 31 } 36 32 } 37 33 … … 39 35 namespace meta { 40 36 class MetaUsRangeFinder; 41 class MetaVrpnObject;42 37 43 38 /*! \class Uav 44 39 * 45 * \brief Base class to construct sensors/actuators depending on uav type 40 * \brief Base class to construct sensors/actuators depending on uav type. 41 * The Object is created with 42 * the FrameworkManager as parent. FrameworkManager must be created before. 43 * Only one instance of this class is allowed by program. 46 44 */ 47 45 class Uav : public core::Object { 48 46 public: 49 /* 50 typedef enum { 51 None, 52 Auto,//rt serial if hds x4 ou x8, auto ip sinon 53 AutoIP, 54 UserDefinedIP, 55 AutoSerialPort, 56 } VRPNType_t; 57 */ 58 // uav_name: for optitrack 59 Uav(core::FrameworkManager *parent, std::string name, 47 48 Uav(std::string name, 60 49 filter::UavMultiplex *multiplex = NULL); 61 50 ~Uav(); 62 void SetupVRPN(std::string optitrack_address, std::string name);63 // vrpn serial: broken, need to add serial port in uav specific code64 // void SetupVRPNSerial(core::SerialPort *vrpn_port,std::string name,int65 // VRPNSerialObjectId);66 virtual void SetupVRPNAutoIP(std::string name);67 51 68 virtual void StartSensors(void) ;52 virtual void StartSensors(void)=0; 69 53 void UseDefaultPlot(void); 70 54 actuator::Bldc *GetBldc(void) const; … … 75 59 sensor::UsRangeFinder *GetUsRangeFinder(void) const; 76 60 sensor::BatteryMonitor *GetBatteryMonitor(void) const; 77 sensor::VrpnClient *GetVrpnClient(void) const;78 meta::MetaVrpnObject *GetVrpnObject(void) const;79 61 sensor::Camera *GetVerticalCamera(void) const; 80 62 sensor::Camera *GetHorizontalCamera(void) const; 63 virtual std::string GetDefaultVrpnAddress(void) const{return "127.0.0.1:3883";} 81 64 82 65 protected: … … 96 79 sensor::UsRangeFinder *us; 97 80 MetaUsRangeFinder *meta_us; 98 sensor::VrpnClient *vrpnclient;99 MetaVrpnObject *uav_vrpn;100 81 sensor::BatteryMonitor *battery; 101 82 sensor::Camera *verticalCamera,*horizontalCamera; 102 83 }; 84 85 /*! 86 * \brief get Uav 87 * 88 * \return the Uav 89 */ 90 Uav *GetUav(void); 91 103 92 } // end namespace meta 104 93 } // end namespace flair -
trunk/lib/FlairMeta/src/UavFactory.cpp
r45 r122 30 30 31 31 namespace { // anonymous 32 vector<flair::meta::Uav* (*)( FrameworkManager*,string,string,UavMultiplex*)> *vectoroffunctions=NULL;32 vector<flair::meta::Uav* (*)(string,string,UavMultiplex*)> *vectoroffunctions=NULL; 33 33 } 34 34 … … 41 41 42 42 43 Uav *CreateUav( FrameworkManager *parent, string uav_name, string uav_type,43 Uav *CreateUav(string name, string uav_type, 44 44 UavMultiplex *multiplex) { 45 45 … … 48 48 if(vectoroffunctions!=NULL) { 49 49 for(int i=0;i<vectoroffunctions->size();i++) { 50 uav=vectoroffunctions->at(i)( parent, uav_name,uav_type,multiplex);50 uav=vectoroffunctions->at(i)(name,uav_type,multiplex); 51 51 if(uav!=NULL) { 52 52 free(vectoroffunctions); … … 58 58 59 59 if (uav_type == "hds_x4") { 60 parent->Err("UAV type %s not yet implemented\n", uav_type.c_str());60 getFrameworkManager()->Err("UAV type %s not yet implemented\n", uav_type.c_str()); 61 61 return NULL; 62 62 } else if (uav_type == "hds_x8") { 63 return new HdsX8( parent, uav_name, multiplex);63 return new HdsX8(name, multiplex); 64 64 } else if (uav_type == "xair") { 65 return new XAir( parent, uav_name, multiplex);65 return new XAir(name, multiplex); 66 66 } else if (uav_type == "hds_xufo") { 67 parent->Err("UAV type %s not yet implemented\n", uav_type.c_str());67 getFrameworkManager()->Err("UAV type %s not yet implemented\n", uav_type.c_str()); 68 68 return NULL; 69 69 } else if (uav_type.compare(0, 7, "x4_simu") == 0) { … … 72 72 simu_id = atoi(uav_type.substr(7, uav_type.size() - 7).c_str()); 73 73 } 74 return new SimuX4( parent, uav_name, simu_id, multiplex);74 return new SimuX4(name, simu_id, multiplex); 75 75 } else if (uav_type.compare(0, 7, "x8_simu") == 0) { 76 76 int simu_id = 0; … … 78 78 simu_id = atoi(uav_type.substr(7, uav_type.size() - 7).c_str()); 79 79 } 80 return new SimuX8( parent, uav_name, simu_id, multiplex);80 return new SimuX8(name, simu_id, multiplex); 81 81 } else { 82 parent->Err("UAV type %s unknown\n", uav_type.c_str());82 getFrameworkManager()->Err("UAV type %s unknown\n", uav_type.c_str()); 83 83 return NULL; 84 84 } 85 85 } 86 86 87 void RegisterUavCreator(flair::meta::Uav*(*func)( FrameworkManager *parent, string uav_name, string uav_type,87 void RegisterUavCreator(flair::meta::Uav*(*func)(string name, string type, 88 88 UavMultiplex *multiplex)) { 89 if(vectoroffunctions==NULL) vectoroffunctions=(vector<flair::meta::Uav* (*)( FrameworkManager*,string,string,UavMultiplex*)>*)malloc(sizeof(vector<flair::meta::Uav* (*)(FrameworkManager*,string,string,UavMultiplex*)>));89 if(vectoroffunctions==NULL) vectoroffunctions=(vector<flair::meta::Uav* (*)(string,string,UavMultiplex*)>*)malloc(sizeof(vector<flair::meta::Uav* (*)(string,string,UavMultiplex*)>)); 90 90 91 91 vectoroffunctions->push_back(func); -
trunk/lib/FlairMeta/src/UavFactory.h
r41 r122 21 21 #include <Uav.h> 22 22 23 flair::meta::Uav *CreateUav(flair::core::FrameworkManager *parent, 24 std::string uav_name, std::string uav_type, 23 flair::meta::Uav *CreateUav(std::string name, std::string type, 25 24 flair::filter::UavMultiplex *multiplex = NULL); 26 25 27 void RegisterUavCreator(flair::meta::Uav*(*func)(flair::core::FrameworkManager *parent, 28 std::string uav_name, std::string uav_type, 26 void RegisterUavCreator(flair::meta::Uav*(*func)(std::string name, std::string type, 29 27 flair::filter::UavMultiplex *multiplex)); 30 28 #endif // UAVFACTORY -
trunk/lib/FlairMeta/src/UavStateMachine.cpp
r106 r122 52 52 using namespace flair::meta; 53 53 54 UavStateMachine::UavStateMachine( Uav* inUav,TargetController *controller):54 UavStateMachine::UavStateMachine(TargetController *controller): 55 55 Thread(getFrameworkManager(),"UavStateMachine",50), 56 uav( inUav),controller(controller),failSafeMode(true),flagConnectionLost(false),flagBatteryLow(false),flagCriticalSensorLost(false),flagZTrajectoryFinished(false),safeToFly(true){56 uav(GetUav()),controller(controller),failSafeMode(true),flagConnectionLost(false),flagBatteryLow(false),flagCriticalSensorLost(false),flagZTrajectoryFinished(false),safeToFly(true){ 57 57 altitudeState=AltitudeState_t::Stopped; 58 58 uav->UseDefaultPlot(); … … 135 135 return currentAngularSpeed; 136 136 } 137 138 const Uav *UavStateMachine::GetUav(void) const { return uav; }139 137 140 138 void UavStateMachine::AltitudeValues(float &altitude, -
trunk/lib/FlairMeta/src/UavStateMachine.h
r45 r122 59 59 * 60 60 * \brief State machine for UAV 61 * 62 * thread synchronized with ahrs, unless a period is set with SetPeriodUS or 63 *SetPeriodMS 61 * The Thread is created with 62 * the FrameworkManager as parent. FrameworkManager must be created before. 63 * The Thread is synchronized with Ahrs, unless a period is set with SetPeriodUS or 64 * SetPeriodMS 64 65 */ 65 66 … … 101 102 }; 102 103 103 UavStateMachine( meta::Uav* uav,sensor::TargetController* controller);104 UavStateMachine(sensor::TargetController* controller); 104 105 ~UavStateMachine(); 105 106 … … 107 108 108 109 const core::Vector3D &GetCurrentAngularSpeed(void) const; 109 110 const meta::Uav *GetUav(void) const;111 110 112 111 void Land(void); -
trunk/lib/FlairMeta/src/XAir.cpp
r100 r122 38 38 namespace meta { 39 39 40 XAir::XAir( FrameworkManager *parent, string uav_name,40 XAir::XAir(string name, 41 41 filter::UavMultiplex *multiplex) 42 : Uav( parent, uav_name, multiplex) {43 RTDM_I2cPort *i2cport = new RTDM_I2cPort( parent, "rtdm_i2c", "rti2c3");44 RTDM_SerialPort *imu_port = new RTDM_SerialPort( parent, "imu_port", "rtser1");42 : Uav(name, multiplex) { 43 RTDM_I2cPort *i2cport = new RTDM_I2cPort(getFrameworkManager(), "rtdm_i2c", "rti2c3"); 44 RTDM_SerialPort *imu_port = new RTDM_SerialPort(getFrameworkManager(), "imu_port", "rtser1"); 45 45 46 46 if (multiplex == NULL) 47 SetMultiplex(new X4X8Multiplex( parent, "motors", X4X8Multiplex::X8));47 SetMultiplex(new X4X8Multiplex(getFrameworkManager(), "motors", X4X8Multiplex::X8)); 48 48 49 49 SetBldc(new AfroBldc(GetUavMultiplex(), GetUavMultiplex()->GetLayout(), 50 50 "motors", GetUavMultiplex()->MotorsCount(), i2cport)); 51 SetUsRangeFinder(new Srf08( parent, "SRF08", i2cport, 0x70, 60));52 SetAhrs(new Gx3_25_ahrs( parent, "imu", imu_port,51 SetUsRangeFinder(new Srf08(getFrameworkManager(), "SRF08", i2cport, 0x70, 60)); 52 SetAhrs(new Gx3_25_ahrs(getFrameworkManager(), "imu", imu_port, 53 53 Gx3_25_imu::AccelerationAngularRateAndOrientationMatrix, 70)); 54 Tab *bat_tab = new Tab( parent->GetTabWidget(), "battery");54 Tab *bat_tab = new Tab(getFrameworkManager()->GetTabWidget(), "battery"); 55 55 SetBatteryMonitor(new BatteryMonitor(bat_tab->NewRow(), "battery")); 56 56 GetBatteryMonitor()->SetBatteryValue(12); 57 58 /* 59 if(VRPNType==Auto || VRPNType==AutoSerialPort) 60 { 61 RTDM_SerialPort* vrpn_port=new 62 RTDM_SerialPort(parent,"vrpn_port","rtser3"); 63 64 vrpnclient=new VrpnClient(parent,"vrpn",vrpn_port,10000,80); 65 uav_vrpn=new 66 MetaVrpnObject(vrpnclient,uav_name,VRPNSerialObjectId); 67 } 68 */ 69 SetVerticalCamera(new Ps3Eye(parent, "camv", 0, 50)); 57 SetVerticalCamera(new Ps3Eye(getFrameworkManager(), "camv", 0, 50)); 70 58 } 71 59 … … 76 64 ((Srf08 *)GetUsRangeFinder())->Start(); 77 65 ((Ps3Eye *)GetVerticalCamera())->Start(); 78 Uav::StartSensors();79 66 } 80 67 -
trunk/lib/FlairMeta/src/XAir.h
r22 r122 24 24 class XAir : public Uav { 25 25 public: 26 XAir( core::FrameworkManager *parent, std::string uav_name,26 XAir(std::string name, 27 27 filter::UavMultiplex *multiplex = NULL); 28 28 ~XAir(); 29 29 void StartSensors(void); 30 std::string GetDefaultVrpnAddress(void) const{return "192.168.147.197:3883";} 30 31 31 32 private:
Note:
See TracChangeset
for help on using the changeset viewer.