Changeset 157 in flair-src for trunk/lib


Ignore:
Timestamp:
Mar 4, 2017, 3:29:18 PM (8 years ago)
Author:
Sanahuja Guillaume
Message:

iadded isready to iodevice:
avoid problem of imu not ready in ardrone2

Location:
trunk/lib
Files:
2 added
67 edited

Legend:

Unmodified
Added
Removed
  • trunk/lib/FlairCore/src/Euler.cpp

    r15 r157  
    113113    rot2 = yaw - angle;
    114114  }
    115   if (rot2 < rot1)
    116     rot1 = -rot2;
     115 
     116  if (rot2 < rot1) rot1 = -rot2;
     117 
    117118  rot1 = -rot1; // pour avoir rot1=yaw-angle
    118119
  • trunk/lib/FlairCore/src/IODevice.cpp

    r121 r157  
    6464DataType const &IODevice::GetOutputDataType() const { return dummyType; }
    6565
     66void IODevice::SetIsReady(bool status) {
     67  pimpl_->SetIsReady(status);
     68}
     69
     70bool IODevice::IsReady(void) const {
     71  return pimpl_->IsReady();
     72}
     73
    6674} // end namespace core
    6775} // end namespace flair
  • trunk/lib/FlairCore/src/IODevice.h

    r121 r157  
    110110  */
    111111  void OutputToShMem(bool enabled);
     112 
     113  /*!
     114  * \brief is device ready
     115  *
     116  * Use it check if a device is ready or not.
     117  * See also setIsReady.
     118  *
     119  * \return true if device is ready
     120  */
     121  bool IsReady(void) const;
    112122
    113123  // TODO: these 2 method should be pure virtual
     
    115125  virtual DataType const &GetOutputDataType() const;
    116126
    117         protected:
    118             /*!
    119             * \brief Process the childs of type IODevice, and log if needed
    120             *
    121             * This method must be called after computing datas;
    122             * generally at the end of the reimplemented UpdateFrom or after acquiring datas in case of a sensor. \n
    123             * It will call UpdateFrom methods of each child of type IODevice,
    124             * and log all datas (this IODevice and its childs)
    125             * if logging is enabled (see SetDataToLog(), AddDeviceToLog(),
    126             * FrameworkManager::StartLog and FrameworkManager::AddDeviceToLog). \n
    127             * If a thread is waiting on this IODevice (see Thread::WaitUpdate), it will be resumed.
    128             *
    129             * \param data data to process
    130             */
    131             void ProcessUpdate(io_data* data);
     127  protected:
     128    /*!
     129    * \brief Process the childs of type IODevice, and log if needed
     130    *
     131    * This method must be called after computing datas;
     132    * generally at the end of the reimplemented UpdateFrom or after acquiring datas in case of a sensor. \n
     133    * It will call UpdateFrom methods of each child of type IODevice,
     134    * and log all datas (this IODevice and its childs)
     135    * if logging is enabled (see SetDataToLog(), AddDeviceToLog(),
     136    * FrameworkManager::StartLog and FrameworkManager::AddDeviceToLog). \n
     137    * If a thread is waiting on this IODevice (see Thread::WaitUpdate), it will be resumed.
     138    *
     139    * \param data data to process
     140    */
     141    void ProcessUpdate(io_data* data);
     142   
     143    /*!
     144    * \brief set is ready
     145    *
     146    * Sets if the device is ready or not. By default the IODevice is not ready.\n
     147    * See also isReady.
     148    *
     149    * \param status status
     150    */
     151    void SetIsReady(bool status);
    132152
    133153private:
  • trunk/lib/FlairCore/src/IODevice_impl.cpp

    r122 r157  
    3939  tobelogged = false;
    4040  outputtoshm = false;
     41  isReady=false;
    4142}
    4243
     
    233234  return status;
    234235}
     236
     237void IODevice_impl::SetIsReady(bool status) {
     238  isReady=status;
     239}
     240
     241bool IODevice_impl::IsReady(void) const {
     242  return isReady;
     243}
  • trunk/lib/FlairCore/src/ui_com.cpp

    r133 r157  
    278278      if (offset != 3) {
    279279        memcpy(&send_buffer[1], &resume_period, sizeof(uint16_t));
    280         // printf("send %i %i %i %x
    281         // %x\n",resume_period,offset,sizeof(uint16_t),send_buffer,&send_buffer[1]);
     280        // printf("send %i %i %i %x %x\n",resume_period,offset,sizeof(uint16_t),send_buffer,&send_buffer[1]);
    282281        // for(int i=0;i<offset;i++) printf("%x ",send_buffer[i]);
    283282        // printf("\n");
     
    292291      }
    293292      send_mutex->ReleaseMutex();
    294       // Printf("%i %lld\n",resume_period,GetTime()/1000000);
     293      //Printf("%i %lld\n",resume_period,GetTime()/1000000);
    295294    } else {
    296295      send_mutex->ReleaseMutex();
    297296      // rien a faire, suspend
    298       // Printf("rien a faire suspend\n");
     297      //Printf("rien a faire suspend\n");
    299298      Suspend();
    300       // Printf("wake\n");
     299      //Printf("wake\n");
    301300      // on planifie la prochaine execution
    302301      Time time = GetTime();
  • trunk/lib/FlairCore/src/unexported/IODevice_impl.h

    r122 r157  
    4747  void WriteToShMem(void);
    4848  void PrintLogsDescriptors(void);
     49  void SetIsReady(bool status);
     50  bool IsReady(void) const;
    4951
    5052private:
     
    5961  bool outputtoshm;
    6062  flair::core::SharedMem *shmem;
     63  bool isReady;
    6164};
    6265
  • trunk/lib/FlairFilter/src/AhrsComplementaryFilter.cpp

    r24 r157  
    5151    kb[1]=new DoubleSpinBox(parent->GetLayout()->LastRowLastCol(),"kb[1]:",0.,10,0.1,2,0.01);
    5252    kb[2]=new DoubleSpinBox(parent->GetLayout()->LastRowLastCol(),"kb[2]:",0.,10,0.1,2,0.01);
    53 
     53 
     54  SetIsReady(true);
    5455}
    5556
  • trunk/lib/FlairFilter/src/AhrsKalman.cpp

    r18 r157  
    3131    GetDatas(&ahrsData);
    3232    pimpl_=new AhrsKalman_impl(parent->GetLayout(),ahrsData);
     33   
     34    SetIsReady(true);
    3335}
    3436
  • trunk/lib/FlairFilter/src/ButterworthLowPass.cpp

    r15 r157  
    3535  pimpl_ = new ButterworthLowPass_impl(this, position, name, order);
    3636  AddDataToLog(pimpl_->output);
     37 
     38  SetIsReady(true);
    3739}
    3840
  • trunk/lib/FlairFilter/src/EulerDerivative.cpp

    r15 r157  
    3434  pimpl_ = new EulerDerivative_impl(this, position, name, init_value);
    3535  AddDataToLog(pimpl_->output);
     36 
     37  SetIsReady(true);
    3638}
    3739
  • trunk/lib/FlairFilter/src/Gx3_25_ahrs.cpp

    r137 r157  
    3030                         SerialPort *serialport, Gx3_25_imu::Command_t command,
    3131                         uint8_t priority)
    32     : Ahrs(new Gx3_25_imu( name, serialport, command, priority), name) {}
     32    : Ahrs(new Gx3_25_imu( name, serialport, command, priority), name) {
     33
     34  SetIsReady(true);
     35}
    3336
    3437Gx3_25_ahrs::~Gx3_25_ahrs() {}
    35 
    36 void Gx3_25_ahrs::Start(void) { ((Gx3_25_imu *)GetImu())->Start(); }
    3738
    3839// datas from Gx3_25_imu are AhrsData!
  • trunk/lib/FlairFilter/src/Gx3_25_ahrs.h

    r137 r157  
    4747  ~Gx3_25_ahrs();
    4848
    49   /*!
    50   * \brief Start Gx3_25_imu Thread
    51   *
    52   */
    53   void Start(void);
    54 
    5549private:
    5650  /*!
  • trunk/lib/FlairFilter/src/JoyReference.cpp

    r15 r157  
    3737  AddDataToLog(pimpl_->output);
    3838  AddDataToLog(pimpl_->ahrsData);
     39 
     40  SetIsReady(true);
    3941}
    4042
  • trunk/lib/FlairFilter/src/LowPassFilter.cpp

    r15 r157  
    3434  pimpl_ = new LowPassFilter_impl(this, position, name, init_value);
    3535  AddDataToLog(pimpl_->output);
     36 
     37  SetIsReady(true);
    3638}
    3739
  • trunk/lib/FlairFilter/src/NestedSat.cpp

    r15 r157  
    3333    : ControlLaw(position->getLayout(), name) {
    3434  pimpl_ = new NestedSat_impl(this, position, name);
     35 
     36  SetIsReady(true);
    3537}
    3638
  • trunk/lib/FlairFilter/src/Pid.cpp

    r15 r157  
    3232    : ControlLaw(position->getLayout(), name) {
    3333  pimpl_ = new Pid_impl(this, position, name);
     34 
     35  SetIsReady(true);
    3436}
    3537
  • trunk/lib/FlairFilter/src/PidThrust.cpp

    r15 r157  
    3333    : ControlLaw(position->getLayout(), name) {
    3434  pimpl_ = new PidThrust_impl(this, position, name);
     35 
     36  SetIsReady(true);
    3537}
    3638
  • trunk/lib/FlairFilter/src/SimuAhrs.cpp

    r137 r157  
    2929SimuAhrs::SimuAhrs(string name, uint32_t dev_id,
    3030                   uint8_t priority)
    31     : Ahrs(new SimuImu(name, dev_id, priority), name) {}
     31    : Ahrs(new SimuImu(name, dev_id, priority), name) {
     32  SetIsReady(true);
     33}
    3234
    3335SimuAhrs::~SimuAhrs() {}
    34 
    35 void SimuAhrs::Start(void) { ((SimuImu *)GetImu())->Start(); }
    3636
    3737// datas from SimuImu are AhrsData!
  • trunk/lib/FlairFilter/src/SimuAhrs.h

    r137 r157  
    4545  ~SimuAhrs();
    4646
    47   /*!
    48  * \brief Start SimuImu Thread
    49  *
    50  */
    51   void Start(void);
    52 
    5347private:
    5448  /*!
  • trunk/lib/FlairFilter/src/TrajectoryGenerator1D.cpp

    r15 r157  
    3434  pimpl_ = new TrajectoryGenerator1D_impl(this, position, name, unit);
    3535  AddDataToLog(pimpl_->output);
     36  SetIsReady(true);
    3637}
    3738
  • trunk/lib/FlairFilter/src/TrajectoryGenerator2DCircle.cpp

    r15 r157  
    3535  pimpl_ = new TrajectoryGenerator2DCircle_impl(this, position, name);
    3636  AddDataToLog(pimpl_->output);
     37  SetIsReady(true);
    3738}
    3839
  • trunk/lib/FlairFilter/src/X4X8Multiplex.cpp

    r137 r157  
    4747    SetMultiplexComboBox(pimpl_->MotorName(i), i);
    4848  }
     49 
     50  SetIsReady(true);
    4951}
    5052
  • trunk/lib/FlairMeta/src/HdsX8.cpp

    r137 r157  
    3535namespace meta {
    3636
    37 HdsX8::HdsX8(string name,
     37HdsX8::HdsX8(string name,string options,
    3838             filter::UavMultiplex *multiplex)
    3939    : Uav(name, multiplex) {
     
    5656
    5757void HdsX8::StartSensors(void) {
    58   ((Gx3_25_ahrs *)GetAhrs())->Start();
     58  ((Gx3_25_imu *)(GetAhrs()->GetImu()))->Start();
    5959  ((Srf08 *)GetUsRangeFinder())->Start();
    6060  ((Ps3Eye *)GetVerticalCamera())->Start();
    6161}
    6262
     63bool HdsX8::isReadyToFly(void) const {
     64  return GetAhrs()->GetImu()->IsReady();
     65}
     66
    6367} // end namespace meta
    6468} // end namespace flair
  • trunk/lib/FlairMeta/src/HdsX8.h

    r122 r157  
    2424class HdsX8 : public Uav {
    2525public:
    26   HdsX8(std::string name,
     26  HdsX8(std::string name,std::string options="",
    2727        filter::UavMultiplex *multiplex = NULL);
    2828  ~HdsX8();
    2929  void StartSensors(void);
    3030        std::string GetDefaultVrpnAddress(void) const{return "192.168.147.197:3883";}
     31  bool isReadyToFly(void) const;
    3132
    3233private:
  • trunk/lib/FlairMeta/src/MetaDualShock3.cpp

    r137 r157  
    4242  getFrameworkManager()->AddDeviceToLog(pimpl_->joy_ref);
    4343  controller->Start();
     44 
     45  SetIsReady(true);
    4446}
    4547
  • trunk/lib/FlairMeta/src/SimuX4.cpp

    r137 r157  
    2626#include <BatteryMonitor.h>
    2727#include <Tab.h>
     28#include <FindArgument.h>
    2829
    2930using std::string;
     
    3738namespace meta {
    3839
    39 SimuX4::SimuX4(string name, int simu_id,
     40SimuX4::SimuX4(string name, int simu_id,string options,
    4041               filter::UavMultiplex *multiplex)
    4142    : Uav(name, multiplex) {
     
    5152  SetBatteryMonitor(new BatteryMonitor(bat_tab->NewRow(), "battery"));
    5253  GetBatteryMonitor()->SetBatteryValue(12);
     54 
     55  string camvOpts=FindArgument(options,"camv=",false);
     56  uint16_t camvWidth=320,camvHeight=240;
     57        if(camvOpts=="") {
     58    Info("using default vertical camera resolution: %ix%i\n",camvWidth, camvHeight);
     59        }
     60 
    5361  SetVerticalCamera(
    54       new SimuCamera("simu_cam_v", 320, 240, 3, simu_id, 10));
     62      new SimuCamera("simu_cam_v", camvWidth, camvHeight, 3, simu_id, 10));
    5563}
    5664
     
    5866
    5967void SimuX4::StartSensors(void) {
    60   ((SimuAhrs *)GetAhrs())->Start();
     68  ((SimuImu *)(GetAhrs()->GetImu()))->Start();
    6169  ((SimuUs *)GetUsRangeFinder())->Start();
    6270  ((SimuCamera *)GetVerticalCamera())->Start();
    6371}
    6472
     73
    6574} // end namespace meta
    6675} // end namespace flair
  • trunk/lib/FlairMeta/src/SimuX4.h

    r122 r157  
    2626  // simu_id: 0 if simulating only one UAV
    2727  //>0 otherwise
    28   SimuX4(std::string name, int simu_id = 0,
     28  SimuX4(std::string name, int simu_id = 0,std::string options="",
    2929         filter::UavMultiplex *multiplex = NULL);
    3030  ~SimuX4();
  • trunk/lib/FlairMeta/src/SimuX8.cpp

    r137 r157  
    3737namespace meta {
    3838
    39 SimuX8::SimuX8(string name, int simu_id,
     39SimuX8::SimuX8(string name, int simu_id,string options,
    4040               filter::UavMultiplex *multiplex)
    4141    : Uav(name, multiplex) {
     
    5858
    5959void SimuX8::StartSensors(void) {
    60   ((SimuAhrs *)GetAhrs())->Start();
     60  ((SimuImu *)(GetAhrs()->GetImu()))->Start();
    6161  ((SimuUs *)GetUsRangeFinder())->Start();
    6262  ((SimuCamera *)GetVerticalCamera())->Start();
  • trunk/lib/FlairMeta/src/SimuX8.h

    r122 r157  
    2626  // simu_id: 0 if simulating only one UAV
    2727  //>0 otherwise
    28   SimuX8(std::string name, int simu_id = 0,
     28  SimuX8(std::string name, int simu_id = 0,std::string options="",
    2929         filter::UavMultiplex *multiplex = NULL);
    3030  ~SimuX8();
  • trunk/lib/FlairMeta/src/Uav.h

    r122 r157  
    1515
    1616#include <Object.h>
     17#include <UsRangeFinder.h>
    1718
    1819namespace flair {
     
    6263  sensor::Camera *GetHorizontalCamera(void) const;
    6364        virtual std::string GetDefaultVrpnAddress(void) const{return "127.0.0.1:3883";}
     65  virtual bool isReadyToFly(void) const { return true;}
    6466
    6567protected:
  • trunk/lib/FlairMeta/src/UavFactory.cpp

    r122 r157  
    3030
    3131namespace { // anonymous
    32      vector<flair::meta::Uav* (*)(string,string,UavMultiplex*)> *vectoroffunctions=NULL;
     32     vector<flair::meta::Uav* (*)(string,string,string,UavMultiplex*)> *vectoroffunctions=NULL;
    3333}
    3434
     
    4141
    4242
    43 Uav *CreateUav(string name, string uav_type,
     43Uav *CreateUav(string name, string type,string options,
    4444               UavMultiplex *multiplex) {
    4545
     
    4848  if(vectoroffunctions!=NULL) {
    4949    for(int i=0;i<vectoroffunctions->size();i++) {
    50       uav=vectoroffunctions->at(i)(name,uav_type,multiplex);
     50      uav=vectoroffunctions->at(i)(name,type,options,multiplex);
    5151      if(uav!=NULL) {
    5252        free(vectoroffunctions);
     
    5757  }
    5858
    59   if (uav_type == "hds_x4") {
    60     getFrameworkManager()->Err("UAV type %s not yet implemented\n", uav_type.c_str());
     59  if (type == "hds_x4") {
     60    getFrameworkManager()->Err("UAV type %s not yet implemented\n", type.c_str());
    6161    return NULL;
    62   } else if (uav_type == "hds_x8") {
    63     return new HdsX8(name, multiplex);
    64   } else if (uav_type == "xair") {
    65     return new XAir(name, multiplex);
    66   } else if (uav_type == "hds_xufo") {
    67     getFrameworkManager()->Err("UAV type %s not yet implemented\n", uav_type.c_str());
     62  } else if (type == "hds_x8") {
     63    return new HdsX8(name,options, multiplex);
     64  } else if (type == "xair") {
     65    return new XAir(name,options, multiplex);
     66  } else if (type == "hds_xufo") {
     67    getFrameworkManager()->Err("UAV type %s not yet implemented\n", type.c_str());
    6868    return NULL;
    69   } else if (uav_type.compare(0, 7, "x4_simu") == 0) {
     69  } else if (type.compare(0, 7, "x4_simu") == 0) {
    7070    int simu_id = 0;
    71     if (uav_type.size() > 7) {
    72       simu_id = atoi(uav_type.substr(7, uav_type.size() - 7).c_str());
     71    if (type.size() > 7) {
     72      simu_id = atoi(type.substr(7, type.size() - 7).c_str());
    7373    }
    74     return new SimuX4(name, simu_id, multiplex);
    75   } else if (uav_type.compare(0, 7, "x8_simu") == 0) {
     74    return new SimuX4(name, simu_id,options, multiplex);
     75  } else if (type.compare(0, 7, "x8_simu") == 0) {
    7676    int simu_id = 0;
    77     if (uav_type.size() > 7) {
    78       simu_id = atoi(uav_type.substr(7, uav_type.size() - 7).c_str());
     77    if (type.size() > 7) {
     78      simu_id = atoi(type.substr(7, type.size() - 7).c_str());
    7979    }
    80     return new SimuX8(name, simu_id, multiplex);
     80    return new SimuX8(name, simu_id,options, multiplex);
    8181  } else {
    82     getFrameworkManager()->Err("UAV type %s unknown\n", uav_type.c_str());
     82    getFrameworkManager()->Err("UAV type %s unknown\n", type.c_str());
    8383    return NULL;
    8484  }
    8585}
    8686
    87 void RegisterUavCreator(flair::meta::Uav*(*func)(string name, string type,
    88                UavMultiplex *multiplex)) {
    89   if(vectoroffunctions==NULL) vectoroffunctions=(vector<flair::meta::Uav* (*)(string,string,UavMultiplex*)>*)malloc(sizeof(vector<flair::meta::Uav* (*)(string,string,UavMultiplex*)>));
     87void RegisterUavCreator(flair::meta::Uav*(*func)(string,string,string,UavMultiplex*)) {
     88  if(vectoroffunctions==NULL) vectoroffunctions=(vector<flair::meta::Uav* (*)(string,string,string,UavMultiplex*)>*)malloc(sizeof(vector<flair::meta::Uav* (*)(string,string,string,UavMultiplex*)>));
    9089
    9190  vectoroffunctions->push_back(func);
  • trunk/lib/FlairMeta/src/UavFactory.h

    r122 r157  
    2121#include <Uav.h>
    2222
    23 flair::meta::Uav *CreateUav(std::string name, std::string type,
     23flair::meta::Uav *CreateUav(std::string name, std::string type,std::string options="",
    2424                            flair::filter::UavMultiplex *multiplex = NULL);
    2525
    26 void RegisterUavCreator(flair::meta::Uav*(*func)(std::string name, std::string type,
    27                                    flair::filter::UavMultiplex *multiplex));
     26void RegisterUavCreator(flair::meta::Uav*(*func)(std::string,std::string,std::string,
     27                                   flair::filter::UavMultiplex*));
    2828#endif // UAVFACTORY
  • trunk/lib/FlairMeta/src/UavStateMachine.cpp

    r153 r157  
    460460  flagZTrajectoryFinished = false;
    461461
    462     if((altitudeState==AltitudeState_t::Stopped) && safeToFly) {// && GetBatteryMonitor()->IsBatteryLow()==false)
    463         //The uav always takes off in fail safe mode
    464         EnterFailSafeMode();
    465         joy->SetLedOFF(4);//DualShock3::led4
    466         joy->SetLedOFF(1);//DualShock3::led1
    467         joy->Rumble(0x70);
    468         joy->SetZRef(0);
     462  if((altitudeState==AltitudeState_t::Stopped) && safeToFly && uav->isReadyToFly()) {// && GetBatteryMonitor()->IsBatteryLow()==false)
     463    //The uav always takes off in fail safe mode
     464    EnterFailSafeMode();
     465    joy->SetLedOFF(4);//DualShock3::led4
     466    joy->SetLedOFF(1);//DualShock3::led1
     467    joy->Rumble(0x70);
     468    joy->SetZRef(0);
    469469
    470470    uZ->SetOffset(); // positionne l'offset de compensation de la gravité à sa
     
    481481    SignalEvent(Event_t::TakingOff);
    482482  } else {
     483    Warn("cannot takeoff\n");
    483484    joy->ErrorNotify();
    484485  }
  • trunk/lib/FlairMeta/src/XAir.cpp

    r137 r157  
    3838namespace meta {
    3939
    40 XAir::XAir(string name,
     40XAir::XAir(string name, string options,
    4141           filter::UavMultiplex *multiplex)
    4242    : Uav(name, multiplex) {
     
    6161
    6262void XAir::StartSensors(void) {
    63   ((Gx3_25_ahrs *)GetAhrs())->Start();
     63  ((Gx3_25_imu *)(GetAhrs()->GetImu()))->Start();
    6464  ((Srf08 *)GetUsRangeFinder())->Start();
    6565  ((Ps3Eye *)GetVerticalCamera())->Start();
    6666}
    6767
     68bool XAir::isReadyToFly(void) const {
     69  return GetAhrs()->GetImu()->IsReady();
     70}
     71
    6872} // end namespace meta
    6973} // end namespace flair
  • trunk/lib/FlairMeta/src/XAir.h

    r122 r157  
    2424class XAir : public Uav {
    2525public:
    26   XAir(std::string name,
     26  XAir(std::string name,std::string options="",
    2727       filter::UavMultiplex *multiplex = NULL);
    2828  ~XAir();
    2929  void StartSensors(void);
    3030        std::string GetDefaultVrpnAddress(void) const{return "192.168.147.197:3883";}
     31  bool isReadyToFly(void) const;
    3132
    3233private:
  • trunk/lib/FlairSensorActuator/src/AfroBldc.cpp

    r15 r157  
    3737    : Bldc(parent, layout, name, motors_count) {
    3838  pimpl_ = new AfroBldc_impl(this, layout, i2cport);
     39 
     40  SetIsReady(true);
    3941}
    4042
  • trunk/lib/FlairSensorActuator/src/BlCtrlV2.cpp

    r15 r157  
    3838    : Bldc(parent, layout, name, motors_count) {
    3939  pimpl_ = new BlCtrlV2_impl(this, layout, i2cport);
     40 
     41  SetIsReady(true);
    4042}
    4143
  • trunk/lib/FlairSensorActuator/src/BlCtrlV2_x4_speed.cpp

    r148 r157  
    134134  delete desc;
    135135 
     136  SetIsReady(true);
     137 
    136138  /*
    137139
  • trunk/lib/FlairSensorActuator/src/Bldc.cpp

    r148 r157  
    6161    : IODevice(parent, name) {
    6262  pimpl_ = new Bldc_impl(this, motors_count);
     63 
     64  SetIsReady(true);
    6365}
    6466
  • trunk/lib/FlairSensorActuator/src/Camera.cpp

    r137 r157  
    5050  setup_groupbox = new GroupBox(sensor_tab->NewRow(), name);
    5151  setup_layout = new GridLayout(sensor_tab->NewRow(), "setup");
     52 
    5253}
    5354
  • trunk/lib/FlairSensorActuator/src/EmulatedController.cpp

    r137 r157  
    3030EmulatedController::EmulatedController(string name,uint8_t priority) :
    3131    TargetController(name,priority) {
     32  SetIsReady(true);
    3233}
    3334
  • trunk/lib/FlairSensorActuator/src/Gx3_25_imu_impl.cpp

    r103 r157  
    9696  SamplingSettings();
    9797  GyrosBias();
     98  self->SetIsReady(true);
    9899  // RealignUpNorth(true,true);
    99100
     
    265266    ssize_t written = 0;
    266267
    267     Printf("Gx3_25_imu::gyros_bias: %s\n",
    268            self->IODevice::ObjectName().c_str());
     268    Printf("Gx3_25_imu::calibrating gyros, do not move imu\n");
    269269
    270270    command[0] = 0xcd; // entete
     
    296296    }
    297297
    298     Printf("Gx3_25_imu::gyros_bias: %s ok\n",
    299            self->IODevice::ObjectName().c_str());
     298    Printf("Gx3_25_imu::calibration done\n");
    300299
    301300  } else {
  • trunk/lib/FlairSensorActuator/src/HokuyoUTM30Lx.cpp

    r148 r157  
    5050  this->serialport = serialport;
    5151  serialport->SetRxTimeout(100000000);
     52 
     53  SetIsReady(true);
    5254}
    5355
  • trunk/lib/FlairSensorActuator/src/Mb800.cpp

    r137 r157  
    3333  this->serialport = serialport;
    3434  serialport->SetRxTimeout(100000000);
     35 
     36  SetIsReady(true);
    3537}
    3638
  • trunk/lib/FlairSensorActuator/src/Novatel.cpp

    r137 r157  
    3232    : NmeaGps(name, NMEAFlags), Thread(getFrameworkManager(), name, priority) {
    3333  this->serialport = serialport;
     34 
     35  SetIsReady(true);
    3436}
    3537
  • trunk/lib/FlairSensorActuator/src/Ps3Eye.cpp

    r137 r157  
    2727               uint8_t priority)
    2828    : V4LCamera( name, camera_index, 320, 240,
    29                 cvimage::Type::Format::YUYV, priority) {}
     29                cvimage::Type::Format::YUYV, priority) {
     30  SetIsReady(true);                 
     31}
    3032
    3133Ps3Eye::~Ps3Eye() {}
  • trunk/lib/FlairSensorActuator/src/RadioReceiver.cpp

    r148 r157  
    5353
    5454  AddDataToLog(output);
     55 
     56  SetIsReady(true);
    5557}
    5658
  • trunk/lib/FlairSensorActuator/src/SimuBldc.cpp

    r15 r157  
    4242  GroupBox *groupbox = new GroupBox(layout->NewRow(), "simubldc");
    4343  k = new DoubleSpinBox(groupbox->NewRow(), "k driver:", 0, 10000, 1);
     44 
     45  SetIsReady(true);
    4446}
    4547
     
    5860
    5961  shmem->Write((char *)&values, motors_count * sizeof(float));
     62 
     63  SetIsReady(true);
    6064}
    6165
  • trunk/lib/FlairSensorActuator/src/SimuCamera.cpp

    r151 r157  
    4545  dev_name << "simu_cam_" << dev_id;
    4646  shmem = new SharedMem((Thread *)this, dev_name.str().c_str(), buf_size, SharedMem::Type::producerConsumer);
     47 
     48  SetIsReady(true);
    4749}
    4850
     
    5961                        buf_size, SharedMem::Type::producerConsumer);
    6062  shmemReadBuf=NULL;
     63 
     64  SetIsReady(true);
    6165}
    6266
  • trunk/lib/FlairSensorActuator/src/SimuGps.cpp

    r137 r157  
    5353  shmem = new SharedMem((Thread *)this, dev_name.str().c_str(),
    5454                        sizeof(gps_states_t));
     55                       
     56  SetIsReady(true);
    5557}
    5658
     
    6466  shmem = new SharedMem((Thread *)this, dev_name.str().c_str(),
    6567                        sizeof(gps_states_t));
     68 
     69  SetIsReady(true);
    6670}
    6771
  • trunk/lib/FlairSensorActuator/src/SimuImu.cpp

    r137 r157  
    4545  shmem = new SharedMem((Thread *)this, dev_name.str().c_str(),
    4646                        sizeof(imu_states_t));
     47  SetIsReady(true);
    4748}
    4849
     
    5556  shmem = new SharedMem((Thread *)this, dev_name.str().c_str(),
    5657                        sizeof(imu_states_t));
     58  SetIsReady(true);
    5759}
    5860
  • trunk/lib/FlairSensorActuator/src/SimuLaser.cpp

    r137 r157  
    4141  dev_name << "simu_Laser_" << dev_id;
    4242  shmem = new SharedMem((Thread *)this, dev_name.str().c_str(),
    43                         360 * sizeof(float)); //****
     43                        360 * sizeof(float));
     44  SetIsReady(true);
    4445}
    4546
     
    5253  shmem = new SharedMem((Thread *)this, dev_name.str().c_str(),
    5354                        360 * sizeof(float));
     55  SetIsReady(true);
    5456}
    5557
  • trunk/lib/FlairSensorActuator/src/SimuUs.cpp

    r137 r157  
    4141  dev_name << "simu_us_" << dev_id;
    4242  shmem = new SharedMem((Thread *)this, dev_name.str().c_str(), sizeof(float));
     43
     44  SetIsReady(true);
    4345}
    4446
     
    5052  dev_name << "simu_us_" << dev_id;
    5153  shmem = new SharedMem((Thread *)this, dev_name.str().c_str(), sizeof(float));
     54 
     55  SetIsReady(true);
    5256}
    5357
  • trunk/lib/FlairSensorActuator/src/Srf08.cpp

    r137 r157  
    5353  SetRange();
    5454  SetMaxGain();
     55 
     56  SetIsReady(true);
    5557}
    5658
  • trunk/lib/FlairSensorActuator/src/VrpnObject.cpp

    r140 r157  
    3535  pimpl_ = new VrpnObject_impl(this, name, -1, tab);
    3636  AddDataToLog(pimpl_->output);
     37 
     38  SetIsReady(true);
    3739}
    3840
     
    4345  pimpl_ = new VrpnObject_impl(this, name, id, tab);
    4446  AddDataToLog(pimpl_->output);
     47 
     48  SetIsReady(true);
    4549}
    4650
  • trunk/lib/FlairSensorActuator/src/XBldc.cpp

    r15 r157  
    3030    : Bldc(parent, layout, name, 4) {
    3131  pimpl_ = new XBldc_impl(this, i2cport);
     32 
     33  SetIsReady(true);
    3234}
    3335
  • trunk/lib/FlairSimulator/src/Man.cpp

    r134 r157  
    6060  r_speed = new DoubleSpinBox(setup_tab->NewRow(), "rotational speed (deg/s):",
    6161                              0, 180, 10);
     62                             
     63  SetIsReady(true);
    6264}
    6365
  • trunk/lib/FlairSimulator/src/X4.cpp

    r15 r157  
    7676
    7777  motors = new SimuBldc(this, name, 4, dev_id);
     78 
     79  SetIsReady(true);
    7880}
    7981
  • trunk/lib/FlairSimulator/src/X4.h

    r69 r157  
    1919
    2020#include <Model.h>
    21 #include <stdint.h>
    22 #include <stdio.h>
    2321
    2422namespace flair {
  • trunk/lib/FlairSimulator/src/X8.cpp

    r15 r157  
    8585
    8686  motors = new SimuBldc(this, name, 8, dev_id);
     87 
     88  SetIsReady(true);
    8789}
    8890
  • trunk/lib/FlairSimulator/src/X8.h

    r69 r157  
    1919
    2020#include <Model.h>
    21 #include <stdint.h>
    2221
    2322namespace flair {
  • trunk/lib/FlairVisionFilter/src/CvtColor.cpp

    r124 r157  
    3737        Err("conversion not supported\n");
    3838    }
     39   
     40    SetIsReady(true);
    3941}
    4042
  • trunk/lib/FlairVisionFilter/src/HoughLines.cpp

    r148 r157  
    5656        if(imageType.GetFormat()!=cvimage::Type::Format::Gray) {
    5757            Err("input image is not gray\n");
     58            return;
    5859        }
    5960    } catch(std::bad_cast& bc) {
    6061        Err("io type mismatch\n");
     62        return;
    6163    }
     64   
     65    SetIsReady(true);
    6266}
    6367
  • trunk/lib/FlairVisionFilter/src/ImgThreshold.cpp

    r124 r157  
    3636        } else {
    3737            Err("input image is not gray\n");
     38            return;
    3839        }
    3940    } catch(std::bad_cast& bc) {
    4041        Err("io type mismatch\n");
     42        return;
    4143    }
     44    SetIsReady(true);
    4245}
    4346
  • trunk/lib/FlairVisionFilter/src/OpticalFlow.cpp

    r144 r157  
    4848        pyr=NULL;
    4949        pyr_old=NULL;
     50        return;
    5051    }
    5152
     
    6364    found_feature=(char *)cvAlloc(max_features->Value()*sizeof(char));
    6465    feature_error=(unsigned int *)cvAlloc(max_features->Value()*sizeof(unsigned int));
     66   
     67    SetIsReady(true);
    6568}
    6669
  • trunk/lib/FlairVisionFilter/src/OpticalFlowSpeed.cpp

    r148 r157  
    3434
    3535        AddDataToLog(output);
     36 
     37  SetIsReady(true);
    3638}
    3739
  • trunk/lib/FlairVisionFilter/src/Sobel.cpp

    r124 r157  
    3838        } else {
    3939            Err("input image is not gray\n");
     40            return;
    4041        }
    4142
    4243    } catch(std::bad_cast& bc) {
    4344        Err("io type mismatch\n");
     45        return;
    4446    }
     47    SetIsReady(true);
    4548}
    4649
Note: See TracChangeset for help on using the changeset viewer.