- Timestamp:
- Mar 4, 2017, 3:29:18 PM (8 years ago)
- Location:
- trunk/lib
- Files:
-
- 2 added
- 67 edited
Legend:
- Unmodified
- Added
- Removed
-
trunk/lib/FlairCore/src/Euler.cpp
r15 r157 113 113 rot2 = yaw - angle; 114 114 } 115 if (rot2 < rot1) 116 rot1 = -rot2; 115 116 if (rot2 < rot1) rot1 = -rot2; 117 117 118 rot1 = -rot1; // pour avoir rot1=yaw-angle 118 119 -
trunk/lib/FlairCore/src/IODevice.cpp
r121 r157 64 64 DataType const &IODevice::GetOutputDataType() const { return dummyType; } 65 65 66 void IODevice::SetIsReady(bool status) { 67 pimpl_->SetIsReady(status); 68 } 69 70 bool IODevice::IsReady(void) const { 71 return pimpl_->IsReady(); 72 } 73 66 74 } // end namespace core 67 75 } // end namespace flair -
trunk/lib/FlairCore/src/IODevice.h
r121 r157 110 110 */ 111 111 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; 112 122 113 123 // TODO: these 2 method should be pure virtual … … 115 125 virtual DataType const &GetOutputDataType() const; 116 126 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); 132 152 133 153 private: -
trunk/lib/FlairCore/src/IODevice_impl.cpp
r122 r157 39 39 tobelogged = false; 40 40 outputtoshm = false; 41 isReady=false; 41 42 } 42 43 … … 233 234 return status; 234 235 } 236 237 void IODevice_impl::SetIsReady(bool status) { 238 isReady=status; 239 } 240 241 bool IODevice_impl::IsReady(void) const { 242 return isReady; 243 } -
trunk/lib/FlairCore/src/ui_com.cpp
r133 r157 278 278 if (offset != 3) { 279 279 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]); 282 281 // for(int i=0;i<offset;i++) printf("%x ",send_buffer[i]); 283 282 // printf("\n"); … … 292 291 } 293 292 send_mutex->ReleaseMutex(); 294 // 293 //Printf("%i %lld\n",resume_period,GetTime()/1000000); 295 294 } else { 296 295 send_mutex->ReleaseMutex(); 297 296 // rien a faire, suspend 298 // 297 //Printf("rien a faire suspend\n"); 299 298 Suspend(); 300 // 299 //Printf("wake\n"); 301 300 // on planifie la prochaine execution 302 301 Time time = GetTime(); -
trunk/lib/FlairCore/src/unexported/IODevice_impl.h
r122 r157 47 47 void WriteToShMem(void); 48 48 void PrintLogsDescriptors(void); 49 void SetIsReady(bool status); 50 bool IsReady(void) const; 49 51 50 52 private: … … 59 61 bool outputtoshm; 60 62 flair::core::SharedMem *shmem; 63 bool isReady; 61 64 }; 62 65 -
trunk/lib/FlairFilter/src/AhrsComplementaryFilter.cpp
r24 r157 51 51 kb[1]=new DoubleSpinBox(parent->GetLayout()->LastRowLastCol(),"kb[1]:",0.,10,0.1,2,0.01); 52 52 kb[2]=new DoubleSpinBox(parent->GetLayout()->LastRowLastCol(),"kb[2]:",0.,10,0.1,2,0.01); 53 53 54 SetIsReady(true); 54 55 } 55 56 -
trunk/lib/FlairFilter/src/AhrsKalman.cpp
r18 r157 31 31 GetDatas(&ahrsData); 32 32 pimpl_=new AhrsKalman_impl(parent->GetLayout(),ahrsData); 33 34 SetIsReady(true); 33 35 } 34 36 -
trunk/lib/FlairFilter/src/ButterworthLowPass.cpp
r15 r157 35 35 pimpl_ = new ButterworthLowPass_impl(this, position, name, order); 36 36 AddDataToLog(pimpl_->output); 37 38 SetIsReady(true); 37 39 } 38 40 -
trunk/lib/FlairFilter/src/EulerDerivative.cpp
r15 r157 34 34 pimpl_ = new EulerDerivative_impl(this, position, name, init_value); 35 35 AddDataToLog(pimpl_->output); 36 37 SetIsReady(true); 36 38 } 37 39 -
trunk/lib/FlairFilter/src/Gx3_25_ahrs.cpp
r137 r157 30 30 SerialPort *serialport, Gx3_25_imu::Command_t command, 31 31 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 } 33 36 34 37 Gx3_25_ahrs::~Gx3_25_ahrs() {} 35 36 void Gx3_25_ahrs::Start(void) { ((Gx3_25_imu *)GetImu())->Start(); }37 38 38 39 // datas from Gx3_25_imu are AhrsData! -
trunk/lib/FlairFilter/src/Gx3_25_ahrs.h
r137 r157 47 47 ~Gx3_25_ahrs(); 48 48 49 /*!50 * \brief Start Gx3_25_imu Thread51 *52 */53 void Start(void);54 55 49 private: 56 50 /*! -
trunk/lib/FlairFilter/src/JoyReference.cpp
r15 r157 37 37 AddDataToLog(pimpl_->output); 38 38 AddDataToLog(pimpl_->ahrsData); 39 40 SetIsReady(true); 39 41 } 40 42 -
trunk/lib/FlairFilter/src/LowPassFilter.cpp
r15 r157 34 34 pimpl_ = new LowPassFilter_impl(this, position, name, init_value); 35 35 AddDataToLog(pimpl_->output); 36 37 SetIsReady(true); 36 38 } 37 39 -
trunk/lib/FlairFilter/src/NestedSat.cpp
r15 r157 33 33 : ControlLaw(position->getLayout(), name) { 34 34 pimpl_ = new NestedSat_impl(this, position, name); 35 36 SetIsReady(true); 35 37 } 36 38 -
trunk/lib/FlairFilter/src/Pid.cpp
r15 r157 32 32 : ControlLaw(position->getLayout(), name) { 33 33 pimpl_ = new Pid_impl(this, position, name); 34 35 SetIsReady(true); 34 36 } 35 37 -
trunk/lib/FlairFilter/src/PidThrust.cpp
r15 r157 33 33 : ControlLaw(position->getLayout(), name) { 34 34 pimpl_ = new PidThrust_impl(this, position, name); 35 36 SetIsReady(true); 35 37 } 36 38 -
trunk/lib/FlairFilter/src/SimuAhrs.cpp
r137 r157 29 29 SimuAhrs::SimuAhrs(string name, uint32_t dev_id, 30 30 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 } 32 34 33 35 SimuAhrs::~SimuAhrs() {} 34 35 void SimuAhrs::Start(void) { ((SimuImu *)GetImu())->Start(); }36 36 37 37 // datas from SimuImu are AhrsData! -
trunk/lib/FlairFilter/src/SimuAhrs.h
r137 r157 45 45 ~SimuAhrs(); 46 46 47 /*!48 * \brief Start SimuImu Thread49 *50 */51 void Start(void);52 53 47 private: 54 48 /*! -
trunk/lib/FlairFilter/src/TrajectoryGenerator1D.cpp
r15 r157 34 34 pimpl_ = new TrajectoryGenerator1D_impl(this, position, name, unit); 35 35 AddDataToLog(pimpl_->output); 36 SetIsReady(true); 36 37 } 37 38 -
trunk/lib/FlairFilter/src/TrajectoryGenerator2DCircle.cpp
r15 r157 35 35 pimpl_ = new TrajectoryGenerator2DCircle_impl(this, position, name); 36 36 AddDataToLog(pimpl_->output); 37 SetIsReady(true); 37 38 } 38 39 -
trunk/lib/FlairFilter/src/X4X8Multiplex.cpp
r137 r157 47 47 SetMultiplexComboBox(pimpl_->MotorName(i), i); 48 48 } 49 50 SetIsReady(true); 49 51 } 50 52 -
trunk/lib/FlairMeta/src/HdsX8.cpp
r137 r157 35 35 namespace meta { 36 36 37 HdsX8::HdsX8(string name, 37 HdsX8::HdsX8(string name,string options, 38 38 filter::UavMultiplex *multiplex) 39 39 : Uav(name, multiplex) { … … 56 56 57 57 void HdsX8::StartSensors(void) { 58 ((Gx3_25_ ahrs *)GetAhrs())->Start();58 ((Gx3_25_imu *)(GetAhrs()->GetImu()))->Start(); 59 59 ((Srf08 *)GetUsRangeFinder())->Start(); 60 60 ((Ps3Eye *)GetVerticalCamera())->Start(); 61 61 } 62 62 63 bool HdsX8::isReadyToFly(void) const { 64 return GetAhrs()->GetImu()->IsReady(); 65 } 66 63 67 } // end namespace meta 64 68 } // end namespace flair -
trunk/lib/FlairMeta/src/HdsX8.h
r122 r157 24 24 class HdsX8 : public Uav { 25 25 public: 26 HdsX8(std::string name, 26 HdsX8(std::string name,std::string options="", 27 27 filter::UavMultiplex *multiplex = NULL); 28 28 ~HdsX8(); 29 29 void StartSensors(void); 30 30 std::string GetDefaultVrpnAddress(void) const{return "192.168.147.197:3883";} 31 bool isReadyToFly(void) const; 31 32 32 33 private: -
trunk/lib/FlairMeta/src/MetaDualShock3.cpp
r137 r157 42 42 getFrameworkManager()->AddDeviceToLog(pimpl_->joy_ref); 43 43 controller->Start(); 44 45 SetIsReady(true); 44 46 } 45 47 -
trunk/lib/FlairMeta/src/SimuX4.cpp
r137 r157 26 26 #include <BatteryMonitor.h> 27 27 #include <Tab.h> 28 #include <FindArgument.h> 28 29 29 30 using std::string; … … 37 38 namespace meta { 38 39 39 SimuX4::SimuX4(string name, int simu_id, 40 SimuX4::SimuX4(string name, int simu_id,string options, 40 41 filter::UavMultiplex *multiplex) 41 42 : Uav(name, multiplex) { … … 51 52 SetBatteryMonitor(new BatteryMonitor(bat_tab->NewRow(), "battery")); 52 53 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 53 61 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)); 55 63 } 56 64 … … 58 66 59 67 void SimuX4::StartSensors(void) { 60 ((Simu Ahrs *)GetAhrs())->Start();68 ((SimuImu *)(GetAhrs()->GetImu()))->Start(); 61 69 ((SimuUs *)GetUsRangeFinder())->Start(); 62 70 ((SimuCamera *)GetVerticalCamera())->Start(); 63 71 } 64 72 73 65 74 } // end namespace meta 66 75 } // end namespace flair -
trunk/lib/FlairMeta/src/SimuX4.h
r122 r157 26 26 // simu_id: 0 if simulating only one UAV 27 27 //>0 otherwise 28 SimuX4(std::string name, int simu_id = 0, 28 SimuX4(std::string name, int simu_id = 0,std::string options="", 29 29 filter::UavMultiplex *multiplex = NULL); 30 30 ~SimuX4(); -
trunk/lib/FlairMeta/src/SimuX8.cpp
r137 r157 37 37 namespace meta { 38 38 39 SimuX8::SimuX8(string name, int simu_id, 39 SimuX8::SimuX8(string name, int simu_id,string options, 40 40 filter::UavMultiplex *multiplex) 41 41 : Uav(name, multiplex) { … … 58 58 59 59 void SimuX8::StartSensors(void) { 60 ((Simu Ahrs *)GetAhrs())->Start();60 ((SimuImu *)(GetAhrs()->GetImu()))->Start(); 61 61 ((SimuUs *)GetUsRangeFinder())->Start(); 62 62 ((SimuCamera *)GetVerticalCamera())->Start(); -
trunk/lib/FlairMeta/src/SimuX8.h
r122 r157 26 26 // simu_id: 0 if simulating only one UAV 27 27 //>0 otherwise 28 SimuX8(std::string name, int simu_id = 0, 28 SimuX8(std::string name, int simu_id = 0,std::string options="", 29 29 filter::UavMultiplex *multiplex = NULL); 30 30 ~SimuX8(); -
trunk/lib/FlairMeta/src/Uav.h
r122 r157 15 15 16 16 #include <Object.h> 17 #include <UsRangeFinder.h> 17 18 18 19 namespace flair { … … 62 63 sensor::Camera *GetHorizontalCamera(void) const; 63 64 virtual std::string GetDefaultVrpnAddress(void) const{return "127.0.0.1:3883";} 65 virtual bool isReadyToFly(void) const { return true;} 64 66 65 67 protected: -
trunk/lib/FlairMeta/src/UavFactory.cpp
r122 r157 30 30 31 31 namespace { // anonymous 32 vector<flair::meta::Uav* (*)(string,string, UavMultiplex*)> *vectoroffunctions=NULL;32 vector<flair::meta::Uav* (*)(string,string,string,UavMultiplex*)> *vectoroffunctions=NULL; 33 33 } 34 34 … … 41 41 42 42 43 Uav *CreateUav(string name, string uav_type,43 Uav *CreateUav(string name, string type,string options, 44 44 UavMultiplex *multiplex) { 45 45 … … 48 48 if(vectoroffunctions!=NULL) { 49 49 for(int i=0;i<vectoroffunctions->size();i++) { 50 uav=vectoroffunctions->at(i)(name, uav_type,multiplex);50 uav=vectoroffunctions->at(i)(name,type,options,multiplex); 51 51 if(uav!=NULL) { 52 52 free(vectoroffunctions); … … 57 57 } 58 58 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()); 61 61 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()); 68 68 return NULL; 69 } else if ( uav_type.compare(0, 7, "x4_simu") == 0) {69 } else if (type.compare(0, 7, "x4_simu") == 0) { 70 70 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()); 73 73 } 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) { 76 76 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()); 79 79 } 80 return new SimuX8(name, simu_id, multiplex);80 return new SimuX8(name, simu_id,options, multiplex); 81 81 } else { 82 getFrameworkManager()->Err("UAV type %s unknown\n", uav_type.c_str());82 getFrameworkManager()->Err("UAV type %s unknown\n", type.c_str()); 83 83 return NULL; 84 84 } 85 85 } 86 86 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*)>)); 87 void 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*)>)); 90 89 91 90 vectoroffunctions->push_back(func); -
trunk/lib/FlairMeta/src/UavFactory.h
r122 r157 21 21 #include <Uav.h> 22 22 23 flair::meta::Uav *CreateUav(std::string name, std::string type, 23 flair::meta::Uav *CreateUav(std::string name, std::string type,std::string options="", 24 24 flair::filter::UavMultiplex *multiplex = NULL); 25 25 26 void RegisterUavCreator(flair::meta::Uav*(*func)(std::string name, std::string type,27 flair::filter::UavMultiplex *multiplex));26 void RegisterUavCreator(flair::meta::Uav*(*func)(std::string,std::string,std::string, 27 flair::filter::UavMultiplex*)); 28 28 #endif // UAVFACTORY -
trunk/lib/FlairMeta/src/UavStateMachine.cpp
r153 r157 460 460 flagZTrajectoryFinished = false; 461 461 462 if((altitudeState==AltitudeState_t::Stopped) && safeToFly) {// && GetBatteryMonitor()->IsBatteryLow()==false)463 464 465 466 467 468 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); 469 469 470 470 uZ->SetOffset(); // positionne l'offset de compensation de la gravité à sa … … 481 481 SignalEvent(Event_t::TakingOff); 482 482 } else { 483 Warn("cannot takeoff\n"); 483 484 joy->ErrorNotify(); 484 485 } -
trunk/lib/FlairMeta/src/XAir.cpp
r137 r157 38 38 namespace meta { 39 39 40 XAir::XAir(string name, 40 XAir::XAir(string name, string options, 41 41 filter::UavMultiplex *multiplex) 42 42 : Uav(name, multiplex) { … … 61 61 62 62 void XAir::StartSensors(void) { 63 ((Gx3_25_ ahrs *)GetAhrs())->Start();63 ((Gx3_25_imu *)(GetAhrs()->GetImu()))->Start(); 64 64 ((Srf08 *)GetUsRangeFinder())->Start(); 65 65 ((Ps3Eye *)GetVerticalCamera())->Start(); 66 66 } 67 67 68 bool XAir::isReadyToFly(void) const { 69 return GetAhrs()->GetImu()->IsReady(); 70 } 71 68 72 } // end namespace meta 69 73 } // end namespace flair -
trunk/lib/FlairMeta/src/XAir.h
r122 r157 24 24 class XAir : public Uav { 25 25 public: 26 XAir(std::string name, 26 XAir(std::string name,std::string options="", 27 27 filter::UavMultiplex *multiplex = NULL); 28 28 ~XAir(); 29 29 void StartSensors(void); 30 30 std::string GetDefaultVrpnAddress(void) const{return "192.168.147.197:3883";} 31 bool isReadyToFly(void) const; 31 32 32 33 private: -
trunk/lib/FlairSensorActuator/src/AfroBldc.cpp
r15 r157 37 37 : Bldc(parent, layout, name, motors_count) { 38 38 pimpl_ = new AfroBldc_impl(this, layout, i2cport); 39 40 SetIsReady(true); 39 41 } 40 42 -
trunk/lib/FlairSensorActuator/src/BlCtrlV2.cpp
r15 r157 38 38 : Bldc(parent, layout, name, motors_count) { 39 39 pimpl_ = new BlCtrlV2_impl(this, layout, i2cport); 40 41 SetIsReady(true); 40 42 } 41 43 -
trunk/lib/FlairSensorActuator/src/BlCtrlV2_x4_speed.cpp
r148 r157 134 134 delete desc; 135 135 136 SetIsReady(true); 137 136 138 /* 137 139 -
trunk/lib/FlairSensorActuator/src/Bldc.cpp
r148 r157 61 61 : IODevice(parent, name) { 62 62 pimpl_ = new Bldc_impl(this, motors_count); 63 64 SetIsReady(true); 63 65 } 64 66 -
trunk/lib/FlairSensorActuator/src/Camera.cpp
r137 r157 50 50 setup_groupbox = new GroupBox(sensor_tab->NewRow(), name); 51 51 setup_layout = new GridLayout(sensor_tab->NewRow(), "setup"); 52 52 53 } 53 54 -
trunk/lib/FlairSensorActuator/src/EmulatedController.cpp
r137 r157 30 30 EmulatedController::EmulatedController(string name,uint8_t priority) : 31 31 TargetController(name,priority) { 32 SetIsReady(true); 32 33 } 33 34 -
trunk/lib/FlairSensorActuator/src/Gx3_25_imu_impl.cpp
r103 r157 96 96 SamplingSettings(); 97 97 GyrosBias(); 98 self->SetIsReady(true); 98 99 // RealignUpNorth(true,true); 99 100 … … 265 266 ssize_t written = 0; 266 267 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"); 269 269 270 270 command[0] = 0xcd; // entete … … 296 296 } 297 297 298 Printf("Gx3_25_imu::gyros_bias: %s ok\n", 299 self->IODevice::ObjectName().c_str()); 298 Printf("Gx3_25_imu::calibration done\n"); 300 299 301 300 } else { -
trunk/lib/FlairSensorActuator/src/HokuyoUTM30Lx.cpp
r148 r157 50 50 this->serialport = serialport; 51 51 serialport->SetRxTimeout(100000000); 52 53 SetIsReady(true); 52 54 } 53 55 -
trunk/lib/FlairSensorActuator/src/Mb800.cpp
r137 r157 33 33 this->serialport = serialport; 34 34 serialport->SetRxTimeout(100000000); 35 36 SetIsReady(true); 35 37 } 36 38 -
trunk/lib/FlairSensorActuator/src/Novatel.cpp
r137 r157 32 32 : NmeaGps(name, NMEAFlags), Thread(getFrameworkManager(), name, priority) { 33 33 this->serialport = serialport; 34 35 SetIsReady(true); 34 36 } 35 37 -
trunk/lib/FlairSensorActuator/src/Ps3Eye.cpp
r137 r157 27 27 uint8_t priority) 28 28 : V4LCamera( name, camera_index, 320, 240, 29 cvimage::Type::Format::YUYV, priority) {} 29 cvimage::Type::Format::YUYV, priority) { 30 SetIsReady(true); 31 } 30 32 31 33 Ps3Eye::~Ps3Eye() {} -
trunk/lib/FlairSensorActuator/src/RadioReceiver.cpp
r148 r157 53 53 54 54 AddDataToLog(output); 55 56 SetIsReady(true); 55 57 } 56 58 -
trunk/lib/FlairSensorActuator/src/SimuBldc.cpp
r15 r157 42 42 GroupBox *groupbox = new GroupBox(layout->NewRow(), "simubldc"); 43 43 k = new DoubleSpinBox(groupbox->NewRow(), "k driver:", 0, 10000, 1); 44 45 SetIsReady(true); 44 46 } 45 47 … … 58 60 59 61 shmem->Write((char *)&values, motors_count * sizeof(float)); 62 63 SetIsReady(true); 60 64 } 61 65 -
trunk/lib/FlairSensorActuator/src/SimuCamera.cpp
r151 r157 45 45 dev_name << "simu_cam_" << dev_id; 46 46 shmem = new SharedMem((Thread *)this, dev_name.str().c_str(), buf_size, SharedMem::Type::producerConsumer); 47 48 SetIsReady(true); 47 49 } 48 50 … … 59 61 buf_size, SharedMem::Type::producerConsumer); 60 62 shmemReadBuf=NULL; 63 64 SetIsReady(true); 61 65 } 62 66 -
trunk/lib/FlairSensorActuator/src/SimuGps.cpp
r137 r157 53 53 shmem = new SharedMem((Thread *)this, dev_name.str().c_str(), 54 54 sizeof(gps_states_t)); 55 56 SetIsReady(true); 55 57 } 56 58 … … 64 66 shmem = new SharedMem((Thread *)this, dev_name.str().c_str(), 65 67 sizeof(gps_states_t)); 68 69 SetIsReady(true); 66 70 } 67 71 -
trunk/lib/FlairSensorActuator/src/SimuImu.cpp
r137 r157 45 45 shmem = new SharedMem((Thread *)this, dev_name.str().c_str(), 46 46 sizeof(imu_states_t)); 47 SetIsReady(true); 47 48 } 48 49 … … 55 56 shmem = new SharedMem((Thread *)this, dev_name.str().c_str(), 56 57 sizeof(imu_states_t)); 58 SetIsReady(true); 57 59 } 58 60 -
trunk/lib/FlairSensorActuator/src/SimuLaser.cpp
r137 r157 41 41 dev_name << "simu_Laser_" << dev_id; 42 42 shmem = new SharedMem((Thread *)this, dev_name.str().c_str(), 43 360 * sizeof(float)); //**** 43 360 * sizeof(float)); 44 SetIsReady(true); 44 45 } 45 46 … … 52 53 shmem = new SharedMem((Thread *)this, dev_name.str().c_str(), 53 54 360 * sizeof(float)); 55 SetIsReady(true); 54 56 } 55 57 -
trunk/lib/FlairSensorActuator/src/SimuUs.cpp
r137 r157 41 41 dev_name << "simu_us_" << dev_id; 42 42 shmem = new SharedMem((Thread *)this, dev_name.str().c_str(), sizeof(float)); 43 44 SetIsReady(true); 43 45 } 44 46 … … 50 52 dev_name << "simu_us_" << dev_id; 51 53 shmem = new SharedMem((Thread *)this, dev_name.str().c_str(), sizeof(float)); 54 55 SetIsReady(true); 52 56 } 53 57 -
trunk/lib/FlairSensorActuator/src/Srf08.cpp
r137 r157 53 53 SetRange(); 54 54 SetMaxGain(); 55 56 SetIsReady(true); 55 57 } 56 58 -
trunk/lib/FlairSensorActuator/src/VrpnObject.cpp
r140 r157 35 35 pimpl_ = new VrpnObject_impl(this, name, -1, tab); 36 36 AddDataToLog(pimpl_->output); 37 38 SetIsReady(true); 37 39 } 38 40 … … 43 45 pimpl_ = new VrpnObject_impl(this, name, id, tab); 44 46 AddDataToLog(pimpl_->output); 47 48 SetIsReady(true); 45 49 } 46 50 -
trunk/lib/FlairSensorActuator/src/XBldc.cpp
r15 r157 30 30 : Bldc(parent, layout, name, 4) { 31 31 pimpl_ = new XBldc_impl(this, i2cport); 32 33 SetIsReady(true); 32 34 } 33 35 -
trunk/lib/FlairSimulator/src/Man.cpp
r134 r157 60 60 r_speed = new DoubleSpinBox(setup_tab->NewRow(), "rotational speed (deg/s):", 61 61 0, 180, 10); 62 63 SetIsReady(true); 62 64 } 63 65 -
trunk/lib/FlairSimulator/src/X4.cpp
r15 r157 76 76 77 77 motors = new SimuBldc(this, name, 4, dev_id); 78 79 SetIsReady(true); 78 80 } 79 81 -
trunk/lib/FlairSimulator/src/X4.h
r69 r157 19 19 20 20 #include <Model.h> 21 #include <stdint.h>22 #include <stdio.h>23 21 24 22 namespace flair { -
trunk/lib/FlairSimulator/src/X8.cpp
r15 r157 85 85 86 86 motors = new SimuBldc(this, name, 8, dev_id); 87 88 SetIsReady(true); 87 89 } 88 90 -
trunk/lib/FlairSimulator/src/X8.h
r69 r157 19 19 20 20 #include <Model.h> 21 #include <stdint.h>22 21 23 22 namespace flair { -
trunk/lib/FlairVisionFilter/src/CvtColor.cpp
r124 r157 37 37 Err("conversion not supported\n"); 38 38 } 39 40 SetIsReady(true); 39 41 } 40 42 -
trunk/lib/FlairVisionFilter/src/HoughLines.cpp
r148 r157 56 56 if(imageType.GetFormat()!=cvimage::Type::Format::Gray) { 57 57 Err("input image is not gray\n"); 58 return; 58 59 } 59 60 } catch(std::bad_cast& bc) { 60 61 Err("io type mismatch\n"); 62 return; 61 63 } 64 65 SetIsReady(true); 62 66 } 63 67 -
trunk/lib/FlairVisionFilter/src/ImgThreshold.cpp
r124 r157 36 36 } else { 37 37 Err("input image is not gray\n"); 38 return; 38 39 } 39 40 } catch(std::bad_cast& bc) { 40 41 Err("io type mismatch\n"); 42 return; 41 43 } 44 SetIsReady(true); 42 45 } 43 46 -
trunk/lib/FlairVisionFilter/src/OpticalFlow.cpp
r144 r157 48 48 pyr=NULL; 49 49 pyr_old=NULL; 50 return; 50 51 } 51 52 … … 63 64 found_feature=(char *)cvAlloc(max_features->Value()*sizeof(char)); 64 65 feature_error=(unsigned int *)cvAlloc(max_features->Value()*sizeof(unsigned int)); 66 67 SetIsReady(true); 65 68 } 66 69 -
trunk/lib/FlairVisionFilter/src/OpticalFlowSpeed.cpp
r148 r157 34 34 35 35 AddDataToLog(output); 36 37 SetIsReady(true); 36 38 } 37 39 -
trunk/lib/FlairVisionFilter/src/Sobel.cpp
r124 r157 38 38 } else { 39 39 Err("input image is not gray\n"); 40 return; 40 41 } 41 42 42 43 } catch(std::bad_cast& bc) { 43 44 Err("io type mismatch\n"); 45 return; 44 46 } 47 SetIsReady(true); 45 48 } 46 49
Note:
See TracChangeset
for help on using the changeset viewer.