- Timestamp:
- Jan 6, 2017, 1:56:26 PM (8 years ago)
- Location:
- trunk
- Files:
-
- 50 added
- 15 deleted
- 50 edited
Legend:
- Unmodified
- Added
- Removed
-
trunk/ReleaseNotes
r121 r122 3 3 - added fixed cameras in simulator, see $FLAIR_ROOT/flair-bin/models/indoor_fligh 4 4 t_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. 6 See 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 5 10 6 11 ----------------------------------------------------------- -
trunk/demos/CircleFollower/uav/src/CircleFollower.cpp
r121 r122 39 39 using namespace flair::meta; 40 40 41 CircleFollower::CircleFollower(Uav* uav,TargetController *controller): UavStateMachine(uav,controller), behaviourMode(BehaviourMode_t::Default), vrpnLost(false) { 42 uav->SetupVRPNAutoIP(uav->ObjectName()); 43 41 CircleFollower::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 44 49 startCircle=new PushButton(GetButtonsLayout()->NewRow(),"start_circle"); 45 50 stopCircle=new PushButton(GetButtonsLayout()->LastRowLastCol(),"stop_circle"); 46 51 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); 49 54 } else { 50 targetVrpn=new MetaVrpnObject( uav->GetVrpnClient(),"target");55 targetVrpn=new MetaVrpnObject("target"); 51 56 } 52 57 53 58 getFrameworkManager()->AddDeviceToLog(targetVrpn); 54 59 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"); 61 66 62 67 uX=new Pid(setupLawTab->At(1,0),"u_x"); … … 79 84 //get yaw from vrpn 80 85 Euler vrpnEuler; 81 GetUav()->GetVrpnObject()->GetEuler(vrpnEuler);86 uavVrpn->GetEuler(vrpnEuler); 82 87 83 88 //get roll, pitch and w from imu … … 98 103 Vector3D uav_pos,uav_vel; 99 104 100 GetUav()->GetVrpnObject()->GetPosition(uav_pos);101 GetUav()->GetVrpnObject()->GetSpeed(uav_vel);105 uavVrpn->GetPosition(uav_pos); 106 uavVrpn->GetSpeed(uav_vel); 102 107 //z and dz must be in uav's frame 103 108 z=-uav_pos.z; … … 131 136 Vector2D uav_2Dpos,uav_2Dvel; // in VRPN coordinate system 132 137 133 GetUav()->GetVrpnObject()->GetPosition(uav_pos);134 GetUav()->GetVrpnObject()->GetSpeed(uav_vel);138 uavVrpn->GetPosition(uav_pos); 139 uavVrpn->GetSpeed(uav_vel); 135 140 136 141 uav_pos.To2Dxy(uav_2Dpos); … … 195 200 Land(); 196 201 } 197 if (! GetUav()->GetVrpnObject()->IsTracked(500)) {202 if (!uavVrpn->IsTracked(500)) { 198 203 Thread::Err("VRPN, uav lost\n"); 199 204 vrpnLost=true; … … 239 244 circle->SetCenter(target_2Dpos); 240 245 241 GetUav()->GetVrpnObject()->GetPosition(uav_pos);246 uavVrpn->GetPosition(uav_pos); 242 247 uav_pos.To2Dxy(uav_2Dpos); 243 248 circle->StartTraj(uav_2Dpos); … … 258 263 Vector3D vrpn_pos; 259 264 260 GetUav()->GetVrpnObject()->GetEuler(vrpn_euler);265 uavVrpn->GetEuler(vrpn_euler); 261 266 yawHold=vrpn_euler.yaw; 262 267 263 GetUav()->GetVrpnObject()->GetPosition(vrpn_pos);268 uavVrpn->GetPosition(vrpn_pos); 264 269 vrpn_pos.To2Dxy(posHold); 265 270 -
trunk/demos/CircleFollower/uav/src/CircleFollower.h
r38 r122 34 34 class CircleFollower : public flair::meta::UavStateMachine { 35 35 public: 36 CircleFollower(flair:: meta::Uav* uav,flair::sensor::TargetController *controller);36 CircleFollower(flair::sensor::TargetController *controller); 37 37 ~CircleFollower(); 38 38 … … 65 65 66 66 flair::gui::PushButton *startCircle,*stopCircle; 67 flair::meta::MetaVrpnObject *targetVrpn ;67 flair::meta::MetaVrpnObject *targetVrpn,*uavVrpn; 68 68 flair::filter::TrajectoryGenerator2DCircle *circle; 69 69 flair::core::AhrsData *customReferenceOrientation,*customOrientation; -
trunk/demos/CircleFollower/uav/src/main.cpp
r38 r122 45 45 manager->SetupLogger(log_path); 46 46 47 Uav* drone=CreateUav( manager,name,uav_type);47 Uav* drone=CreateUav(name,uav_type); 48 48 TargetEthController *controller=new TargetEthController(manager,"Dualshock3",ds3port); 49 CircleFollower* demo=new CircleFollower( drone,controller);49 CircleFollower* demo=new CircleFollower(controller); 50 50 51 51 demo->Start(); -
trunk/demos/Gps/uav/CMakeLists.txt
r89 r122 6 6 SET(FLAIR_USE_SENSOR_ACTUATOR TRUE) 7 7 SET(FLAIR_USE_META TRUE) 8 SET(FLAIR_USE_VRPN TRUE)9 8 SET(FLAIR_USE_GPS TRUE) 10 9 -
trunk/demos/Gps/uav/src/DemoGps.cpp
r101 r122 39 39 using namespace flair::meta; 40 40 41 DemoGps::DemoGps( Uav* uav,TargetController *controller): UavStateMachine(uav,controller), behaviourMode(BehaviourMode_t::Default) {42 41 DemoGps::DemoGps(TargetController *controller): UavStateMachine(controller), behaviourMode(BehaviourMode_t::Default) { 42 Uav* uav=GetUav(); 43 43 startCircle=new PushButton(GetButtonsLayout()->NewRow(),"start_circle"); 44 44 stopCircle=new PushButton(GetButtonsLayout()->LastRowLastCol(),"stop_circle"); -
trunk/demos/Gps/uav/src/DemoGps.h
r89 r122 33 33 class DemoGps : public flair::meta::UavStateMachine { 34 34 public: 35 DemoGps(flair:: meta::Uav* uav,flair::sensor::TargetController *controller);35 DemoGps(flair::sensor::TargetController *controller); 36 36 ~DemoGps(); 37 37 -
trunk/demos/Gps/uav/src/main.cpp
r89 r122 45 45 manager->SetupLogger(log_path); 46 46 47 Uav* drone=CreateUav( manager,name,uav_type);47 Uav* drone=CreateUav(name,uav_type); 48 48 TargetEthController *controller=new TargetEthController(manager,"Dualshock3",ds3port); 49 DemoGps* demo=new DemoGps( drone,controller);49 DemoGps* demo=new DemoGps(controller); 50 50 51 51 demo->Start(); -
trunk/demos/SimpleFleet/uav/src/SimpleFleet.cpp
r104 r122 50 50 51 51 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); 52 SimpleFleet::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); 64 69 65 70 //parent->AddDeviceToLog(Uz()); … … 101 106 //get yaw from vrpn 102 107 Euler vrpnEuler; 103 GetUav()->GetVrpnObject()->GetEuler(vrpnEuler);108 uavVrpn->GetEuler(vrpnEuler); 104 109 105 110 //get roll, pitch and w from imu … … 120 125 Vector3D uav_pos,uav_vel; 121 126 122 GetUav()->GetVrpnObject()->GetPosition(uav_pos);123 GetUav()->GetVrpnObject()->GetSpeed(uav_vel);127 uavVrpn->GetPosition(uav_pos); 128 uavVrpn->GetSpeed(uav_vel); 124 129 //z and dz must be in uav's frame 125 130 z=-uav_pos.z; … … 154 159 Euler vrpn_euler; // in VRPN coordinate system 155 160 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); 159 164 160 165 uav_pos.To2Dxy(uav_2Dpos); … … 294 299 void SimpleFleet::ExtraSecurityCheck(void) { 295 300 if (!vrpnLost && behaviourMode!=BehaviourMode_t::Default) { 296 if (! GetUav()->GetVrpnObject()->IsTracked(500)) {301 if (!uavVrpn->IsTracked(500)) { 297 302 Thread::Err("Optitrack, uav lost\n"); 298 303 vrpnLost=true; … … 322 327 circle->SetCenter(target_2Dpos); 323 328 324 GetUav()->GetVrpnObject()->GetPosition(uav_pos);329 uavVrpn->GetPosition(uav_pos); 325 330 uav_pos.To2Dxy(uav_2Dpos); 326 331 circle->StartTraj(uav_2Dpos,1); … … 347 352 } 348 353 349 GetUav()->GetVrpnObject()->GetEuler(vrpn_euler);354 uavVrpn->GetEuler(vrpn_euler); 350 355 yaw_hold=vrpn_euler.yaw; 351 356 352 GetUav()->GetVrpnObject()->GetPosition(vrpn_pos);357 uavVrpn->GetPosition(vrpn_pos); 353 358 vrpn_pos.To2Dxy(pos_hold); 354 359 -
trunk/demos/SimpleFleet/uav/src/SimpleFleet.h
r38 r122 26 26 class TrajectoryGenerator2DCircle; 27 27 } 28 namespace meta { 29 class MetaVrpnObject; 30 } 28 31 namespace gui { 29 32 class DoubleSpinBox; … … 34 37 class SimpleFleet : public flair::meta::UavStateMachine { 35 38 public: 36 SimpleFleet( flair::meta::Uav* uav,std::string broadcast,flair::sensor::TargetController *controller);39 SimpleFleet(std::string broadcast,flair::sensor::TargetController *controller); 37 40 ~SimpleFleet(); 38 41 … … 75 78 flair::gui::DoubleSpinBox *xCircleCenter,*yCircleCenter,*yDisplacement; 76 79 flair::core::AhrsData *customReferenceOrientation,*customOrientation; 80 flair::meta::MetaVrpnObject *uavVrpn; 77 81 }; 78 82 -
trunk/demos/SimpleFleet/uav/src/main.cpp
r38 r122 46 46 manager->SetupUserInterface(xml_file); 47 47 48 Uav* drone=CreateUav( manager,name,uav_type);48 Uav* drone=CreateUav(name,uav_type); 49 49 TargetEthController *controller=new TargetEthController(manager,"Dualshock3",ds3port); 50 SimpleFleet* demo=new SimpleFleet( drone,broadcast,controller);50 SimpleFleet* demo=new SimpleFleet(broadcast,controller); 51 51 52 52 demo->Start(); -
trunk/demos/Skeletons/CustomReferenceAngles/CMakeLists.txt
r43 r122 6 6 SET(FLAIR_USE_SENSOR_ACTUATOR TRUE) 7 7 SET(FLAIR_USE_META TRUE) 8 SET(FLAIR_USE_VRPN TRUE)9 8 10 9 include($ENV{FLAIR_ROOT}/flair-dev/cmake-modules/GlobalCmakeFlair.cmake) -
trunk/demos/Skeletons/CustomReferenceAngles/src/MyApp.cpp
r43 r122 29 29 using namespace flair::sensor; 30 30 31 MyApp::MyApp( Uav* uav,TargetController *controller): UavStateMachine(uav,controller), behaviourMode(BehaviourMode_t::Default) {31 MyApp::MyApp(TargetController *controller): UavStateMachine(controller), behaviourMode(BehaviourMode_t::Default) { 32 32 start_CustomAngles=new PushButton(GetButtonsLayout()->NewRow(),"start CustomReferenceAngles"); 33 33 stop_CustomAngles=new PushButton(GetButtonsLayout()->NewRow(),"stop CustomReferenceAngles"); 34 34 35 35 customReferenceOrientation= new AhrsData(this,"reference"); 36 uav->GetAhrs()->AddPlot(customReferenceOrientation,DataPlot::Yellow);36 GetUav()->GetAhrs()->AddPlot(customReferenceOrientation,DataPlot::Yellow); 37 37 AddDataToControlLawLog(customReferenceOrientation); 38 38 } -
trunk/demos/Skeletons/CustomReferenceAngles/src/MyApp.h
r43 r122 31 31 class MyApp : public flair::meta::UavStateMachine { 32 32 public: 33 MyApp(flair:: meta::Uav* uav,flair::sensor::TargetController *controller);33 MyApp(flair::sensor::TargetController *controller); 34 34 ~MyApp(); 35 35 -
trunk/demos/Skeletons/CustomReferenceAngles/src/main.cpp
r43 r122 44 44 manager->SetupLogger(log_path); 45 45 46 Uav* drone=CreateUav( manager,name,uav_type);46 Uav* drone=CreateUav(name,uav_type); 47 47 TargetEthController *controller=new TargetEthController(manager,"Dualshock3",ds3port); 48 MyApp* app=new MyApp( drone,controller);48 MyApp* app=new MyApp(controller); 49 49 50 50 app->Start(); -
trunk/demos/Skeletons/CustomTorques/CMakeLists.txt
r43 r122 6 6 SET(FLAIR_USE_SENSOR_ACTUATOR TRUE) 7 7 SET(FLAIR_USE_META TRUE) 8 SET(FLAIR_USE_VRPN TRUE)9 8 10 9 include($ENV{FLAIR_ROOT}/flair-dev/cmake-modules/GlobalCmakeFlair.cmake) -
trunk/demos/Skeletons/CustomTorques/src/MyApp.cpp
r43 r122 26 26 using namespace flair::sensor; 27 27 28 MyApp::MyApp( Uav* uav,TargetController *controller): UavStateMachine(uav,controller), behaviourMode(BehaviourMode_t::Default) {28 MyApp::MyApp(TargetController *controller): UavStateMachine(controller), behaviourMode(BehaviourMode_t::Default) { 29 29 start_CustomTorques=new PushButton(GetButtonsLayout()->NewRow(),"start CustomTorques"); 30 30 stop_CustomTorques=new PushButton(GetButtonsLayout()->NewRow(),"stop CustomTorques"); -
trunk/demos/Skeletons/CustomTorques/src/MyApp.h
r43 r122 28 28 class MyApp : public flair::meta::UavStateMachine { 29 29 public: 30 MyApp(flair:: meta::Uav* uav,flair::sensor::TargetController *controller);30 MyApp(flair::sensor::TargetController *controller); 31 31 ~MyApp(); 32 32 -
trunk/demos/Skeletons/CustomTorques/src/main.cpp
r43 r122 45 45 manager->SetupLogger(log_path); 46 46 47 Uav* drone=CreateUav( manager,name,uav_type);47 Uav* drone=CreateUav(name,uav_type); 48 48 TargetEthController *controller=new TargetEthController(manager,"Dualshock3",ds3port); 49 MyApp* app=new MyApp( drone,controller);49 MyApp* app=new MyApp(controller); 50 50 51 51 app->Start(); -
trunk/lib/FlairCore/src/FrameworkManager.cpp
r55 r122 178 178 } 179 179 180 bool FrameworkManager::IsDeviceLogged(const IODevice *device) const { 181 return pimpl_->IsDeviceLogged(device); 182 } 183 180 184 void FrameworkManager::StartLog(void) { pimpl_->StartLog(); } 181 185 -
trunk/lib/FlairCore/src/FrameworkManager.h
r55 r122 121 121 */ 122 122 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; 123 133 124 134 /*! -
trunk/lib/FlairCore/src/FrameworkManager_impl.cpp
r118 r122 630 630 631 631 if (is_logging == false) { 632 if (device->pimpl_->SetToBeLogged()) { 632 if (!device->pimpl_->IsSetToBeLogged()) { 633 device->pimpl_->SetToBeLogged(); 633 634 log_desc_t tmp; 634 635 tmp.device = device; … … 640 641 Err("impossible while logging\n"); 641 642 } 643 } 644 645 bool FrameworkManager_impl::IsDeviceLogged(const IODevice *device) const { 646 return device->pimpl_->IsSetToBeLogged(); 642 647 } 643 648 -
trunk/lib/FlairCore/src/IODevice_impl.cpp
r15 r122 106 106 } 107 107 108 bool IODevice_impl::SetToBeLogged(void) { 108 bool IODevice_impl::IsSetToBeLogged(void) const{ 109 return tobelogged; 110 } 111 112 void IODevice_impl::SetToBeLogged(void) { 109 113 if (!tobelogged) { 110 114 tobelogged = true; 111 return true;112 115 } else { 113 116 self->Warn("already added to log\n"); 114 return false;115 117 } 116 118 } 117 119 118 120 void IODevice_impl::WriteLogsDescriptors(fstream &desc_file, int *index) { 119 // own descriptor 121 //Printf("WriteLogsDescriptors %s\n",self->ObjectName().c_str()); 122 // own descriptor 120 123 for (size_t i = 0; i < datasToLog.size(); i++) 121 124 datasToLog.at(i)->pimpl_->WriteLogDescriptor(desc_file, index); … … 127 130 for (size_t i = 0; i < devicesToLog.size(); i++) 128 131 devicesToLog.at(i)->pimpl_->WriteLogsDescriptors(desc_file, index); 132 //Printf("WriteLogsDescriptors %s ok\n",self->ObjectName().c_str()); 129 133 } 130 134 … … 194 198 195 199 void 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); 197 201 198 202 // copy state to buf 199 203 for (size_t i = 0; i < datasToLog.size(); i++) { 200 // printf("copy \n");204 // printf("copy %s\n",datasToLog.at(i)->ObjectName().c_str()); 201 205 datasToLog.at(i)->CopyDatas(*ptr); 202 206 (*ptr) += datasToLog.at(i)->GetDataType().GetSize(); -
trunk/lib/FlairCore/src/io_data_impl.cpp
r15 r122 42 42 43 43 void 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"); 44 45 for (size_t i = 0; i < descriptors.size(); i++) { 45 46 desc_file << (*index)++ << ": " << self->ObjectName() << " - " -
trunk/lib/FlairCore/src/unexported/FrameworkManager_impl.h
r55 r122 48 48 void SetupLogger(std::string log_path); 49 49 void AddDeviceToLog(flair::core::IODevice *device); 50 bool IsDeviceLogged(const flair::core::IODevice *device) const; 50 51 void StartLog(); 51 52 void StopLog(); -
trunk/lib/FlairCore/src/unexported/IODevice_impl.h
r15 r122 42 42 void WriteLog(flair::core::Time time); 43 43 void AddDeviceToLog(const flair::core::IODevice *device); 44 bool SetToBeLogged(void); // return true if possible 44 void SetToBeLogged(void); 45 bool IsSetToBeLogged(void) const; 45 46 void OutputToShMem(bool enabled); 46 47 void WriteToShMem(void); -
trunk/lib/FlairMeta/src/HdsX8.cpp
r107 r122 35 35 namespace meta { 36 36 37 HdsX8::HdsX8( FrameworkManager *parent, string uav_name,37 HdsX8::HdsX8(string name, 38 38 filter::UavMultiplex *multiplex) 39 : Uav( parent, uav_name, multiplex) {40 RTDM_I2cPort *i2cport = new RTDM_I2cPort( parent, "rtdm_i2c", "rti2c3");41 RTDM_SerialPort *imu_port = new RTDM_SerialPort( parent, "imu_port", "rtser1");39 : Uav(name, multiplex) { 40 RTDM_I2cPort *i2cport = new RTDM_I2cPort(getFrameworkManager(), "rtdm_i2c", "rti2c3"); 41 RTDM_SerialPort *imu_port = new RTDM_SerialPort(getFrameworkManager(), "imu_port", "rtser1"); 42 42 43 43 if (multiplex == NULL) 44 SetMultiplex(new X4X8Multiplex( parent, "motors", X4X8Multiplex::X8));44 SetMultiplex(new X4X8Multiplex(getFrameworkManager(), "motors", X4X8Multiplex::X8)); 45 45 46 46 SetBldc(new BlCtrlV2(GetUavMultiplex(), GetUavMultiplex()->GetLayout(), 47 47 "motors", GetUavMultiplex()->MotorsCount(), i2cport)); 48 SetUsRangeFinder(new Srf08( parent, "SRF08", i2cport, 0x70, 60));49 SetAhrs(new Gx3_25_ahrs( parent, "imu", imu_port,48 SetUsRangeFinder(new Srf08(getFrameworkManager(), "SRF08", i2cport, 0x70, 60)); 49 SetAhrs(new Gx3_25_ahrs(getFrameworkManager(), "imu", imu_port, 50 50 Gx3_25_imu::AccelerationAngularRateAndOrientationMatrix, 70)); 51 51 SetBatteryMonitor(((BlCtrlV2 *)GetBldc())->GetBatteryMonitor()); 52 53 /* 54 if(VRPNType==Auto || VRPNType==AutoSerialPort) 55 { 56 RTDM_SerialPort* vrpn_port=new 57 RTDM_SerialPort(parent,"vrpn_port","rtser3"); 58 59 vrpnclient=new VrpnClient(parent,"vrpn",vrpn_port,10000,80); 60 uav_vrpn=new 61 MetaVrpnObject(vrpnclient,uav_name,VRPNSerialObjectId); 62 } 63 */ 64 SetVerticalCamera(new Ps3Eye(parent, "camv", 0, 50)); 52 SetVerticalCamera(new Ps3Eye(getFrameworkManager(), "camv", 0, 50)); 65 53 } 66 54 … … 71 59 ((Srf08 *)GetUsRangeFinder())->Start(); 72 60 ((Ps3Eye *)GetVerticalCamera())->Start(); 73 Uav::StartSensors();74 61 } 75 62 -
trunk/lib/FlairMeta/src/HdsX8.h
r22 r122 24 24 class HdsX8 : public Uav { 25 25 public: 26 HdsX8( core::FrameworkManager *parent, std::string uav_name,26 HdsX8(std::string name, 27 27 filter::UavMultiplex *multiplex = NULL); 28 28 ~HdsX8(); 29 29 void StartSensors(void); 30 std::string GetDefaultVrpnAddress(void) const{return "192.168.147.197:3883";} 30 31 31 32 private: -
trunk/lib/FlairMeta/src/MetaVrpnObject.cpp
r15 r122 39 39 namespace meta { 40 40 41 MetaVrpnObject::MetaVrpnObject( const VrpnClient *parent,string name)42 : VrpnObject( parent, name, parent->GetTabWidget()) {43 ConstructorCommon( parent,name);41 MetaVrpnObject::MetaVrpnObject(string name) 42 : VrpnObject( name, GetVrpnClient()->GetTabWidget()) { 43 ConstructorCommon(name); 44 44 } 45 45 46 MetaVrpnObject::MetaVrpnObject( const VrpnClient *parent,std::string name,46 MetaVrpnObject::MetaVrpnObject(std::string name, 47 47 uint8_t id) 48 : VrpnObject( parent, name, id, parent->GetTabWidget()) {49 ConstructorCommon( parent,name);48 : VrpnObject(name, id, GetVrpnClient()->GetTabWidget()) { 49 ConstructorCommon( name); 50 50 } 51 51 52 void MetaVrpnObject::ConstructorCommon( const VrpnClient *parent,string name) {52 void MetaVrpnObject::ConstructorCommon(string name) { 53 53 cvmatrix_descriptor *desc = new cvmatrix_descriptor(6, 1); 54 54 for (int i = 0; i < 6; i++) { … … 60 60 } 61 61 62 pbas = new LowPassFilter(this, parent->GetLayout()->NewRow(),62 pbas = new LowPassFilter(this, GetVrpnClient()->GetLayout()->NewRow(), 63 63 name + " Passe bas", prev_value); 64 64 … … 72 72 } 73 73 74 euler = new EulerDerivative(pbas, parent->GetLayout()->NewRow(),74 euler = new EulerDerivative(pbas, GetVrpnClient()->GetLayout()->NewRow(), 75 75 name + "_euler", prev_value); 76 76 … … 82 82 vz_opti_plot->AddCurve(euler->Matrix()->Element(5)); 83 83 84 plot_tab = new Tab( parent->GetTabWidget(), "Mesures (xy) " + name);84 plot_tab = new Tab(GetVrpnClient()->GetTabWidget(), "Mesures (xy) " + name); 85 85 xy_plot = new DataPlot2D(plot_tab->NewRow(), "xy", "y", -5, 5, "x", -5, 5); 86 86 xy_plot->AddCurve(Output()->Element(4, 0), Output()->Element(3, 0)); -
trunk/lib/FlairMeta/src/MetaVrpnObject.h
r15 r122 18 18 19 19 namespace flair { 20 namespace core { 21 class Vector3D; 22 class FloatType; 23 } 24 namespace gui { 25 class DataPlot1D; 26 class DataPlot2D; 27 class Tab; 28 } 29 namespace filter { 30 class EulerDerivative; 31 class LowPassFilter; 32 } 33 namespace sensor { 34 class VrpnClient; 35 } 20 namespace core { 21 class Vector3D; 22 class FloatType; 23 } 24 namespace gui { 25 class DataPlot1D; 26 class DataPlot2D; 27 class Tab; 28 } 29 namespace filter { 30 class EulerDerivative; 31 class LowPassFilter; 32 } 36 33 } 37 34 … … 47 44 class MetaVrpnObject : public sensor::VrpnObject { 48 45 public: 49 MetaVrpnObject(const sensor::VrpnClient *parent, std::string name); 50 MetaVrpnObject(const sensor::VrpnClient *parent, std::string name, 51 uint8_t id); 46 MetaVrpnObject(std::string name); 47 MetaVrpnObject(std::string name,uint8_t id); 52 48 ~MetaVrpnObject(); 53 49 gui::DataPlot1D *VxPlot(void) const; // 1,0 … … 58 54 59 55 private: 60 void ConstructorCommon( const sensor::VrpnClient *parent,std::string name);56 void ConstructorCommon(std::string name); 61 57 filter::LowPassFilter *pbas; 62 58 filter::EulerDerivative *euler; -
trunk/lib/FlairMeta/src/SimuX4.cpp
r22 r122 37 37 namespace meta { 38 38 39 SimuX4::SimuX4( FrameworkManager *parent, string uav_name, int simu_id,39 SimuX4::SimuX4(string name, int simu_id, 40 40 filter::UavMultiplex *multiplex) 41 : Uav( parent, uav_name, multiplex) {41 : Uav(name, multiplex) { 42 42 43 43 if (multiplex == NULL) 44 SetMultiplex(new X4X8Multiplex( parent, "motors", X4X8Multiplex::X4));44 SetMultiplex(new X4X8Multiplex(getFrameworkManager(), "motors", X4X8Multiplex::X4)); 45 45 46 46 SetBldc(new SimuBldc(GetUavMultiplex(), GetUavMultiplex()->GetLayout(), 47 47 "motors", GetUavMultiplex()->MotorsCount(), simu_id)); 48 SetUsRangeFinder(new SimuUs( parent, "us", simu_id, 60));49 SetAhrs(new SimuAhrs( parent, "imu", simu_id, 70));50 Tab *bat_tab = new Tab( parent->GetTabWidget(), "battery");48 SetUsRangeFinder(new SimuUs(getFrameworkManager(), "us", simu_id, 60)); 49 SetAhrs(new SimuAhrs(getFrameworkManager(), "imu", simu_id, 70)); 50 Tab *bat_tab = new Tab(getFrameworkManager()->GetTabWidget(), "battery"); 51 51 SetBatteryMonitor(new BatteryMonitor(bat_tab->NewRow(), "battery")); 52 52 GetBatteryMonitor()->SetBatteryValue(12); 53 53 SetVerticalCamera( 54 new SimuCamera( parent, "simu_cam_v", 320, 240, 3, simu_id, 10));54 new SimuCamera(getFrameworkManager(), "simu_cam_v", 320, 240, 3, simu_id, 10)); 55 55 } 56 56 … … 61 61 ((SimuUs *)GetUsRangeFinder())->Start(); 62 62 ((SimuCamera *)GetVerticalCamera())->Start(); 63 Uav::StartSensors();64 63 } 65 66 void SimuX4::SetupVRPNAutoIP(string name) { SetupVRPN("127.0.0.1:3883", name); }67 64 68 65 } // end namespace meta -
trunk/lib/FlairMeta/src/SimuX4.h
r22 r122 26 26 // simu_id: 0 if simulating only one UAV 27 27 //>0 otherwise 28 SimuX4( core::FrameworkManager *parent, std::string uav_name, int simu_id = 0,28 SimuX4(std::string name, int simu_id = 0, 29 29 filter::UavMultiplex *multiplex = NULL); 30 30 ~SimuX4(); 31 31 void StartSensors(void); 32 void SetupVRPNAutoIP(std::string name);33 32 }; 34 33 } // end namespace meta -
trunk/lib/FlairMeta/src/SimuX8.cpp
r22 r122 37 37 namespace meta { 38 38 39 SimuX8::SimuX8( FrameworkManager *parent, string uav_name, int simu_id,39 SimuX8::SimuX8(string name, int simu_id, 40 40 filter::UavMultiplex *multiplex) 41 : Uav( parent, uav_name, multiplex) {41 : Uav(name, multiplex) { 42 42 43 43 if (multiplex == NULL) 44 SetMultiplex(new X4X8Multiplex( parent, "motors", X4X8Multiplex::X8));44 SetMultiplex(new X4X8Multiplex(getFrameworkManager(), "motors", X4X8Multiplex::X8)); 45 45 46 46 SetBldc(new SimuBldc(GetUavMultiplex(), GetUavMultiplex()->GetLayout(), 47 47 "motors", GetUavMultiplex()->MotorsCount(), simu_id)); 48 SetUsRangeFinder(new SimuUs( parent, "us", simu_id, 60));49 SetAhrs(new SimuAhrs( parent, "imu", simu_id, 70));50 Tab *bat_tab = new Tab( parent->GetTabWidget(), "battery");48 SetUsRangeFinder(new SimuUs(getFrameworkManager(), "us", simu_id, 60)); 49 SetAhrs(new SimuAhrs(getFrameworkManager(), "imu", simu_id, 70)); 50 Tab *bat_tab = new Tab(getFrameworkManager()->GetTabWidget(), "battery"); 51 51 SetBatteryMonitor(new BatteryMonitor(bat_tab->NewRow(), "battery")); 52 52 GetBatteryMonitor()->SetBatteryValue(12); 53 53 SetVerticalCamera( 54 new SimuCamera( parent, "simu_cam_v", 320, 240, 3, simu_id, 10));54 new SimuCamera(getFrameworkManager(), "simu_cam_v", 320, 240, 3, simu_id, 10)); 55 55 } 56 56 … … 61 61 ((SimuUs *)GetUsRangeFinder())->Start(); 62 62 ((SimuCamera *)GetVerticalCamera())->Start(); 63 Uav::StartSensors();64 63 } 65 66 void SimuX8::SetupVRPNAutoIP(string name) { SetupVRPN("127.0.0.1:3883", name); }67 64 68 65 } // end namespace meta -
trunk/lib/FlairMeta/src/SimuX8.h
r22 r122 26 26 // simu_id: 0 if simulating only one UAV 27 27 //>0 otherwise 28 SimuX8( core::FrameworkManager *parent, std::string uav_name, int simu_id = 0,28 SimuX8(std::string name, int simu_id = 0, 29 29 filter::UavMultiplex *multiplex = NULL); 30 30 ~SimuX8(); 31 31 void StartSensors(void); 32 void SetupVRPNAutoIP(std::string name);33 32 }; 34 33 } // end namespace meta -
trunk/lib/FlairMeta/src/Uav.cpp
r121 r122 38 38 using namespace flair::actuator; 39 39 40 namespace { 41 flair::meta::Uav *uavSingleton = NULL; 42 } 43 40 44 namespace flair { 41 45 namespace meta { 42 46 43 Uav::Uav(FrameworkManager *parent, string name, UavMultiplex *multiplex) 44 : Object(parent, name) { 45 vrpnclient = NULL; 46 uav_vrpn = NULL; 47 Uav *GetUav(void) { return uavSingleton; } 48 49 Uav::Uav(string name, UavMultiplex *multiplex) 50 : Object(getFrameworkManager(), name) { 51 if (uavSingleton != NULL) { 52 Err("Uav must be instanced only one time\n"); 53 return; 54 } 55 56 uavSingleton = this; 47 57 verticalCamera = NULL; 48 58 horizontalCamera = NULL; … … 82 92 horizontalCamera = (Camera *)inHorizontalCamera; 83 93 } 84 /*85 void Uav::SetupVRPNSerial(SerialPort *vrpn_port,string name,int86 VRPNSerialObjectId) {87 vrpnclient=new VrpnClient(getFrameworkManager(),"vrpn",vrpn_port,10000,80);88 uav_vrpn=new MetaVrpnObject(vrpnclient,name,VRPNSerialObjectId);89 94 90 getFrameworkManager()->AddDeviceToLog(uav_vrpn);91 }92 */93 void Uav::SetupVRPNAutoIP(string name) {94 SetupVRPN("192.168.147.197:3883", name);95 }96 97 void Uav::SetupVRPN(string optitrack_address, string name) {98 vrpnclient = new VrpnClient(getFrameworkManager(), "vrpn", optitrack_address,99 10000, 80);100 uav_vrpn = new MetaVrpnObject(vrpnclient, name);101 102 getFrameworkManager()->AddDeviceToLog(uav_vrpn);103 104 GetAhrs()->YawPlot()->AddCurve(uav_vrpn->State()->Element(2),105 DataPlot::Green);106 // GetAhrs()->RollPlot()->AddCurve(uav_vrpn->State()->Element(0),DataPlot::Green);107 // GetAhrs()->PitchPlot()->AddCurve(uav_vrpn->State()->Element(1),DataPlot::Green);108 }109 110 void Uav::StartSensors(void) {111 if (vrpnclient != NULL) {112 vrpnclient->Start();113 }114 }115 95 void Uav::UseDefaultPlot(void) { 116 96 multiplex->UseDefaultPlot(); … … 184 164 BatteryMonitor *Uav::GetBatteryMonitor(void) const { return battery; } 185 165 186 VrpnClient *Uav::GetVrpnClient(void) const {187 if (vrpnclient == NULL)188 Err("vrpn is not setup, call SetupVRPN before\n");189 return vrpnclient;190 }191 192 MetaVrpnObject *Uav::GetVrpnObject(void) const { return uav_vrpn; }193 194 166 Camera *Uav::GetVerticalCamera(void) const { return verticalCamera; } 195 167 -
trunk/lib/FlairMeta/src/Uav.h
r121 r122 17 17 18 18 namespace flair { 19 namespace core { 20 class FrameworkManager; 21 } 22 namespace filter { 23 class Ahrs; 24 class UavMultiplex; 25 } 26 namespace actuator { 27 class Bldc; 28 } 29 namespace sensor { 30 class UsRangeFinder; 31 class BatteryMonitor; 32 class VrpnClient; 33 class Imu; 34 class Camera; 35 } 19 namespace filter { 20 class Ahrs; 21 class UavMultiplex; 22 } 23 namespace actuator { 24 class Bldc; 25 } 26 namespace sensor { 27 class UsRangeFinder; 28 class BatteryMonitor; 29 class Imu; 30 class Camera; 31 } 36 32 } 37 33 … … 39 35 namespace meta { 40 36 class MetaUsRangeFinder; 41 class MetaVrpnObject;42 37 43 38 /*! \class Uav 44 39 * 45 * \brief Base class to construct sensors/actuators depending on uav type 40 * \brief Base class to construct sensors/actuators depending on uav type. 41 * The Object is created with 42 * the FrameworkManager as parent. FrameworkManager must be created before. 43 * Only one instance of this class is allowed by program. 46 44 */ 47 45 class Uav : public core::Object { 48 46 public: 49 /* 50 typedef enum { 51 None, 52 Auto,//rt serial if hds x4 ou x8, auto ip sinon 53 AutoIP, 54 UserDefinedIP, 55 AutoSerialPort, 56 } VRPNType_t; 57 */ 58 // uav_name: for optitrack 59 Uav(core::FrameworkManager *parent, std::string name, 47 48 Uav(std::string name, 60 49 filter::UavMultiplex *multiplex = NULL); 61 50 ~Uav(); 62 void SetupVRPN(std::string optitrack_address, std::string name);63 // vrpn serial: broken, need to add serial port in uav specific code64 // void SetupVRPNSerial(core::SerialPort *vrpn_port,std::string name,int65 // VRPNSerialObjectId);66 virtual void SetupVRPNAutoIP(std::string name);67 51 68 virtual void StartSensors(void) ;52 virtual void StartSensors(void)=0; 69 53 void UseDefaultPlot(void); 70 54 actuator::Bldc *GetBldc(void) const; … … 75 59 sensor::UsRangeFinder *GetUsRangeFinder(void) const; 76 60 sensor::BatteryMonitor *GetBatteryMonitor(void) const; 77 sensor::VrpnClient *GetVrpnClient(void) const;78 meta::MetaVrpnObject *GetVrpnObject(void) const;79 61 sensor::Camera *GetVerticalCamera(void) const; 80 62 sensor::Camera *GetHorizontalCamera(void) const; 63 virtual std::string GetDefaultVrpnAddress(void) const{return "127.0.0.1:3883";} 81 64 82 65 protected: … … 96 79 sensor::UsRangeFinder *us; 97 80 MetaUsRangeFinder *meta_us; 98 sensor::VrpnClient *vrpnclient;99 MetaVrpnObject *uav_vrpn;100 81 sensor::BatteryMonitor *battery; 101 82 sensor::Camera *verticalCamera,*horizontalCamera; 102 83 }; 84 85 /*! 86 * \brief get Uav 87 * 88 * \return the Uav 89 */ 90 Uav *GetUav(void); 91 103 92 } // end namespace meta 104 93 } // end namespace flair -
trunk/lib/FlairMeta/src/UavFactory.cpp
r45 r122 30 30 31 31 namespace { // anonymous 32 vector<flair::meta::Uav* (*)( FrameworkManager*,string,string,UavMultiplex*)> *vectoroffunctions=NULL;32 vector<flair::meta::Uav* (*)(string,string,UavMultiplex*)> *vectoroffunctions=NULL; 33 33 } 34 34 … … 41 41 42 42 43 Uav *CreateUav( FrameworkManager *parent, string uav_name, string uav_type,43 Uav *CreateUav(string name, string uav_type, 44 44 UavMultiplex *multiplex) { 45 45 … … 48 48 if(vectoroffunctions!=NULL) { 49 49 for(int i=0;i<vectoroffunctions->size();i++) { 50 uav=vectoroffunctions->at(i)( parent, uav_name,uav_type,multiplex);50 uav=vectoroffunctions->at(i)(name,uav_type,multiplex); 51 51 if(uav!=NULL) { 52 52 free(vectoroffunctions); … … 58 58 59 59 if (uav_type == "hds_x4") { 60 parent->Err("UAV type %s not yet implemented\n", uav_type.c_str());60 getFrameworkManager()->Err("UAV type %s not yet implemented\n", uav_type.c_str()); 61 61 return NULL; 62 62 } else if (uav_type == "hds_x8") { 63 return new HdsX8( parent, uav_name, multiplex);63 return new HdsX8(name, multiplex); 64 64 } else if (uav_type == "xair") { 65 return new XAir( parent, uav_name, multiplex);65 return new XAir(name, multiplex); 66 66 } else if (uav_type == "hds_xufo") { 67 parent->Err("UAV type %s not yet implemented\n", uav_type.c_str());67 getFrameworkManager()->Err("UAV type %s not yet implemented\n", uav_type.c_str()); 68 68 return NULL; 69 69 } else if (uav_type.compare(0, 7, "x4_simu") == 0) { … … 72 72 simu_id = atoi(uav_type.substr(7, uav_type.size() - 7).c_str()); 73 73 } 74 return new SimuX4( parent, uav_name, simu_id, multiplex);74 return new SimuX4(name, simu_id, multiplex); 75 75 } else if (uav_type.compare(0, 7, "x8_simu") == 0) { 76 76 int simu_id = 0; … … 78 78 simu_id = atoi(uav_type.substr(7, uav_type.size() - 7).c_str()); 79 79 } 80 return new SimuX8( parent, uav_name, simu_id, multiplex);80 return new SimuX8(name, simu_id, multiplex); 81 81 } else { 82 parent->Err("UAV type %s unknown\n", uav_type.c_str());82 getFrameworkManager()->Err("UAV type %s unknown\n", uav_type.c_str()); 83 83 return NULL; 84 84 } 85 85 } 86 86 87 void RegisterUavCreator(flair::meta::Uav*(*func)( FrameworkManager *parent, string uav_name, string uav_type,87 void RegisterUavCreator(flair::meta::Uav*(*func)(string name, string type, 88 88 UavMultiplex *multiplex)) { 89 if(vectoroffunctions==NULL) vectoroffunctions=(vector<flair::meta::Uav* (*)( FrameworkManager*,string,string,UavMultiplex*)>*)malloc(sizeof(vector<flair::meta::Uav* (*)(FrameworkManager*,string,string,UavMultiplex*)>));89 if(vectoroffunctions==NULL) vectoroffunctions=(vector<flair::meta::Uav* (*)(string,string,UavMultiplex*)>*)malloc(sizeof(vector<flair::meta::Uav* (*)(string,string,UavMultiplex*)>)); 90 90 91 91 vectoroffunctions->push_back(func); -
trunk/lib/FlairMeta/src/UavFactory.h
r41 r122 21 21 #include <Uav.h> 22 22 23 flair::meta::Uav *CreateUav(flair::core::FrameworkManager *parent, 24 std::string uav_name, std::string uav_type, 23 flair::meta::Uav *CreateUav(std::string name, std::string type, 25 24 flair::filter::UavMultiplex *multiplex = NULL); 26 25 27 void RegisterUavCreator(flair::meta::Uav*(*func)(flair::core::FrameworkManager *parent, 28 std::string uav_name, std::string uav_type, 26 void RegisterUavCreator(flair::meta::Uav*(*func)(std::string name, std::string type, 29 27 flair::filter::UavMultiplex *multiplex)); 30 28 #endif // UAVFACTORY -
trunk/lib/FlairMeta/src/UavStateMachine.cpp
r106 r122 52 52 using namespace flair::meta; 53 53 54 UavStateMachine::UavStateMachine( Uav* inUav,TargetController *controller):54 UavStateMachine::UavStateMachine(TargetController *controller): 55 55 Thread(getFrameworkManager(),"UavStateMachine",50), 56 uav( inUav),controller(controller),failSafeMode(true),flagConnectionLost(false),flagBatteryLow(false),flagCriticalSensorLost(false),flagZTrajectoryFinished(false),safeToFly(true){56 uav(GetUav()),controller(controller),failSafeMode(true),flagConnectionLost(false),flagBatteryLow(false),flagCriticalSensorLost(false),flagZTrajectoryFinished(false),safeToFly(true){ 57 57 altitudeState=AltitudeState_t::Stopped; 58 58 uav->UseDefaultPlot(); … … 135 135 return currentAngularSpeed; 136 136 } 137 138 const Uav *UavStateMachine::GetUav(void) const { return uav; }139 137 140 138 void UavStateMachine::AltitudeValues(float &altitude, -
trunk/lib/FlairMeta/src/UavStateMachine.h
r45 r122 59 59 * 60 60 * \brief State machine for UAV 61 * 62 * thread synchronized with ahrs, unless a period is set with SetPeriodUS or 63 *SetPeriodMS 61 * The Thread is created with 62 * the FrameworkManager as parent. FrameworkManager must be created before. 63 * The Thread is synchronized with Ahrs, unless a period is set with SetPeriodUS or 64 * SetPeriodMS 64 65 */ 65 66 … … 101 102 }; 102 103 103 UavStateMachine( meta::Uav* uav,sensor::TargetController* controller);104 UavStateMachine(sensor::TargetController* controller); 104 105 ~UavStateMachine(); 105 106 … … 107 108 108 109 const core::Vector3D &GetCurrentAngularSpeed(void) const; 109 110 const meta::Uav *GetUav(void) const;111 110 112 111 void Land(void); -
trunk/lib/FlairMeta/src/XAir.cpp
r100 r122 38 38 namespace meta { 39 39 40 XAir::XAir( FrameworkManager *parent, string uav_name,40 XAir::XAir(string name, 41 41 filter::UavMultiplex *multiplex) 42 : Uav( parent, uav_name, multiplex) {43 RTDM_I2cPort *i2cport = new RTDM_I2cPort( parent, "rtdm_i2c", "rti2c3");44 RTDM_SerialPort *imu_port = new RTDM_SerialPort( parent, "imu_port", "rtser1");42 : Uav(name, multiplex) { 43 RTDM_I2cPort *i2cport = new RTDM_I2cPort(getFrameworkManager(), "rtdm_i2c", "rti2c3"); 44 RTDM_SerialPort *imu_port = new RTDM_SerialPort(getFrameworkManager(), "imu_port", "rtser1"); 45 45 46 46 if (multiplex == NULL) 47 SetMultiplex(new X4X8Multiplex( parent, "motors", X4X8Multiplex::X8));47 SetMultiplex(new X4X8Multiplex(getFrameworkManager(), "motors", X4X8Multiplex::X8)); 48 48 49 49 SetBldc(new AfroBldc(GetUavMultiplex(), GetUavMultiplex()->GetLayout(), 50 50 "motors", GetUavMultiplex()->MotorsCount(), i2cport)); 51 SetUsRangeFinder(new Srf08( parent, "SRF08", i2cport, 0x70, 60));52 SetAhrs(new Gx3_25_ahrs( parent, "imu", imu_port,51 SetUsRangeFinder(new Srf08(getFrameworkManager(), "SRF08", i2cport, 0x70, 60)); 52 SetAhrs(new Gx3_25_ahrs(getFrameworkManager(), "imu", imu_port, 53 53 Gx3_25_imu::AccelerationAngularRateAndOrientationMatrix, 70)); 54 Tab *bat_tab = new Tab( parent->GetTabWidget(), "battery");54 Tab *bat_tab = new Tab(getFrameworkManager()->GetTabWidget(), "battery"); 55 55 SetBatteryMonitor(new BatteryMonitor(bat_tab->NewRow(), "battery")); 56 56 GetBatteryMonitor()->SetBatteryValue(12); 57 58 /* 59 if(VRPNType==Auto || VRPNType==AutoSerialPort) 60 { 61 RTDM_SerialPort* vrpn_port=new 62 RTDM_SerialPort(parent,"vrpn_port","rtser3"); 63 64 vrpnclient=new VrpnClient(parent,"vrpn",vrpn_port,10000,80); 65 uav_vrpn=new 66 MetaVrpnObject(vrpnclient,uav_name,VRPNSerialObjectId); 67 } 68 */ 69 SetVerticalCamera(new Ps3Eye(parent, "camv", 0, 50)); 57 SetVerticalCamera(new Ps3Eye(getFrameworkManager(), "camv", 0, 50)); 70 58 } 71 59 … … 76 64 ((Srf08 *)GetUsRangeFinder())->Start(); 77 65 ((Ps3Eye *)GetVerticalCamera())->Start(); 78 Uav::StartSensors();79 66 } 80 67 -
trunk/lib/FlairMeta/src/XAir.h
r22 r122 24 24 class XAir : public Uav { 25 25 public: 26 XAir( core::FrameworkManager *parent, std::string uav_name,26 XAir(std::string name, 27 27 filter::UavMultiplex *multiplex = NULL); 28 28 ~XAir(); 29 29 void StartSensors(void); 30 std::string GetDefaultVrpnAddress(void) const{return "192.168.147.197:3883";} 30 31 31 32 private: -
trunk/lib/FlairSensorActuator/src/Camera.cpp
r121 r122 24 24 #include <DataPlot1D.h> 25 25 #include <Picture.h> 26 #include <Buffer.h>27 26 #include <highgui.h> 28 27 #include <fstream> … … 39 38 : IODevice(parent, name) { 40 39 plot_tab = NULL; 41 jpgBuffer=NULL;42 40 logFormat=LogFormat::NONE; 43 41 … … 63 61 64 62 output = NULL; 65 jpgBuffer=NULL;66 63 logFormat=LogFormat::NONE; 67 64 } … … 80 77 break; 81 78 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"); 88 81 break; 82 default: 83 Warn("LogFormat unknown\n"); 89 84 } 90 85 } … … 119 114 120 115 void 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 } 125 123 } 126 124 IODevice::ProcessUpdate(data); -
trunk/lib/FlairSensorActuator/src/Camera.h
r121 r122 25 25 class Picture; 26 26 class GridLayout; 27 }28 namespace core {29 class Buffer;30 27 } 31 28 } … … 163 160 gui::GridLayout *setup_layout; 164 161 LogFormat logFormat; 165 core::Buffer *jpgBuffer;166 162 }; 167 163 } // end namespace sensor -
trunk/lib/FlairSensorActuator/src/VrpnClient.cpp
r15 r122 26 26 using namespace flair::gui; 27 27 28 namespace { 29 flair::sensor::VrpnClient *singleton = NULL; 30 } 31 32 28 33 namespace flair { 29 34 namespace sensor { 30 35 31 VrpnClient::VrpnClient(const FrameworkManager *parent, string name, 36 VrpnClient *GetVrpnClient(void) { return singleton; } 37 38 VrpnClient::VrpnClient(string name, 32 39 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; 34 47 pimpl_ = new VrpnClient_impl(this, name, address, us_period); 35 48 } 36 49 37 VrpnClient::VrpnClient( const FrameworkManager *parent,string name,50 VrpnClient::VrpnClient(string name, 38 51 SerialPort *serialport, uint16_t us_period, 39 52 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; 41 60 pimpl_ = new VrpnClient_impl(this, name, serialport, us_period); 42 61 } -
trunk/lib/FlairSensorActuator/src/VrpnClient.h
r15 r122 18 18 19 19 namespace 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 } 28 27 } 29 28 … … 35 34 /*! \class VrpnClient 36 35 * 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. 38 39 */ 39 40 class VrpnClient : public core::Thread { … … 46 47 * Construct a VrpnClient. Connection is done by IP. 47 48 * 48 * \param parent parent49 49 * \param name name 50 50 * \param address server address … … 52 52 * \param priority priority of the Thread 53 53 */ 54 VrpnClient( const core::FrameworkManager *parent,std::string name,54 VrpnClient(std::string name, 55 55 std::string address, uint16_t us_period, uint8_t priority); 56 56 … … 60 60 * Construct a VrpnClient. Connection is done by XBee modem. 61 61 * 62 * \param parent parent63 62 * \param name name 64 63 * \param serialport SerialPort for XBee modem … … 66 65 * \param priority priority of the Thread 67 66 */ 68 VrpnClient( const core::FrameworkManager *parent,std::string name,67 VrpnClient(std::string name, 69 68 core::SerialPort *serialport, uint16_t us_period, 70 69 uint8_t priority); … … 108 107 class VrpnClient_impl *pimpl_; 109 108 }; 109 110 /*! 111 * \brief get VrpnClient 112 * 113 * \return the VrpnClient 114 */ 115 VrpnClient *GetVrpnClient(void); 116 110 117 } // end namespace sensor 111 118 } // end namespace flair -
trunk/lib/FlairSensorActuator/src/VrpnObject.cpp
r15 r122 30 30 namespace sensor { 31 31 32 VrpnObject::VrpnObject( const VrpnClient *parent,string name,32 VrpnObject::VrpnObject(string name, 33 33 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); 36 36 AddDataToLog(pimpl_->output); 37 37 } 38 38 39 VrpnObject::VrpnObject( const VrpnClient *parent,string name, uint8_t id,39 VrpnObject::VrpnObject(string name, uint8_t id, 40 40 const TabWidget *tab) 41 : IODevice( parent, name) {41 : IODevice(GetVrpnClient(), name) { 42 42 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); 44 44 AddDataToLog(pimpl_->output); 45 45 } -
trunk/lib/FlairSensorActuator/src/VrpnObject.h
r15 r122 19 19 20 20 namespace 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 } 32 32 } 33 33 … … 41 41 /*! \class VrpnObject 42 42 * 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. 44 45 */ 45 46 class VrpnObject : public core::IODevice { … … 53 54 * Construct a VrpnObject. Connection is done by IP. 54 55 * 55 * \param parent parent56 56 * \param name VRPN object name, should be the same as defined in the server 57 57 * \param tab Tab for the user interface 58 58 */ 59 VrpnObject( const VrpnClient *parent,std::string name,59 VrpnObject(std::string name, 60 60 const gui::TabWidget *tab); 61 61 … … 65 65 * Construct a VrpnObject. Connection is done by IP. 66 66 * 67 * \param parent parent68 67 * \param name name 69 68 * \param id VRPN object id, should be the same as defined in the server 70 69 * \param tab Tab for the user interface 71 70 */ 72 VrpnObject( const VrpnClient *parent,std::string name, uint8_t id,71 VrpnObject(std::string name, uint8_t id, 73 72 const gui::TabWidget *tab); 74 73 -
trunk/lib/FlairSensorActuator/src/VrpnObject_impl.cpp
r15 r122 39 39 using namespace flair::sensor; 40 40 41 VrpnObject_impl::VrpnObject_impl(VrpnObject *self, const VrpnClient *parent,41 VrpnObject_impl::VrpnObject_impl(VrpnObject *self, 42 42 string name, int id, const TabWidget *tab) { 43 this->parent = parent;43 parent = GetVrpnClient(); 44 44 this->self = self; 45 45 46 if(parent==NULL) { 47 self->Err("VrpnClient must be instanced before creating VrpnObject\n"); 48 return; 49 } 46 50 if (id == -1 && parent->UseXbee()) { 47 51 self->Err("erreur aucun identifiant specifie pour la connexion Xbee\n"); -
trunk/lib/FlairSensorActuator/src/unexported/VrpnObject_impl.h
r15 r122 26 26 27 27 namespace 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 } 42 42 } 43 43 … … 47 47 public: 48 48 VrpnObject_impl(flair::sensor::VrpnObject *self, 49 const flair::sensor::VrpnClient *parent,std::string name,49 std::string name, 50 50 int id, const flair::gui::TabWidget *tab); 51 51 ~VrpnObject_impl(void);
Note:
See TracChangeset
for help on using the changeset viewer.