Changeset 122 in flair-src for trunk/lib/FlairMeta


Ignore:
Timestamp:
Jan 6, 2017, 1:56:26 PM (8 years ago)
Author:
Sanahuja Guillaume
Message:

modifs uav vrpn i686

Location:
trunk/lib/FlairMeta/src
Files:
16 edited

Legend:

Unmodified
Added
Removed
  • trunk/lib/FlairMeta/src/HdsX8.cpp

    r107 r122  
    3535namespace meta {
    3636
    37 HdsX8::HdsX8(FrameworkManager *parent, string uav_name,
     37HdsX8::HdsX8(string name,
    3838             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");
    4242
    4343  if (multiplex == NULL)
    44     SetMultiplex(new X4X8Multiplex(parent, "motors", X4X8Multiplex::X8));
     44    SetMultiplex(new X4X8Multiplex(getFrameworkManager(), "motors", X4X8Multiplex::X8));
    4545
    4646  SetBldc(new BlCtrlV2(GetUavMultiplex(), GetUavMultiplex()->GetLayout(),
    4747                       "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,
    5050                          Gx3_25_imu::AccelerationAngularRateAndOrientationMatrix, 70));
    5151  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));
    6553}
    6654
     
    7159  ((Srf08 *)GetUsRangeFinder())->Start();
    7260  ((Ps3Eye *)GetVerticalCamera())->Start();
    73   Uav::StartSensors();
    7461}
    7562
  • trunk/lib/FlairMeta/src/HdsX8.h

    r22 r122  
    2424class HdsX8 : public Uav {
    2525public:
    26   HdsX8(core::FrameworkManager *parent, std::string uav_name,
     26  HdsX8(std::string name,
    2727        filter::UavMultiplex *multiplex = NULL);
    2828  ~HdsX8();
    2929  void StartSensors(void);
     30        std::string GetDefaultVrpnAddress(void) const{return "192.168.147.197:3883";}
    3031
    3132private:
  • trunk/lib/FlairMeta/src/MetaVrpnObject.cpp

    r15 r122  
    3939namespace meta {
    4040
    41 MetaVrpnObject::MetaVrpnObject(const VrpnClient *parent, string name)
    42     : VrpnObject(parent, name, parent->GetTabWidget()) {
    43   ConstructorCommon(parent, name);
     41MetaVrpnObject::MetaVrpnObject(string name)
     42    : VrpnObject( name, GetVrpnClient()->GetTabWidget()) {
     43  ConstructorCommon(name);
    4444}
    4545
    46 MetaVrpnObject::MetaVrpnObject(const VrpnClient *parent, std::string name,
     46MetaVrpnObject::MetaVrpnObject(std::string name,
    4747                               uint8_t id)
    48     : VrpnObject(parent, name, id, parent->GetTabWidget()) {
    49   ConstructorCommon(parent, name);
     48    : VrpnObject(name, id, GetVrpnClient()->GetTabWidget()) {
     49  ConstructorCommon( name);
    5050}
    5151
    52 void MetaVrpnObject::ConstructorCommon(const VrpnClient *parent, string name) {
     52void MetaVrpnObject::ConstructorCommon(string name) {
    5353  cvmatrix_descriptor *desc = new cvmatrix_descriptor(6, 1);
    5454  for (int i = 0; i < 6; i++) {
     
    6060  }
    6161
    62   pbas = new LowPassFilter(this, parent->GetLayout()->NewRow(),
     62  pbas = new LowPassFilter(this, GetVrpnClient()->GetLayout()->NewRow(),
    6363                           name + " Passe bas", prev_value);
    6464
     
    7272  }
    7373
    74   euler = new EulerDerivative(pbas, parent->GetLayout()->NewRow(),
     74  euler = new EulerDerivative(pbas, GetVrpnClient()->GetLayout()->NewRow(),
    7575                              name + "_euler", prev_value);
    7676
     
    8282  vz_opti_plot->AddCurve(euler->Matrix()->Element(5));
    8383
    84   plot_tab = new Tab(parent->GetTabWidget(), "Mesures (xy) " + name);
     84  plot_tab = new Tab(GetVrpnClient()->GetTabWidget(), "Mesures (xy) " + name);
    8585  xy_plot = new DataPlot2D(plot_tab->NewRow(), "xy", "y", -5, 5, "x", -5, 5);
    8686  xy_plot->AddCurve(Output()->Element(4, 0), Output()->Element(3, 0));
  • trunk/lib/FlairMeta/src/MetaVrpnObject.h

    r15 r122  
    1818
    1919namespace 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        }
    3633}
    3734
     
    4744class MetaVrpnObject : public sensor::VrpnObject {
    4845public:
    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);
    5248  ~MetaVrpnObject();
    5349  gui::DataPlot1D *VxPlot(void) const; // 1,0
     
    5854
    5955private:
    60   void ConstructorCommon(const sensor::VrpnClient *parent, std::string name);
     56  void ConstructorCommon(std::string name);
    6157  filter::LowPassFilter *pbas;
    6258  filter::EulerDerivative *euler;
  • trunk/lib/FlairMeta/src/SimuX4.cpp

    r22 r122  
    3737namespace meta {
    3838
    39 SimuX4::SimuX4(FrameworkManager *parent, string uav_name, int simu_id,
     39SimuX4::SimuX4(string name, int simu_id,
    4040               filter::UavMultiplex *multiplex)
    41     : Uav(parent, uav_name, multiplex) {
     41    : Uav(name, multiplex) {
    4242
    4343  if (multiplex == NULL)
    44     SetMultiplex(new X4X8Multiplex(parent, "motors", X4X8Multiplex::X4));
     44    SetMultiplex(new X4X8Multiplex(getFrameworkManager(), "motors", X4X8Multiplex::X4));
    4545
    4646  SetBldc(new SimuBldc(GetUavMultiplex(), GetUavMultiplex()->GetLayout(),
    4747                       "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");
    5151  SetBatteryMonitor(new BatteryMonitor(bat_tab->NewRow(), "battery"));
    5252  GetBatteryMonitor()->SetBatteryValue(12);
    5353  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));
    5555}
    5656
     
    6161  ((SimuUs *)GetUsRangeFinder())->Start();
    6262  ((SimuCamera *)GetVerticalCamera())->Start();
    63   Uav::StartSensors();
    6463}
    65 
    66 void SimuX4::SetupVRPNAutoIP(string name) { SetupVRPN("127.0.0.1:3883", name); }
    6764
    6865} // end namespace meta
  • trunk/lib/FlairMeta/src/SimuX4.h

    r22 r122  
    2626  // simu_id: 0 if simulating only one UAV
    2727  //>0 otherwise
    28   SimuX4(core::FrameworkManager *parent, std::string uav_name, int simu_id = 0,
     28  SimuX4(std::string name, int simu_id = 0,
    2929         filter::UavMultiplex *multiplex = NULL);
    3030  ~SimuX4();
    3131  void StartSensors(void);
    32   void SetupVRPNAutoIP(std::string name);
    3332};
    3433} // end namespace meta
  • trunk/lib/FlairMeta/src/SimuX8.cpp

    r22 r122  
    3737namespace meta {
    3838
    39 SimuX8::SimuX8(FrameworkManager *parent, string uav_name, int simu_id,
     39SimuX8::SimuX8(string name, int simu_id,
    4040               filter::UavMultiplex *multiplex)
    41     : Uav(parent, uav_name, multiplex) {
     41    : Uav(name, multiplex) {
    4242
    4343  if (multiplex == NULL)
    44     SetMultiplex(new X4X8Multiplex(parent, "motors", X4X8Multiplex::X8));
     44    SetMultiplex(new X4X8Multiplex(getFrameworkManager(), "motors", X4X8Multiplex::X8));
    4545
    4646  SetBldc(new SimuBldc(GetUavMultiplex(), GetUavMultiplex()->GetLayout(),
    4747                       "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");
    5151  SetBatteryMonitor(new BatteryMonitor(bat_tab->NewRow(), "battery"));
    5252  GetBatteryMonitor()->SetBatteryValue(12);
    5353  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));
    5555}
    5656
     
    6161  ((SimuUs *)GetUsRangeFinder())->Start();
    6262  ((SimuCamera *)GetVerticalCamera())->Start();
    63   Uav::StartSensors();
    6463}
    65 
    66 void SimuX8::SetupVRPNAutoIP(string name) { SetupVRPN("127.0.0.1:3883", name); }
    6764
    6865} // end namespace meta
  • trunk/lib/FlairMeta/src/SimuX8.h

    r22 r122  
    2626  // simu_id: 0 if simulating only one UAV
    2727  //>0 otherwise
    28   SimuX8(core::FrameworkManager *parent, std::string uav_name, int simu_id = 0,
     28  SimuX8(std::string name, int simu_id = 0,
    2929         filter::UavMultiplex *multiplex = NULL);
    3030  ~SimuX8();
    3131  void StartSensors(void);
    32   void SetupVRPNAutoIP(std::string name);
    3332};
    3433} // end namespace meta
  • trunk/lib/FlairMeta/src/Uav.cpp

    r121 r122  
    3838using namespace flair::actuator;
    3939
     40namespace {
     41  flair::meta::Uav *uavSingleton = NULL;
     42}
     43
    4044namespace flair {
    4145namespace meta {
    4246
    43 Uav::Uav(FrameworkManager *parent, string name, UavMultiplex *multiplex)
    44     : Object(parent, name) {
    45   vrpnclient = NULL;
    46   uav_vrpn = NULL;
     47Uav *GetUav(void) { return uavSingleton; }
     48       
     49Uav::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;
    4757  verticalCamera = NULL;
    4858  horizontalCamera = NULL;
     
    8292  horizontalCamera = (Camera *)inHorizontalCamera;
    8393}
    84 /*
    85 void Uav::SetupVRPNSerial(SerialPort *vrpn_port,string name,int
    86 VRPNSerialObjectId) {
    87     vrpnclient=new VrpnClient(getFrameworkManager(),"vrpn",vrpn_port,10000,80);
    88     uav_vrpn=new MetaVrpnObject(vrpnclient,name,VRPNSerialObjectId);
    8994
    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 }
    11595void Uav::UseDefaultPlot(void) {
    11696  multiplex->UseDefaultPlot();
     
    184164BatteryMonitor *Uav::GetBatteryMonitor(void) const { return battery; }
    185165
    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 
    194166Camera *Uav::GetVerticalCamera(void) const { return verticalCamera; }
    195167
  • trunk/lib/FlairMeta/src/Uav.h

    r121 r122  
    1717
    1818namespace flair {
    19 namespace core {
    20 class FrameworkManager;
    21 }
    22 namespace filter {
    23 class Ahrs;
    24 class UavMultiplex;
    25 }
    26 namespace actuator {
    27 class Bldc;
    28 }
    29 namespace sensor {
    30 class UsRangeFinder;
    31 class BatteryMonitor;
    32 class VrpnClient;
    33 class Imu;
    34 class Camera;
    35 }
     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        }
    3632}
    3733
     
    3935namespace meta {
    4036class MetaUsRangeFinder;
    41 class MetaVrpnObject;
    4237
    4338/*! \class Uav
    4439*
    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.
    4644*/
    4745class Uav : public core::Object {
    4846public:
    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,
    6049      filter::UavMultiplex *multiplex = NULL);
    6150  ~Uav();
    62   void SetupVRPN(std::string optitrack_address, std::string name);
    63   // vrpn serial: broken, need to add serial port in uav specific code
    64   // void SetupVRPNSerial(core::SerialPort *vrpn_port,std::string name,int
    65   // VRPNSerialObjectId);
    66   virtual void SetupVRPNAutoIP(std::string name);
    6751
    68   virtual void StartSensors(void);
     52  virtual void StartSensors(void)=0;
    6953  void UseDefaultPlot(void);
    7054  actuator::Bldc *GetBldc(void) const;
     
    7559  sensor::UsRangeFinder *GetUsRangeFinder(void) const;
    7660  sensor::BatteryMonitor *GetBatteryMonitor(void) const;
    77   sensor::VrpnClient *GetVrpnClient(void) const;
    78   meta::MetaVrpnObject *GetVrpnObject(void) const;
    7961  sensor::Camera *GetVerticalCamera(void) const;
    8062  sensor::Camera *GetHorizontalCamera(void) const;
     63        virtual std::string GetDefaultVrpnAddress(void) const{return "127.0.0.1:3883";}
    8164
    8265protected:
     
    9679  sensor::UsRangeFinder *us;
    9780  MetaUsRangeFinder *meta_us;
    98   sensor::VrpnClient *vrpnclient;
    99   MetaVrpnObject *uav_vrpn;
    10081  sensor::BatteryMonitor *battery;
    10182  sensor::Camera *verticalCamera,*horizontalCamera;
    10283};
     84
     85/*!
     86* \brief get Uav
     87*
     88* \return the Uav
     89*/
     90Uav *GetUav(void);
     91
    10392} // end namespace meta
    10493} // end namespace flair
  • trunk/lib/FlairMeta/src/UavFactory.cpp

    r45 r122  
    3030
    3131namespace { // anonymous
    32      vector<flair::meta::Uav* (*)(FrameworkManager*,string,string,UavMultiplex*)> *vectoroffunctions=NULL;
     32     vector<flair::meta::Uav* (*)(string,string,UavMultiplex*)> *vectoroffunctions=NULL;
    3333}
    3434
     
    4141
    4242
    43 Uav *CreateUav(FrameworkManager *parent, string uav_name, string uav_type,
     43Uav *CreateUav(string name, string uav_type,
    4444               UavMultiplex *multiplex) {
    4545
     
    4848  if(vectoroffunctions!=NULL) {
    4949    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);
    5151      if(uav!=NULL) {
    5252        free(vectoroffunctions);
     
    5858
    5959  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());
    6161    return NULL;
    6262  } else if (uav_type == "hds_x8") {
    63     return new HdsX8(parent, uav_name, multiplex);
     63    return new HdsX8(name, multiplex);
    6464  } else if (uav_type == "xair") {
    65     return new XAir(parent, uav_name, multiplex);
     65    return new XAir(name, multiplex);
    6666  } 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());
    6868    return NULL;
    6969  } else if (uav_type.compare(0, 7, "x4_simu") == 0) {
     
    7272      simu_id = atoi(uav_type.substr(7, uav_type.size() - 7).c_str());
    7373    }
    74     return new SimuX4(parent, uav_name, simu_id, multiplex);
     74    return new SimuX4(name, simu_id, multiplex);
    7575  } else if (uav_type.compare(0, 7, "x8_simu") == 0) {
    7676    int simu_id = 0;
     
    7878      simu_id = atoi(uav_type.substr(7, uav_type.size() - 7).c_str());
    7979    }
    80     return new SimuX8(parent, uav_name, simu_id, multiplex);
     80    return new SimuX8(name, simu_id, multiplex);
    8181  } 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());
    8383    return NULL;
    8484  }
    8585}
    8686
    87 void RegisterUavCreator(flair::meta::Uav*(*func)(FrameworkManager *parent, string uav_name, string uav_type,
     87void RegisterUavCreator(flair::meta::Uav*(*func)(string name, string type,
    8888               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*)>));
    9090
    9191  vectoroffunctions->push_back(func);
  • trunk/lib/FlairMeta/src/UavFactory.h

    r41 r122  
    2121#include <Uav.h>
    2222
    23 flair::meta::Uav *CreateUav(flair::core::FrameworkManager *parent,
    24                             std::string uav_name, std::string uav_type,
     23flair::meta::Uav *CreateUav(std::string name, std::string type,
    2524                            flair::filter::UavMultiplex *multiplex = NULL);
    2625
    27 void RegisterUavCreator(flair::meta::Uav*(*func)(flair::core::FrameworkManager *parent,
    28                                    std::string uav_name, std::string uav_type,
     26void RegisterUavCreator(flair::meta::Uav*(*func)(std::string name, std::string type,
    2927                                   flair::filter::UavMultiplex *multiplex));
    3028#endif // UAVFACTORY
  • trunk/lib/FlairMeta/src/UavStateMachine.cpp

    r106 r122  
    5252using namespace flair::meta;
    5353
    54 UavStateMachine::UavStateMachine(Uav* inUav,TargetController *controller):
     54UavStateMachine::UavStateMachine(TargetController *controller):
    5555        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){
    5757    altitudeState=AltitudeState_t::Stopped;
    5858    uav->UseDefaultPlot();
     
    135135  return currentAngularSpeed;
    136136}
    137 
    138 const Uav *UavStateMachine::GetUav(void) const { return uav; }
    139137
    140138void UavStateMachine::AltitudeValues(float &altitude,
  • trunk/lib/FlairMeta/src/UavStateMachine.h

    r45 r122  
    5959*
    6060* \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
    6465*/
    6566
     
    101102  };
    102103
    103         UavStateMachine(meta::Uav* uav, sensor::TargetController* controller);
     104        UavStateMachine(sensor::TargetController* controller);
    104105        ~UavStateMachine();
    105106
     
    107108
    108109  const core::Vector3D &GetCurrentAngularSpeed(void) const;
    109 
    110   const meta::Uav *GetUav(void) const;
    111110
    112111        void Land(void);
  • trunk/lib/FlairMeta/src/XAir.cpp

    r100 r122  
    3838namespace meta {
    3939
    40 XAir::XAir(FrameworkManager *parent, string uav_name,
     40XAir::XAir(string name,
    4141           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");
    4545
    4646  if (multiplex == NULL)
    47     SetMultiplex(new X4X8Multiplex(parent, "motors", X4X8Multiplex::X8));
     47    SetMultiplex(new X4X8Multiplex(getFrameworkManager(), "motors", X4X8Multiplex::X8));
    4848
    4949  SetBldc(new AfroBldc(GetUavMultiplex(), GetUavMultiplex()->GetLayout(),
    5050                       "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,
    5353                          Gx3_25_imu::AccelerationAngularRateAndOrientationMatrix, 70));
    54   Tab *bat_tab = new Tab(parent->GetTabWidget(), "battery");
     54  Tab *bat_tab = new Tab(getFrameworkManager()->GetTabWidget(), "battery");
    5555  SetBatteryMonitor(new BatteryMonitor(bat_tab->NewRow(), "battery"));
    5656  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));
    7058}
    7159
     
    7664  ((Srf08 *)GetUsRangeFinder())->Start();
    7765  ((Ps3Eye *)GetVerticalCamera())->Start();
    78   Uav::StartSensors();
    7966}
    8067
  • trunk/lib/FlairMeta/src/XAir.h

    r22 r122  
    2424class XAir : public Uav {
    2525public:
    26   XAir(core::FrameworkManager *parent, std::string uav_name,
     26  XAir(std::string name,
    2727       filter::UavMultiplex *multiplex = NULL);
    2828  ~XAir();
    2929  void StartSensors(void);
     30        std::string GetDefaultVrpnAddress(void) const{return "192.168.147.197:3883";}
    3031
    3132private:
Note: See TracChangeset for help on using the changeset viewer.