Changeset 122 in flair-src


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

modifs uav vrpn i686

Location:
trunk
Files:
50 added
15 deleted
50 edited

Legend:

Unmodified
Added
Removed
  • trunk/ReleaseNotes

    r121 r122  
    33- added fixed cameras in simulator, see $FLAIR_ROOT/flair-bin/models/indoor_fligh
    44t_arena.xml for an exemple
     5- added lib/FlairVisionFilter: some basic vision algorithms using opencv. Note that this lib can be remplaced by HdsVisionFilter if you have access to it, in order to use the DSP in HDS UAV's.
     6See also https://devel.hds.utc.fr/software/flair/wiki/hds_users
     7- added demos/OpticalFlow: stabilization using optical flow (vertical camera)
     8- Uav class is now a singleton
     9- VrpnClient class is now a singleton
    510
    611-----------------------------------------------------------
  • trunk/demos/CircleFollower/uav/src/CircleFollower.cpp

    r121 r122  
    3939using namespace flair::meta;
    4040
    41 CircleFollower::CircleFollower(Uav* uav,TargetController *controller): UavStateMachine(uav,controller), behaviourMode(BehaviourMode_t::Default), vrpnLost(false) {
    42     uav->SetupVRPNAutoIP(uav->ObjectName());
    43 
     41CircleFollower::CircleFollower(TargetController *controller): UavStateMachine(controller), behaviourMode(BehaviourMode_t::Default), vrpnLost(false) {
     42    Uav* uav=GetUav();
     43               
     44                VrpnClient* vrpnclient=new VrpnClient("vrpn", uav->GetDefaultVrpnAddress(),10000, 80);
     45                uavVrpn = new MetaVrpnObject(uav->ObjectName());
     46                getFrameworkManager()->AddDeviceToLog(uavVrpn);
     47                uav->GetAhrs()->YawPlot()->AddCurve(uavVrpn->State()->Element(2),DataPlot::Green);
     48                                                                                                                                 
    4449    startCircle=new PushButton(GetButtonsLayout()->NewRow(),"start_circle");
    4550    stopCircle=new PushButton(GetButtonsLayout()->LastRowLastCol(),"stop_circle");
    4651
    47     if(uav->GetVrpnClient()->UseXbee()==true) {
    48         targetVrpn=new MetaVrpnObject(uav->GetVrpnClient(),"target",1);
     52    if(vrpnclient->UseXbee()==true) {
     53        targetVrpn=new MetaVrpnObject("target",1);
    4954    } else {
    50         targetVrpn=new MetaVrpnObject(uav->GetVrpnClient(),"target");
     55        targetVrpn=new MetaVrpnObject("target");
    5156    }
    5257
    5358    getFrameworkManager()->AddDeviceToLog(targetVrpn);
    5459
    55     circle=new TrajectoryGenerator2DCircle(uav->GetVrpnClient()->GetLayout()->NewRow(),"circle");
    56     uav->GetVrpnObject()->xPlot()->AddCurve(circle->Matrix()->Element(0,0),DataPlot::Blue);
    57     uav->GetVrpnObject()->yPlot()->AddCurve(circle->Matrix()->Element(0,1),DataPlot::Blue);
    58     uav->GetVrpnObject()->VxPlot()->AddCurve(circle->Matrix()->Element(1,0),DataPlot::Blue);
    59     uav->GetVrpnObject()->VyPlot()->AddCurve(circle->Matrix()->Element(1,1),DataPlot::Blue);
    60     uav->GetVrpnObject()->XyPlot()->AddCurve(circle->Matrix()->Element(0,1),circle->Matrix()->Element(0,0),DataPlot::Blue,"circle");
     60    circle=new TrajectoryGenerator2DCircle(vrpnclient->GetLayout()->NewRow(),"circle");
     61    uavVrpn->xPlot()->AddCurve(circle->Matrix()->Element(0,0),DataPlot::Blue);
     62    uavVrpn->yPlot()->AddCurve(circle->Matrix()->Element(0,1),DataPlot::Blue);
     63    uavVrpn->VxPlot()->AddCurve(circle->Matrix()->Element(1,0),DataPlot::Blue);
     64    uavVrpn->VyPlot()->AddCurve(circle->Matrix()->Element(1,1),DataPlot::Blue);
     65    uavVrpn->XyPlot()->AddCurve(circle->Matrix()->Element(0,1),circle->Matrix()->Element(0,0),DataPlot::Blue,"circle");
    6166
    6267    uX=new Pid(setupLawTab->At(1,0),"u_x");
     
    7984    //get yaw from vrpn
    8085    Euler vrpnEuler;
    81     GetUav()->GetVrpnObject()->GetEuler(vrpnEuler);
     86    uavVrpn->GetEuler(vrpnEuler);
    8287
    8388    //get roll, pitch and w from imu
     
    98103    Vector3D uav_pos,uav_vel;
    99104
    100     GetUav()->GetVrpnObject()->GetPosition(uav_pos);
    101     GetUav()->GetVrpnObject()->GetSpeed(uav_vel);
     105    uavVrpn->GetPosition(uav_pos);
     106    uavVrpn->GetSpeed(uav_vel);
    102107    //z and dz must be in uav's frame
    103108    z=-uav_pos.z;
     
    131136    Vector2D uav_2Dpos,uav_2Dvel; // in VRPN coordinate system
    132137
    133     GetUav()->GetVrpnObject()->GetPosition(uav_pos);
    134     GetUav()->GetVrpnObject()->GetSpeed(uav_vel);
     138    uavVrpn->GetPosition(uav_pos);
     139    uavVrpn->GetSpeed(uav_vel);
    135140
    136141    uav_pos.To2Dxy(uav_2Dpos);
     
    195200            Land();
    196201        }
    197         if (!GetUav()->GetVrpnObject()->IsTracked(500)) {
     202        if (!uavVrpn->IsTracked(500)) {
    198203            Thread::Err("VRPN, uav lost\n");
    199204            vrpnLost=true;
     
    239244    circle->SetCenter(target_2Dpos);
    240245
    241     GetUav()->GetVrpnObject()->GetPosition(uav_pos);
     246    uavVrpn->GetPosition(uav_pos);
    242247    uav_pos.To2Dxy(uav_2Dpos);
    243248    circle->StartTraj(uav_2Dpos);
     
    258263    Vector3D vrpn_pos;
    259264
    260     GetUav()->GetVrpnObject()->GetEuler(vrpn_euler);
     265    uavVrpn->GetEuler(vrpn_euler);
    261266    yawHold=vrpn_euler.yaw;
    262267
    263     GetUav()->GetVrpnObject()->GetPosition(vrpn_pos);
     268    uavVrpn->GetPosition(vrpn_pos);
    264269    vrpn_pos.To2Dxy(posHold);
    265270
  • trunk/demos/CircleFollower/uav/src/CircleFollower.h

    r38 r122  
    3434class CircleFollower : public flair::meta::UavStateMachine {
    3535    public:
    36         CircleFollower(flair::meta::Uav* uav,flair::sensor::TargetController *controller);
     36        CircleFollower(flair::sensor::TargetController *controller);
    3737        ~CircleFollower();
    3838
     
    6565
    6666        flair::gui::PushButton *startCircle,*stopCircle;
    67         flair::meta::MetaVrpnObject *targetVrpn;
     67        flair::meta::MetaVrpnObject *targetVrpn,*uavVrpn;
    6868        flair::filter::TrajectoryGenerator2DCircle *circle;
    6969        flair::core::AhrsData *customReferenceOrientation,*customOrientation;
  • trunk/demos/CircleFollower/uav/src/main.cpp

    r38 r122  
    4545    manager->SetupLogger(log_path);
    4646
    47     Uav* drone=CreateUav(manager,name,uav_type);
     47    Uav* drone=CreateUav(name,uav_type);
    4848    TargetEthController *controller=new TargetEthController(manager,"Dualshock3",ds3port);
    49     CircleFollower* demo=new CircleFollower(drone,controller);
     49    CircleFollower* demo=new CircleFollower(controller);
    5050
    5151    demo->Start();
  • trunk/demos/Gps/uav/CMakeLists.txt

    r89 r122  
    66SET(FLAIR_USE_SENSOR_ACTUATOR TRUE)
    77SET(FLAIR_USE_META TRUE)
    8 SET(FLAIR_USE_VRPN TRUE)
    98SET(FLAIR_USE_GPS TRUE)
    109
  • trunk/demos/Gps/uav/src/DemoGps.cpp

    r101 r122  
    3939using namespace flair::meta;
    4040
    41 DemoGps::DemoGps(Uav* uav,TargetController *controller): UavStateMachine(uav,controller), behaviourMode(BehaviourMode_t::Default) {
    42 
     41DemoGps::DemoGps(TargetController *controller): UavStateMachine(controller), behaviourMode(BehaviourMode_t::Default) {
     42                Uav* uav=GetUav();
    4343    startCircle=new PushButton(GetButtonsLayout()->NewRow(),"start_circle");
    4444    stopCircle=new PushButton(GetButtonsLayout()->LastRowLastCol(),"stop_circle");
  • trunk/demos/Gps/uav/src/DemoGps.h

    r89 r122  
    3333class DemoGps : public flair::meta::UavStateMachine {
    3434    public:
    35         DemoGps(flair::meta::Uav* uav,flair::sensor::TargetController *controller);
     35        DemoGps(flair::sensor::TargetController *controller);
    3636        ~DemoGps();
    3737
  • trunk/demos/Gps/uav/src/main.cpp

    r89 r122  
    4545    manager->SetupLogger(log_path);
    4646
    47     Uav* drone=CreateUav(manager,name,uav_type);
     47    Uav* drone=CreateUav(name,uav_type);
    4848    TargetEthController *controller=new TargetEthController(manager,"Dualshock3",ds3port);
    49     DemoGps* demo=new DemoGps(drone,controller);
     49    DemoGps* demo=new DemoGps(controller);
    5050
    5151    demo->Start();
  • trunk/demos/SimpleFleet/uav/src/SimpleFleet.cpp

    r104 r122  
    5050
    5151
    52 SimpleFleet::SimpleFleet(flair::meta::Uav* uav,string broadcast,TargetController *controller): UavStateMachine(uav,controller), behaviourMode(BehaviourMode_t::Default), vrpnLost(false) {
    53     uav->SetupVRPNAutoIP(uav->ObjectName());
    54 
    55     circle=new TrajectoryGenerator2DCircle(uav->GetVrpnClient()->GetLayout()->NewRow(),"circle");
    56     uav->GetVrpnObject()->xPlot()->AddCurve(circle->Matrix()->Element(0,0),0,0,255);
    57     uav->GetVrpnObject()->yPlot()->AddCurve(circle->Matrix()->Element(0,1),0,0,255);
    58     uav->GetVrpnObject()->VxPlot()->AddCurve(circle->Matrix()->Element(1,0),0,0,255);
    59     uav->GetVrpnObject()->VyPlot()->AddCurve(circle->Matrix()->Element(1,1),0,0,255);
    60 
    61     xCircleCenter=new DoubleSpinBox(uav->GetVrpnClient()->GetLayout()->NewRow(),"x circle center"," m",-5,5,0.1,1,0);
    62     yCircleCenter=new DoubleSpinBox(uav->GetVrpnClient()->GetLayout()->NewRow(),"y circle center"," m",-5,5,0.1,1,0);
    63     yDisplacement=new DoubleSpinBox(uav->GetVrpnClient()->GetLayout()->NewRow(),"y displacement"," m",0,2,0.1,1,0);
     52SimpleFleet::SimpleFleet(string broadcast,TargetController *controller): UavStateMachine(controller), behaviourMode(BehaviourMode_t::Default), vrpnLost(false) {
     53    Uav* uav=GetUav();
     54               
     55                VrpnClient* vrpnclient=new VrpnClient("vrpn", uav->GetDefaultVrpnAddress(),10000, 80);
     56                uavVrpn = new MetaVrpnObject(uav->ObjectName());
     57                getFrameworkManager()->AddDeviceToLog(uavVrpn);
     58                uav->GetAhrs()->YawPlot()->AddCurve(uavVrpn->State()->Element(2),DataPlot::Green);
     59
     60    circle=new TrajectoryGenerator2DCircle(vrpnclient->GetLayout()->NewRow(),"circle");
     61    uavVrpn->xPlot()->AddCurve(circle->Matrix()->Element(0,0),0,0,255);
     62    uavVrpn->yPlot()->AddCurve(circle->Matrix()->Element(0,1),0,0,255);
     63    uavVrpn->VxPlot()->AddCurve(circle->Matrix()->Element(1,0),0,0,255);
     64    uavVrpn->VyPlot()->AddCurve(circle->Matrix()->Element(1,1),0,0,255);
     65
     66    xCircleCenter=new DoubleSpinBox(vrpnclient->GetLayout()->NewRow(),"x circle center"," m",-5,5,0.1,1,0);
     67    yCircleCenter=new DoubleSpinBox(vrpnclient->GetLayout()->NewRow(),"y circle center"," m",-5,5,0.1,1,0);
     68    yDisplacement=new DoubleSpinBox(vrpnclient->GetLayout()->NewRow(),"y displacement"," m",0,2,0.1,1,0);
    6469
    6570    //parent->AddDeviceToLog(Uz());
     
    101106    //get yaw from vrpn
    102107    Euler vrpnEuler;
    103     GetUav()->GetVrpnObject()->GetEuler(vrpnEuler);
     108    uavVrpn->GetEuler(vrpnEuler);
    104109
    105110    //get roll, pitch and w from imu
     
    120125    Vector3D uav_pos,uav_vel;
    121126
    122     GetUav()->GetVrpnObject()->GetPosition(uav_pos);
    123     GetUav()->GetVrpnObject()->GetSpeed(uav_vel);
     127    uavVrpn->GetPosition(uav_pos);
     128    uavVrpn->GetSpeed(uav_vel);
    124129    //z and dz must be in uav's frame
    125130    z=-uav_pos.z;
     
    154159    Euler vrpn_euler; // in VRPN coordinate system
    155160
    156     GetUav()->GetVrpnObject()->GetPosition(uav_pos);
    157     GetUav()->GetVrpnObject()->GetSpeed(uav_vel);
    158     GetUav()->GetVrpnObject()->GetEuler(vrpn_euler);
     161    uavVrpn->GetPosition(uav_pos);
     162    uavVrpn->GetSpeed(uav_vel);
     163    uavVrpn->GetEuler(vrpn_euler);
    159164
    160165    uav_pos.To2Dxy(uav_2Dpos);
     
    294299void SimpleFleet::ExtraSecurityCheck(void) {
    295300    if (!vrpnLost && behaviourMode!=BehaviourMode_t::Default) {
    296         if (!GetUav()->GetVrpnObject()->IsTracked(500)) {
     301        if (!uavVrpn->IsTracked(500)) {
    297302            Thread::Err("Optitrack, uav lost\n");
    298303            vrpnLost=true;
     
    322327    circle->SetCenter(target_2Dpos);
    323328
    324     GetUav()->GetVrpnObject()->GetPosition(uav_pos);
     329    uavVrpn->GetPosition(uav_pos);
    325330    uav_pos.To2Dxy(uav_2Dpos);
    326331    circle->StartTraj(uav_2Dpos,1);
     
    347352    }
    348353
    349     GetUav()->GetVrpnObject()->GetEuler(vrpn_euler);
     354    uavVrpn->GetEuler(vrpn_euler);
    350355    yaw_hold=vrpn_euler.yaw;
    351356
    352     GetUav()->GetVrpnObject()->GetPosition(vrpn_pos);
     357    uavVrpn->GetPosition(vrpn_pos);
    353358    vrpn_pos.To2Dxy(pos_hold);
    354359
  • trunk/demos/SimpleFleet/uav/src/SimpleFleet.h

    r38 r122  
    2626        class TrajectoryGenerator2DCircle;
    2727    }
     28                namespace meta {
     29        class MetaVrpnObject;
     30    }
    2831    namespace gui {
    2932        class DoubleSpinBox;
     
    3437class SimpleFleet : public flair::meta::UavStateMachine {
    3538    public:
    36         SimpleFleet(flair::meta::Uav* uav,std::string broadcast,flair::sensor::TargetController *controller);
     39        SimpleFleet(std::string broadcast,flair::sensor::TargetController *controller);
    3740        ~SimpleFleet();
    3841
     
    7578        flair::gui::DoubleSpinBox *xCircleCenter,*yCircleCenter,*yDisplacement;
    7679        flair::core::AhrsData *customReferenceOrientation,*customOrientation;
     80                                flair::meta::MetaVrpnObject *uavVrpn;
    7781};
    7882
  • trunk/demos/SimpleFleet/uav/src/main.cpp

    r38 r122  
    4646    manager->SetupUserInterface(xml_file);
    4747
    48     Uav* drone=CreateUav(manager,name,uav_type);
     48    Uav* drone=CreateUav(name,uav_type);
    4949    TargetEthController *controller=new TargetEthController(manager,"Dualshock3",ds3port);
    50     SimpleFleet* demo=new SimpleFleet(drone,broadcast,controller);
     50    SimpleFleet* demo=new SimpleFleet(broadcast,controller);
    5151
    5252    demo->Start();
  • trunk/demos/Skeletons/CustomReferenceAngles/CMakeLists.txt

    r43 r122  
    66SET(FLAIR_USE_SENSOR_ACTUATOR TRUE)
    77SET(FLAIR_USE_META TRUE)
    8 SET(FLAIR_USE_VRPN TRUE)
    98
    109include($ENV{FLAIR_ROOT}/flair-dev/cmake-modules/GlobalCmakeFlair.cmake)
  • trunk/demos/Skeletons/CustomReferenceAngles/src/MyApp.cpp

    r43 r122  
    2929using namespace flair::sensor;
    3030
    31 MyApp::MyApp(Uav* uav,TargetController *controller): UavStateMachine(uav,controller), behaviourMode(BehaviourMode_t::Default) {
     31MyApp::MyApp(TargetController *controller): UavStateMachine(controller), behaviourMode(BehaviourMode_t::Default) {
    3232    start_CustomAngles=new PushButton(GetButtonsLayout()->NewRow(),"start CustomReferenceAngles");
    3333    stop_CustomAngles=new PushButton(GetButtonsLayout()->NewRow(),"stop CustomReferenceAngles");
    3434
    3535    customReferenceOrientation= new AhrsData(this,"reference");
    36     uav->GetAhrs()->AddPlot(customReferenceOrientation,DataPlot::Yellow);
     36    GetUav()->GetAhrs()->AddPlot(customReferenceOrientation,DataPlot::Yellow);
    3737    AddDataToControlLawLog(customReferenceOrientation);
    3838}
  • trunk/demos/Skeletons/CustomReferenceAngles/src/MyApp.h

    r43 r122  
    3131class MyApp : public flair::meta::UavStateMachine {
    3232    public:
    33         MyApp(flair::meta::Uav* uav,flair::sensor::TargetController *controller);
     33        MyApp(flair::sensor::TargetController *controller);
    3434        ~MyApp();
    3535
  • trunk/demos/Skeletons/CustomReferenceAngles/src/main.cpp

    r43 r122  
    4444    manager->SetupLogger(log_path);
    4545
    46     Uav* drone=CreateUav(manager,name,uav_type);
     46    Uav* drone=CreateUav(name,uav_type);
    4747    TargetEthController *controller=new TargetEthController(manager,"Dualshock3",ds3port);
    48     MyApp* app=new MyApp(drone,controller);
     48    MyApp* app=new MyApp(controller);
    4949
    5050    app->Start();
  • trunk/demos/Skeletons/CustomTorques/CMakeLists.txt

    r43 r122  
    66SET(FLAIR_USE_SENSOR_ACTUATOR TRUE)
    77SET(FLAIR_USE_META TRUE)
    8 SET(FLAIR_USE_VRPN TRUE)
    98
    109include($ENV{FLAIR_ROOT}/flair-dev/cmake-modules/GlobalCmakeFlair.cmake)
  • trunk/demos/Skeletons/CustomTorques/src/MyApp.cpp

    r43 r122  
    2626using namespace flair::sensor;
    2727
    28 MyApp::MyApp(Uav* uav,TargetController *controller): UavStateMachine(uav,controller), behaviourMode(BehaviourMode_t::Default) {
     28MyApp::MyApp(TargetController *controller): UavStateMachine(controller), behaviourMode(BehaviourMode_t::Default) {
    2929    start_CustomTorques=new PushButton(GetButtonsLayout()->NewRow(),"start CustomTorques");
    3030    stop_CustomTorques=new PushButton(GetButtonsLayout()->NewRow(),"stop CustomTorques");
  • trunk/demos/Skeletons/CustomTorques/src/MyApp.h

    r43 r122  
    2828class MyApp : public flair::meta::UavStateMachine {
    2929    public:
    30         MyApp(flair::meta::Uav* uav,flair::sensor::TargetController *controller);
     30        MyApp(flair::sensor::TargetController *controller);
    3131        ~MyApp();
    3232
  • trunk/demos/Skeletons/CustomTorques/src/main.cpp

    r43 r122  
    4545    manager->SetupLogger(log_path);
    4646
    47     Uav* drone=CreateUav(manager,name,uav_type);
     47    Uav* drone=CreateUav(name,uav_type);
    4848    TargetEthController *controller=new TargetEthController(manager,"Dualshock3",ds3port);
    49     MyApp* app=new MyApp(drone,controller);
     49    MyApp* app=new MyApp(controller);
    5050
    5151    app->Start();
  • trunk/lib/FlairCore/src/FrameworkManager.cpp

    r55 r122  
    178178}
    179179
     180bool FrameworkManager::IsDeviceLogged(const IODevice *device) const {
     181        return pimpl_->IsDeviceLogged(device);
     182}
     183
    180184void FrameworkManager::StartLog(void) { pimpl_->StartLog(); }
    181185
  • trunk/lib/FlairCore/src/FrameworkManager.h

    r55 r122  
    121121  */
    122122  void AddDeviceToLog(IODevice *device);
     123       
     124        /*!
     125  * \brief Is device logged
     126  *
     127  * Check if AddDeviceToLog was called for an IODevice
     128  *
     129  * \param device IODevice to check
     130  * \return true if AddDeviceToLog was called for this IODevice
     131  */
     132  bool IsDeviceLogged(const IODevice *device) const;
    123133
    124134  /*!
  • trunk/lib/FlairCore/src/FrameworkManager_impl.cpp

    r118 r122  
    630630
    631631  if (is_logging == false) {
    632     if (device->pimpl_->SetToBeLogged()) {
     632    if (!device->pimpl_->IsSetToBeLogged()) {
     633                        device->pimpl_->SetToBeLogged();
    633634      log_desc_t tmp;
    634635      tmp.device = device;
     
    640641    Err("impossible while logging\n");
    641642  }
     643}
     644
     645bool FrameworkManager_impl::IsDeviceLogged(const IODevice *device) const {
     646        return device->pimpl_->IsSetToBeLogged();
    642647}
    643648
  • trunk/lib/FlairCore/src/IODevice_impl.cpp

    r15 r122  
    106106}
    107107
    108 bool IODevice_impl::SetToBeLogged(void) {
     108bool IODevice_impl::IsSetToBeLogged(void) const{
     109        return tobelogged;
     110}
     111
     112void IODevice_impl::SetToBeLogged(void) {
    109113  if (!tobelogged) {
    110114    tobelogged = true;
    111     return true;
    112115  } else {
    113116    self->Warn("already added to log\n");
    114     return false;
    115117  }
    116118}
    117119
    118120void IODevice_impl::WriteLogsDescriptors(fstream &desc_file, int *index) {
    119   // own descriptor
     121  //Printf("WriteLogsDescriptors %s\n",self->ObjectName().c_str());
     122        // own descriptor
    120123  for (size_t i = 0; i < datasToLog.size(); i++)
    121124    datasToLog.at(i)->pimpl_->WriteLogDescriptor(desc_file, index);
     
    127130  for (size_t i = 0; i < devicesToLog.size(); i++)
    128131    devicesToLog.at(i)->pimpl_->WriteLogsDescriptors(desc_file, index);
     132        //Printf("WriteLogsDescriptors %s ok\n",self->ObjectName().c_str());
    129133}
    130134
     
    194198
    195199void IODevice_impl::AppendLog(char **ptr) {
    196   // Printf("AppendLog %s %x\n",self->ObjectName().c_str(),*ptr);
     200   //Printf("AppendLog %s %x\n",self->ObjectName().c_str(),*ptr);
    197201
    198202  // copy state to buf
    199203  for (size_t i = 0; i < datasToLog.size(); i++) {
    200     // printf("copy\n");
     204    // printf("copy %s\n",datasToLog.at(i)->ObjectName().c_str());
    201205    datasToLog.at(i)->CopyDatas(*ptr);
    202206    (*ptr) += datasToLog.at(i)->GetDataType().GetSize();
  • trunk/lib/FlairCore/src/io_data_impl.cpp

    r15 r122  
    4242
    4343void io_data_impl::WriteLogDescriptor(std::fstream &desc_file, int *index) {
     44        if(descriptors.size()==0) self->Warn("AppendLogDescription was not called for this object.\n");
    4445  for (size_t i = 0; i < descriptors.size(); i++) {
    4546    desc_file << (*index)++ << ": " << self->ObjectName() << " - "
  • trunk/lib/FlairCore/src/unexported/FrameworkManager_impl.h

    r55 r122  
    4848  void SetupLogger(std::string log_path);
    4949  void AddDeviceToLog(flair::core::IODevice *device);
     50        bool IsDeviceLogged(const flair::core::IODevice *device) const;
    5051  void StartLog();
    5152  void StopLog();
  • trunk/lib/FlairCore/src/unexported/IODevice_impl.h

    r15 r122  
    4242  void WriteLog(flair::core::Time time);
    4343  void AddDeviceToLog(const flair::core::IODevice *device);
    44   bool SetToBeLogged(void); // return true if possible
     44  void SetToBeLogged(void);
     45        bool IsSetToBeLogged(void) const;
    4546  void OutputToShMem(bool enabled);
    4647  void WriteToShMem(void);
  • 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:
  • trunk/lib/FlairSensorActuator/src/Camera.cpp

    r121 r122  
    2424#include <DataPlot1D.h>
    2525#include <Picture.h>
    26 #include <Buffer.h>
    2726#include <highgui.h>
    2827#include <fstream>
     
    3938    : IODevice(parent, name) {
    4039  plot_tab = NULL;
    41         jpgBuffer=NULL;
    4240        logFormat=LogFormat::NONE;
    4341
     
    6361
    6462  output = NULL;
    65         jpgBuffer=NULL;
    6663        logFormat=LogFormat::NONE;
    6764}
     
    8077                        break;
    8178                case LogFormat::JPG:
    82                         if(jpgBuffer==NULL) {
    83                                 jpgBuffer=new Buffer(this,"jpg_bufer");
    84                                 AddDataToLog(jpgBuffer);
    85                         }else{
    86                                 Warn("log format already defined\n");
    87                         }
     79                                Warn("logging cvimage to jpeg\n");
     80                                Warn("jpeg are not included in classical dbt file, as dbt does not handle variable length\n");
    8881                        break;
     82                default:
     83                        Warn("LogFormat unknown\n");
    8984        }
    9085}
     
    119114
    120115void Camera::ProcessUpdate(core::io_data* data) {
    121         switch(logFormat) {
    122                 case LogFormat::JPG:
    123                                 ajouter compression jpg
    124                         break;
     116        if(getFrameworkManager()->IsLogging() && getFrameworkManager()->IsDeviceLogged(this)) {
     117                switch(logFormat) {
     118                        case LogFormat::JPG:
     119                                        IplImage *img=((cvimage*)data)->img;
     120                                        //dspSaveToJpeg(img,"toto");
     121                                break;
     122                }
    125123        }
    126124        IODevice::ProcessUpdate(data);
  • trunk/lib/FlairSensorActuator/src/Camera.h

    r121 r122  
    2525                class Picture;
    2626                class GridLayout;
    27         }
    28         namespace core {
    29                 class Buffer;
    3027        }
    3128}
     
    163160  gui::GridLayout *setup_layout;
    164161        LogFormat logFormat;
    165         core::Buffer *jpgBuffer;
    166162};
    167163} // end namespace sensor
  • trunk/lib/FlairSensorActuator/src/VrpnClient.cpp

    r15 r122  
    2626using namespace flair::gui;
    2727
     28namespace {
     29  flair::sensor::VrpnClient *singleton = NULL;
     30}
     31
     32
    2833namespace flair {
    2934namespace sensor {
    3035
    31 VrpnClient::VrpnClient(const FrameworkManager *parent, string name,
     36VrpnClient *GetVrpnClient(void) { return singleton; }
     37       
     38VrpnClient::VrpnClient(string name,
    3239                       string address, uint16_t us_period, uint8_t priority)
    33     : Thread(parent, name, priority) {
     40    : Thread(getFrameworkManager(), name, priority) {
     41        if (singleton != NULL) {
     42    Err("VrpnClient must be instanced only one time\n");
     43    return;
     44  }
     45
     46  singleton = this;
    3447  pimpl_ = new VrpnClient_impl(this, name, address, us_period);
    3548}
    3649
    37 VrpnClient::VrpnClient(const FrameworkManager *parent, string name,
     50VrpnClient::VrpnClient(string name,
    3851                       SerialPort *serialport, uint16_t us_period,
    3952                       uint8_t priority)
    40     : Thread(parent, name, priority) {
     53    : Thread(getFrameworkManager(), name, priority) {
     54        if (singleton != NULL) {
     55    Err("VrpnClient must be instanced only one time\n");
     56    return;
     57  }
     58
     59  singleton = this;
    4160  pimpl_ = new VrpnClient_impl(this, name, serialport, us_period);
    4261}
  • trunk/lib/FlairSensorActuator/src/VrpnClient.h

    r15 r122  
    1818
    1919namespace flair {
    20 namespace core {
    21 class FrameworkManager;
    22 class SerialPort;
    23 }
    24 namespace gui {
    25 class TabWidget;
    26 class Layout;
    27 }
     20        namespace core {
     21                class SerialPort;
     22        }
     23        namespace gui {
     24                class TabWidget;
     25                class Layout;
     26        }
    2827}
    2928
     
    3534/*! \class VrpnClient
    3635*
    37 * \brief Class to connect to a Vrpn server
     36* \brief Class to connect to a Vrpn server. The Thread is created with
     37*  the FrameworkManager as parent. FrameworkManager must be created before.
     38* Only one instance of this class is allowed by program.
    3839*/
    3940class VrpnClient : public core::Thread {
     
    4647  * Construct a VrpnClient. Connection is done by IP.
    4748  *
    48   * \param parent parent
    4949  * \param name name
    5050  * \param address server address
     
    5252  * \param priority priority of the Thread
    5353  */
    54   VrpnClient(const core::FrameworkManager *parent, std::string name,
     54  VrpnClient(std::string name,
    5555             std::string address, uint16_t us_period, uint8_t priority);
    5656
     
    6060  * Construct a VrpnClient. Connection is done by XBee modem.
    6161  *
    62   * \param parent parent
    6362  * \param name name
    6463  * \param serialport SerialPort for XBee modem
     
    6665  * \param priority priority of the Thread
    6766  */
    68   VrpnClient(const core::FrameworkManager *parent, std::string name,
     67  VrpnClient(std::string name,
    6968             core::SerialPort *serialport, uint16_t us_period,
    7069             uint8_t priority);
     
    108107  class VrpnClient_impl *pimpl_;
    109108};
     109
     110/*!
     111* \brief get VrpnClient
     112*
     113* \return the VrpnClient
     114*/
     115VrpnClient *GetVrpnClient(void);
     116
    110117} // end namespace sensor
    111118} // end namespace flair
  • trunk/lib/FlairSensorActuator/src/VrpnObject.cpp

    r15 r122  
    3030namespace sensor {
    3131
    32 VrpnObject::VrpnObject(const VrpnClient *parent, string name,
     32VrpnObject::VrpnObject(string name,
    3333                       const TabWidget *tab)
    34     : IODevice(parent, name) {
    35   pimpl_ = new VrpnObject_impl(this, parent, name, -1, tab);
     34    : IODevice(GetVrpnClient(), name) {
     35  pimpl_ = new VrpnObject_impl(this, name, -1, tab);
    3636  AddDataToLog(pimpl_->output);
    3737}
    3838
    39 VrpnObject::VrpnObject(const VrpnClient *parent, string name, uint8_t id,
     39VrpnObject::VrpnObject(string name, uint8_t id,
    4040                       const TabWidget *tab)
    41     : IODevice(parent, name) {
     41    : IODevice(GetVrpnClient(), name) {
    4242  Warn("Creation of object %s with id %i\n", name.c_str(), id);
    43   pimpl_ = new VrpnObject_impl(this, parent, name, id, tab);
     43  pimpl_ = new VrpnObject_impl(this, name, id, tab);
    4444  AddDataToLog(pimpl_->output);
    4545}
  • trunk/lib/FlairSensorActuator/src/VrpnObject.h

    r15 r122  
    1919
    2020namespace flair {
    21 namespace core {
    22 class cvmatrix;
    23 class Vector3D;
    24 class Euler;
    25 class Quaternion;
    26 }
    27 namespace gui {
    28 class TabWidget;
    29 class Tab;
    30 class DataPlot1D;
    31 }
     21        namespace core {
     22                class cvmatrix;
     23                class Vector3D;
     24                class Euler;
     25                class Quaternion;
     26        }
     27        namespace gui {
     28                class TabWidget;
     29                class Tab;
     30                class DataPlot1D;
     31        }
    3232}
    3333
     
    4141/*! \class VrpnObject
    4242*
    43 * \brief Class for VRPN object
     43* \brief Class for VRPN object. The IODevice is created with
     44*  the VrpnClient as parent. VrpnClient must be created before.
    4445*/
    4546class VrpnObject : public core::IODevice {
     
    5354  * Construct a VrpnObject. Connection is done by IP.
    5455  *
    55   * \param parent parent
    5656  * \param name VRPN object name, should be the same as defined in the server
    5757  * \param tab Tab for the user interface
    5858  */
    59   VrpnObject(const VrpnClient *parent, std::string name,
     59  VrpnObject(std::string name,
    6060             const gui::TabWidget *tab);
    6161
     
    6565  * Construct a VrpnObject. Connection is done by IP.
    6666  *
    67   * \param parent parent
    6867  * \param name name
    6968  * \param id VRPN object id, should be the same as defined in the server
    7069  * \param tab Tab for the user interface
    7170  */
    72   VrpnObject(const VrpnClient *parent, std::string name, uint8_t id,
     71  VrpnObject(std::string name, uint8_t id,
    7372             const gui::TabWidget *tab);
    7473
  • trunk/lib/FlairSensorActuator/src/VrpnObject_impl.cpp

    r15 r122  
    3939using namespace flair::sensor;
    4040
    41 VrpnObject_impl::VrpnObject_impl(VrpnObject *self, const VrpnClient *parent,
     41VrpnObject_impl::VrpnObject_impl(VrpnObject *self,
    4242                                 string name, int id, const TabWidget *tab) {
    43   this->parent = parent;
     43  parent = GetVrpnClient();
    4444  this->self = self;
    4545
     46        if(parent==NULL) {
     47                self->Err("VrpnClient must be instanced before creating VrpnObject\n");
     48                return;
     49        }
    4650  if (id == -1 && parent->UseXbee()) {
    4751    self->Err("erreur aucun identifiant specifie pour la connexion Xbee\n");
  • trunk/lib/FlairSensorActuator/src/unexported/VrpnObject_impl.h

    r15 r122  
    2626
    2727namespace flair {
    28 namespace core {
    29 class cvmatrix;
    30 class Vector3D;
    31 class Euler;
    32 }
    33 namespace gui {
    34 class TabWidget;
    35 class Tab;
    36 class DataPlot1D;
    37 }
    38 namespace sensor {
    39 class VrpnClient;
    40 class VrpnObject;
    41 }
     28        namespace core {
     29                class cvmatrix;
     30                class Vector3D;
     31                class Euler;
     32        }
     33        namespace gui {
     34                class TabWidget;
     35                class Tab;
     36                class DataPlot1D;
     37        }
     38        namespace sensor {
     39                class VrpnClient;
     40                class VrpnObject;
     41        }
    4242}
    4343
     
    4747public:
    4848  VrpnObject_impl(flair::sensor::VrpnObject *self,
    49                   const flair::sensor::VrpnClient *parent, std::string name,
     49                  std::string name,
    5050                  int id, const flair::gui::TabWidget *tab);
    5151  ~VrpnObject_impl(void);
Note: See TracChangeset for help on using the changeset viewer.