Changeset 13 in flair-dev for trunk/include/FlairMeta


Ignore:
Timestamp:
Apr 8, 2016, 3:39:24 PM (9 years ago)
Author:
Bayard Gildas
Message:

formatting script + include reformatted

Location:
trunk/include/FlairMeta
Files:
10 edited

Legend:

Unmodified
Added
Removed
  • trunk/include/FlairMeta/HdsX8.h

    r9 r13  
    1616#include "Uav.h"
    1717
    18 namespace flair
    19 {
    20 namespace meta
    21 {
    22     /*! \class HdsX8
    23     *
    24     * \brief Class defining an ardrone2 uav
    25     */
    26     class HdsX8 : public Uav {
    27         public:
    28             HdsX8(core::FrameworkManager* parent,std::string uav_name,filter::UavMultiplex *multiplex=NULL);
    29             ~HdsX8();
    30             void StartSensors(void);
     18namespace flair {
     19namespace meta {
     20/*! \class HdsX8
     21*
     22* \brief Class defining an ardrone2 uav
     23*/
     24class HdsX8 : public Uav {
     25public:
     26  HdsX8(core::FrameworkManager *parent, std::string uav_name,
     27        filter::UavMultiplex *multiplex = NULL);
     28  ~HdsX8();
     29  void StartSensors(void);
    3130
    32         private:
    33 
    34     };
     31private:
     32};
    3533} // end namespace meta
    3634} // end namespace flair
  • trunk/include/FlairMeta/MetaDualShock3.h

    r9 r13  
    1717
    1818namespace flair {
    19     namespace core {
    20         class AhrsData;
    21         class Quaternion;
    22     }
    23     namespace filter {
    24         class Ahrs;
    25     }
     19namespace core {
     20class AhrsData;
     21class Quaternion;
     22}
     23namespace filter {
     24class Ahrs;
     25}
    2626}
    2727
     
    3131namespace meta {
    3232
    33     /*! \class MetaDualShock3
    34     *
    35     * \brief Classe intégrant la manette MetaDualShock3
    36     */
    37     class MetaDualShock3 : public sensor::TargetEthController {
    38         friend class ::MetaDualShock3_impl;
     33/*! \class MetaDualShock3
     34*
     35* \brief Classe intégrant la manette MetaDualShock3
     36*/
     37class MetaDualShock3 : public sensor::TargetEthController {
     38  friend class ::MetaDualShock3_impl;
    3939
    40         public:
    41             MetaDualShock3(core::FrameworkManager* parent,std::string name,uint16_t port,uint8_t priority);
    42             ~MetaDualShock3();
    43             core::AhrsData* GetReferenceOrientation(void) const;
    44             float ZRef(void) const;
    45             float DzRef(void) const;
    46             void SetYawRef(float value);
    47             /*!
    48             * \brief Set yaw reference
    49             *
    50             * Yaw part of the output quaternion is obtained by integrating the wz desired angular speed.\n
    51             * This method reset the yaw.
    52             *
    53             * \param value value, only the yaw part of the quaternion is used
    54             */
    55             void SetYawRef(core::Quaternion const &value);
    56             void SetZRef(float value);
    57             float RollTrim(void) const;
    58             float PitchTrim(void) const;
    59             void ErrorNotify(void);
    60             void Rumble(uint8_t left_force,uint8_t left_timeout=20,uint8_t right_force=0,uint8_t right_timeout=0);
    61             void SetLedON(unsigned int ledId);
    62             void SetLedOFF(unsigned int ledId);
    63             void FlashLed(unsigned int ledId,uint8_t on_timeout,uint8_t off_timeout);
     40public:
     41  MetaDualShock3(core::FrameworkManager *parent, std::string name,
     42                 uint16_t port, uint8_t priority);
     43  ~MetaDualShock3();
     44  core::AhrsData *GetReferenceOrientation(void) const;
     45  float ZRef(void) const;
     46  float DzRef(void) const;
     47  void SetYawRef(float value);
     48  /*!
     49  * \brief Set yaw reference
     50  *
     51  * Yaw part of the output quaternion is obtained by integrating the wz desired
     52  *angular speed.\n
     53  * This method reset the yaw.
     54  *
     55  * \param value value, only the yaw part of the quaternion is used
     56  */
     57  void SetYawRef(core::Quaternion const &value);
     58  void SetZRef(float value);
     59  float RollTrim(void) const;
     60  float PitchTrim(void) const;
     61  void ErrorNotify(void);
     62  void Rumble(uint8_t left_force, uint8_t left_timeout = 20,
     63              uint8_t right_force = 0, uint8_t right_timeout = 0);
     64  void SetLedON(unsigned int ledId);
     65  void SetLedOFF(unsigned int ledId);
     66  void FlashLed(unsigned int ledId, uint8_t on_timeout, uint8_t off_timeout);
    6467
    65         private:
    66             class MetaDualShock3_impl* pimpl_;
    67 
    68     };
     68private:
     69  class MetaDualShock3_impl *pimpl_;
     70};
    6971} // end namespace meta
    7072} // end namespace flair
  • trunk/include/FlairMeta/MetaUsRangeFinder.h

    r9 r13  
    1717
    1818namespace flair {
    19     namespace filter {
    20         class ButterworthLowPass;
    21         class EulerDerivative;
    22     }
    23     namespace sensor {
    24         class UsRangeFinder;
    25     }
    26     namespace gui {
    27         class DataPlot1D;
    28     }
     19namespace filter {
     20class ButterworthLowPass;
     21class EulerDerivative;
     22}
     23namespace sensor {
     24class UsRangeFinder;
     25}
     26namespace gui {
     27class DataPlot1D;
     28}
    2929}
    3030
    31 namespace flair
    32 {
    33 namespace meta
    34 {
    35     /*! \class MetaUsRangeFinder
    36     *
    37     * \brief Classe haut niveau pour capteur à ultra son
    38     *
    39     * Contient une dérivée d'euler et un passe bas.
    40     * Cette classe est adaptée pour un capteur d'altitude.
    41     */
    42     class MetaUsRangeFinder: public core::Object {
    43         public:
    44             MetaUsRangeFinder(sensor::UsRangeFinder* us);
    45             ~MetaUsRangeFinder();
    46             void UseDefaultPlot(void);
    47             float z(void) const;
    48             float Vz(void) const;
    49             gui::DataPlot1D *GetZPlot();
    50             gui::DataPlot1D *GetVzPlot();
     31namespace flair {
     32namespace meta {
     33/*! \class MetaUsRangeFinder
     34*
     35* \brief Classe haut niveau pour capteur à ultra son
     36*
     37* Contient une dérivée d'euler et un passe bas.
     38* Cette classe est adaptée pour un capteur d'altitude.
     39*/
     40class MetaUsRangeFinder : public core::Object {
     41public:
     42  MetaUsRangeFinder(sensor::UsRangeFinder *us);
     43  ~MetaUsRangeFinder();
     44  void UseDefaultPlot(void);
     45  float z(void) const;
     46  float Vz(void) const;
     47  gui::DataPlot1D *GetZPlot();
     48  gui::DataPlot1D *GetVzPlot();
    5149
    52         private:
    53             sensor::UsRangeFinder* us;
    54             filter::ButterworthLowPass *pbas_z,*pbas_vz;
    55             filter::EulerDerivative *vz_euler;
    56             gui::DataPlot1D* vz_plot;
    57     };
     50private:
     51  sensor::UsRangeFinder *us;
     52  filter::ButterworthLowPass *pbas_z, *pbas_vz;
     53  filter::EulerDerivative *vz_euler;
     54  gui::DataPlot1D *vz_plot;
     55};
    5856} // end namespace meta
    5957} // end namespace flair
  • trunk/include/FlairMeta/MetaVrpnObject.h

    r9 r13  
    1717#include "io_data.h"
    1818
    19 namespace flair
    20 {
    21     namespace core
    22     {
    23         class Vector3D;
    24         class FloatType;
    25     }
    26     namespace gui
    27     {
    28         class DataPlot1D;
    29         class DataPlot2D;
    30         class Tab;
    31     }
    32     namespace filter
    33     {
    34         class EulerDerivative;
    35         class LowPassFilter;
    36     }
    37     namespace sensor
    38     {
    39         class VrpnClient;
    40     }
     19namespace flair {
     20namespace core {
     21class Vector3D;
     22class FloatType;
     23}
     24namespace gui {
     25class DataPlot1D;
     26class DataPlot2D;
     27class Tab;
     28}
     29namespace filter {
     30class EulerDerivative;
     31class LowPassFilter;
     32}
     33namespace sensor {
     34class VrpnClient;
     35}
    4136}
    4237
    43 namespace flair
    44 {
    45 namespace meta
    46 {
     38namespace flair {
     39namespace meta {
    4740
    48     /*! \class MetaVrpnObject
    49     *
    50     * \brief Classe haut niveau intégrant un objet VRPN
    51     *
    52     * Contient un objet VRPN et une dérivée, d'euler.
    53     */
    54     class MetaVrpnObject: public sensor::VrpnObject {
    55         public:
    56             MetaVrpnObject(const sensor::VrpnClient *parent,std::string name);
    57             MetaVrpnObject(const sensor::VrpnClient *parent,std::string name,uint8_t id);
    58             ~MetaVrpnObject();
    59             gui::DataPlot1D* VxPlot(void) const;//1,0
    60             gui::DataPlot1D* VyPlot(void) const;//1,1
    61             gui::DataPlot1D* VzPlot(void) const;//1,2
    62             gui::DataPlot2D* XyPlot(void) const;
    63             void GetSpeed(core::Vector3D &speed) const;
     41/*! \class MetaVrpnObject
     42*
     43* \brief Classe haut niveau intégrant un objet VRPN
     44*
     45* Contient un objet VRPN et une dérivée, d'euler.
     46*/
     47class MetaVrpnObject : public sensor::VrpnObject {
     48public:
     49  MetaVrpnObject(const sensor::VrpnClient *parent, std::string name);
     50  MetaVrpnObject(const sensor::VrpnClient *parent, std::string name,
     51                 uint8_t id);
     52  ~MetaVrpnObject();
     53  gui::DataPlot1D *VxPlot(void) const; // 1,0
     54  gui::DataPlot1D *VyPlot(void) const; // 1,1
     55  gui::DataPlot1D *VzPlot(void) const; // 1,2
     56  gui::DataPlot2D *XyPlot(void) const;
     57  void GetSpeed(core::Vector3D &speed) const;
    6458
    65         private:
    66             void ConstructorCommon(const sensor::VrpnClient *parent,std::string name);
    67             filter::LowPassFilter *pbas;
    68             filter::EulerDerivative *euler;
    69             gui::DataPlot2D *xy_plot;
    70             gui::DataPlot1D *vx_opti_plot,*vy_opti_plot,*vz_opti_plot;
    71             gui::Tab* plot_tab;
    72             core::FloatType elementDataType;
    73 
    74     };
     59private:
     60  void ConstructorCommon(const sensor::VrpnClient *parent, std::string name);
     61  filter::LowPassFilter *pbas;
     62  filter::EulerDerivative *euler;
     63  gui::DataPlot2D *xy_plot;
     64  gui::DataPlot1D *vx_opti_plot, *vy_opti_plot, *vz_opti_plot;
     65  gui::Tab *plot_tab;
     66  core::FloatType elementDataType;
     67};
    7568} // end namespace meta
    7669} // end namespace flair
  • trunk/include/FlairMeta/SimuX4.h

    r9 r13  
    1616#include "Uav.h"
    1717
    18 namespace flair
    19 {
    20 namespace meta
    21 {
    22     /*! \class SimuX4
    23     *
    24     * \brief Class defining a simultation x4 uav
    25     */
    26     class SimuX4 : public Uav {
    27         public:
    28             //simu_id: 0 if simulating only one UAV
    29             //>0 otherwise
    30             SimuX4(core::FrameworkManager* parent,std::string uav_name,int simu_id=0,filter::UavMultiplex *multiplex=NULL);
    31             ~SimuX4();
    32             void StartSensors(void);
    33             void SetupVRPNAutoIP(std::string name);
    34     };
     18namespace flair {
     19namespace meta {
     20/*! \class SimuX4
     21*
     22* \brief Class defining a simultation x4 uav
     23*/
     24class SimuX4 : public Uav {
     25public:
     26  // simu_id: 0 if simulating only one UAV
     27  //>0 otherwise
     28  SimuX4(core::FrameworkManager *parent, std::string uav_name, int simu_id = 0,
     29         filter::UavMultiplex *multiplex = NULL);
     30  ~SimuX4();
     31  void StartSensors(void);
     32  void SetupVRPNAutoIP(std::string name);
     33};
    3534} // end namespace meta
    3635} // end namespace flair
  • trunk/include/FlairMeta/SimuX8.h

    r9 r13  
    1616#include "Uav.h"
    1717
    18 namespace flair
    19 {
    20 namespace meta
    21 {
    22     /*! \class SimuX8
    23     *
    24     * \brief Class defining a simultation x8 uav
    25     */
    26     class SimuX8 : public Uav {
    27         public:
    28             //simu_id: 0 if simulating only one UAV
    29             //>0 otherwise
    30             SimuX8(core::FrameworkManager* parent,std::string uav_name,int simu_id=0,filter::UavMultiplex *multiplex=NULL);
    31             ~SimuX8();
    32             void StartSensors(void);
    33             void SetupVRPNAutoIP(std::string name);
    34     };
     18namespace flair {
     19namespace meta {
     20/*! \class SimuX8
     21*
     22* \brief Class defining a simultation x8 uav
     23*/
     24class SimuX8 : public Uav {
     25public:
     26  // simu_id: 0 if simulating only one UAV
     27  //>0 otherwise
     28  SimuX8(core::FrameworkManager *parent, std::string uav_name, int simu_id = 0,
     29         filter::UavMultiplex *multiplex = NULL);
     30  ~SimuX8();
     31  void StartSensors(void);
     32  void SetupVRPNAutoIP(std::string name);
     33};
    3534} // end namespace meta
    3635} // end namespace flair
  • trunk/include/FlairMeta/Uav.h

    r9 r13  
    1717
    1818namespace flair {
    19     namespace core {
    20         class FrameworkManager;
    21     }
    22     namespace filter {
    23         class Ahrs;
    24         class UavMultiplex;
    25     }
    26     namespace actuator {
    27         class Bldc;
    28     }
    29     namespace sensor {
    30         class UsRangeFinder;
    31         class BatteryMonitor;
    32         class VrpnClient;
    33         class Imu;
    34         class Camera;
    35     }
     19namespace core {
     20class FrameworkManager;
     21}
     22namespace filter {
     23class Ahrs;
     24class UavMultiplex;
     25}
     26namespace actuator {
     27class Bldc;
     28}
     29namespace sensor {
     30class UsRangeFinder;
     31class BatteryMonitor;
     32class VrpnClient;
     33class Imu;
     34class Camera;
     35}
    3636}
    3737
    3838namespace flair {
    3939namespace meta {
    40     class MetaUsRangeFinder;
    41     class MetaVrpnObject;
     40class MetaUsRangeFinder;
     41class MetaVrpnObject;
    4242
    43     /*! \class Uav
    44     *
    45     * \brief Base class to construct sensors/actuators depending on uav type
    46     */
    47     class Uav: public core::Object {
    48         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;
     43/*! \class Uav
     44*
     45* \brief Base class to construct sensors/actuators depending on uav type
    5746*/
    58             //uav_name: for optitrack
    59             Uav(core::FrameworkManager* parent,std::string name,filter::UavMultiplex *multiplex=NULL);
    60             ~Uav();
    61             void SetupVRPN(std::string optitrack_address,std::string name);
    62             //vrpn serial: broken, need to add serial port in uav specific code
    63             //void SetupVRPNSerial(core::SerialPort *vrpn_port,std::string name,int VRPNSerialObjectId);
    64             virtual void SetupVRPNAutoIP(std::string name);
     47class Uav : public core::Object {
     48public:
     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,
     60      filter::UavMultiplex *multiplex = NULL);
     61  ~Uav();
     62  void SetupVRPN(std::string optitrack_address, std::string name);
     63  // vrpn serial: broken, need to add serial port in uav specific code
     64  // void SetupVRPNSerial(core::SerialPort *vrpn_port,std::string name,int
     65  // VRPNSerialObjectId);
     66  virtual void SetupVRPNAutoIP(std::string name);
    6567
    66             virtual void StartSensors(void);
    67             void UseDefaultPlot(void);
    68             actuator::Bldc* GetBldc(void) const;
    69             filter::UavMultiplex* GetUavMultiplex(void) const;
    70             sensor::Imu* GetImu(void) const;
    71             filter::Ahrs* GetAhrs(void) const;
    72             MetaUsRangeFinder* GetMetaUsRangeFinder(void) const;
    73             sensor::UsRangeFinder* GetUsRangeFinder(void) const;
    74             sensor::BatteryMonitor* GetBatteryMonitor(void) const;
    75             sensor::VrpnClient* GetVrpnClient(void) const;
    76             meta::MetaVrpnObject* GetVrpnObject(void) const;
    77             sensor::Camera* GetVerticalCamera(void) const;
     68  virtual void StartSensors(void);
     69  void UseDefaultPlot(void);
     70  actuator::Bldc *GetBldc(void) const;
     71  filter::UavMultiplex *GetUavMultiplex(void) const;
     72  sensor::Imu *GetImu(void) const;
     73  filter::Ahrs *GetAhrs(void) const;
     74  MetaUsRangeFinder *GetMetaUsRangeFinder(void) const;
     75  sensor::UsRangeFinder *GetUsRangeFinder(void) const;
     76  sensor::BatteryMonitor *GetBatteryMonitor(void) const;
     77  sensor::VrpnClient *GetVrpnClient(void) const;
     78  meta::MetaVrpnObject *GetVrpnObject(void) const;
     79  sensor::Camera *GetVerticalCamera(void) const;
    7880
    79         protected:
    80             void SetBldc(const actuator::Bldc *bldc);
    81             void SetMultiplex(const filter::UavMultiplex *multiplex);
    82             void SetAhrs(const filter::Ahrs *ahrs);
    83             void SetUsRangeFinder(const sensor::UsRangeFinder *us);
    84             void SetBatteryMonitor(const sensor::BatteryMonitor *battery);
    85             void SetVerticalCamera(const sensor::Camera *verticalCamera);
     81protected:
     82  void SetBldc(const actuator::Bldc *bldc);
     83  void SetMultiplex(const filter::UavMultiplex *multiplex);
     84  void SetAhrs(const filter::Ahrs *ahrs);
     85  void SetUsRangeFinder(const sensor::UsRangeFinder *us);
     86  void SetBatteryMonitor(const sensor::BatteryMonitor *battery);
     87  void SetVerticalCamera(const sensor::Camera *verticalCamera);
    8688
    87         private:
    88             sensor::Imu* imu;
    89             filter::Ahrs* ahrs;
    90             actuator::Bldc* bldc;
    91             filter::UavMultiplex *multiplex;
    92             sensor::UsRangeFinder* us;
    93             MetaUsRangeFinder* meta_us;
    94             sensor::VrpnClient *vrpnclient;
    95             MetaVrpnObject* uav_vrpn;
    96             sensor::BatteryMonitor* battery;
    97             sensor::Camera* verticalCamera;
    98     };
     89private:
     90  sensor::Imu *imu;
     91  filter::Ahrs *ahrs;
     92  actuator::Bldc *bldc;
     93  filter::UavMultiplex *multiplex;
     94  sensor::UsRangeFinder *us;
     95  MetaUsRangeFinder *meta_us;
     96  sensor::VrpnClient *vrpnclient;
     97  MetaVrpnObject *uav_vrpn;
     98  sensor::BatteryMonitor *battery;
     99  sensor::Camera *verticalCamera;
     100};
    99101} // end namespace meta
    100102} // end namespace flair
  • trunk/include/FlairMeta/UavFactory.h

    r9 r13  
    2121#include <Uav.h>
    2222
    23 flair::meta::Uav* CreateUav(flair::core::FrameworkManager* parent,std::string uav_name,std::string uav_type,flair::filter::UavMultiplex *multiplex=NULL);
     23flair::meta::Uav *CreateUav(flair::core::FrameworkManager *parent,
     24                            std::string uav_name, std::string uav_type,
     25                            flair::filter::UavMultiplex *multiplex = NULL);
    2426
    2527#endif // UAVFACTORY
  • trunk/include/FlairMeta/UavStateMachine.h

    r9 r13  
    2626
    2727namespace flair {
    28     namespace core {
    29         class FrameworkManager;
    30         class AhrsData;
    31         class io_data;
    32     }
    33     namespace gui {
    34         class PushButton;
    35         class GridLayout;
    36         class Tab;
    37         class DoubleSpinBox;
    38     }
    39     namespace filter {
    40         class ControlLaw;
    41         class NestedSat;
    42         class Pid;
    43         class PidThrust;
    44         class TrajectoryGenerator1D;
    45     }
    46     namespace sensor {
    47         class TargetController;
    48     }
    49     namespace meta {
    50         class MetaDualShock3;
    51         class Uav;
    52     }
    53 }
    54 
    55 namespace flair { namespace meta {
    56 
    57  /*! \class UavStateMachine
     28namespace core {
     29class FrameworkManager;
     30class AhrsData;
     31class io_data;
     32}
     33namespace gui {
     34class PushButton;
     35class GridLayout;
     36class Tab;
     37class DoubleSpinBox;
     38}
     39namespace filter {
     40class ControlLaw;
     41class NestedSat;
     42class Pid;
     43class PidThrust;
     44class TrajectoryGenerator1D;
     45}
     46namespace sensor {
     47class TargetController;
     48}
     49namespace meta {
     50class MetaDualShock3;
     51class Uav;
     52}
     53}
     54
     55namespace flair {
     56namespace meta {
     57
     58/*! \class UavStateMachine
    5859*
    5960* \brief State machine for UAV
    6061*
    61 * thread synchronized with ahrs, unless a period is set with SetPeriodUS or SetPeriodMS
     62* thread synchronized with ahrs, unless a period is set with SetPeriodUS or
     63*SetPeriodMS
    6264*/
    6365
    64 class UavStateMachine : public core::Thread
    65 {
    66     protected:
    67         enum class AltitudeMode_t {
    68             Manual,
    69             Custom
    70         };
    71         const AltitudeMode_t &GetAltitudeMode(void) const {
    72             return altitudeMode;
    73         }
    74         bool SetAltitudeMode(const AltitudeMode_t &altitudeMode);
    75 
    76         //uses TrajectoryGenerator1D *altitudeTrajectory to go to desiredAltitude
    77         //available in mode AltitudeMode_t::Manual
    78         //return true if goto is possible
    79         bool GotoAltitude(float desiredAltitude);
    80 
    81         enum class OrientationMode_t {
    82             Manual,
    83             Custom
    84         };
    85         const OrientationMode_t &GetOrientationMode(void) const {
    86             return orientationMode;
    87         }
    88         bool SetOrientationMode(const OrientationMode_t &orientationMode);
    89 
    90         enum class ThrustMode_t {
    91             Default,
    92             Custom
    93         };
    94         const ThrustMode_t &GetThrustMode() const {
    95             return thrustMode;
    96         }
    97         bool SetThrustMode(const ThrustMode_t &thrustMode);
    98 
    99         enum class TorqueMode_t {
    100             Default,
    101             Custom
    102         };
    103         const TorqueMode_t &GetTorqueMode(void) const {
    104             return torqueMode;
    105         }
    106         bool SetTorqueMode(const TorqueMode_t &torqueMode);
    107 
    108         enum class Event_t {
    109             EnteringFailSafeMode,
    110             EnteringControlLoop,
    111             StartLanding,
    112             FinishLanding,
    113             Stopped,
    114             TakingOff,
    115             EmergencyStop,
    116             Stabilized, //as soon as uav is 3cm far from the ground
    117             ZTrajectoryFinished,
    118         };
    119 
    120         UavStateMachine(meta::Uav* uav,uint16_t ds3Port=20000);
    121         ~UavStateMachine();
    122 
    123         const core::Quaternion &GetCurrentQuaternion(void) const;
    124 
    125         const core::Vector3D &GetCurrentAngularSpeed(void) const;
    126 
    127         const meta::Uav *GetUav(void) const;
    128 
    129         void Land(void);
    130         void TakeOff(void);
    131         void EmergencyStop(void);
    132         //! Used to signal an event
    133         /*!
    134             \param event the event which occured
    135         */
    136         virtual void SignalEvent(Event_t event);
    137 
    138         virtual const core::AhrsData *GetOrientation(void) const;
    139         const core::AhrsData *GetDefaultOrientation(void) const;
    140 
    141         virtual void AltitudeValues(float &z,float &dz) const;//in uav coordinate!
    142         void EnterFailSafeMode(void);
    143         bool ExitFailSafeMode(void);
    144         void FailSafeAltitudeValues(float &z,float &dz) const;//in uav coordinate!
    145 
    146         gui::GridLayout *GetButtonsLayout(void) const;
    147         virtual void ExtraSecurityCheck(void){};
    148         virtual void ExtraCheckJoystick(void){};
    149         virtual void ExtraCheckPushButton(void){};
    150 
    151         void GetDefaultReferenceAltitude(float &refAltitude, float &refVerticalVelocity);
    152         virtual void GetReferenceAltitude(float &refAltitude, float &refVerticalVelocity);
    153         //float GetDefaultThrustOffset(void);
    154         const core::AhrsData *GetDefaultReferenceOrientation(void) const;
    155         virtual const core::AhrsData *GetReferenceOrientation(void);
    156 
    157         /*!
    158         * \brief Compute Custom Torques
    159         *
    160         * Reimplement this method to use TorqueMode_t::Custom. \n
    161         * This method is called internally by UavStateMachine, do not call it by yourself. \n
    162         * See GetTorques if you need torques values.
    163         *
    164         * \param torques custom torques
    165         */
    166         virtual void ComputeCustomTorques(core::Euler &torques);
    167 
    168         /*!
    169         * \brief Compute Default Torques
    170         *
    171         * This method is called internally by UavStateMachine when using TorqueMode_t::Default. \n
    172         * Torques are only computed once by loop, other calls to this method will use previously computed torques.
    173         *
    174         * \param torques default torques
    175         */
    176         void ComputeDefaultTorques(core::Euler &torques);
    177 
    178         /*!
    179         * \brief Get Torques
    180         *
    181         * \return torques current torques
    182         */
    183         //const core::Euler &GetTorques() const;
    184 
    185         /*!
    186         * \brief Compute Custom Thrust
    187         *
    188         * Reimplement this method to use ThrustMode_t::Custom. \n
    189         * This method is called internally by UavStateMachine, do not call it by yourself. \n
    190         * See GetThrust if you need thrust value.
    191         *
    192         * \return custom Thrust
    193         */
    194         virtual float ComputeCustomThrust(void);
    195 
    196         /*!
    197         * \brief Compute Default Thrust
    198         *
    199         * This method is called internally by UavStateMachine when using ThrustMode_t::Default. \n
    200         * Thrust is only computed once by loop, other calls to this method will use previously computed thrust.
    201         *
    202         * \return default thrust
    203         */
    204         float ComputeDefaultThrust(void);
    205 
    206         /*!
    207         * \brief Get Thrust
    208         *
    209         * \return current thrust
    210         */
    211         //float GetThrust() const;
    212 
    213         /*!
    214         * \brief Add an IODevice to the control law logs
    215         *
    216         * The IODevice will be automatically logged among the Uz logs,
    217         * if logging is enabled (see IODevice::SetDataToLog, FrameworkManager::StartLog
    218         * and FrameworkManager::AddDeviceToLog). \n
    219         *
    220         * \param device IODevice to log
    221         */
    222         void AddDeviceToControlLawLog(const core::IODevice* device);
    223 
    224         /*!
    225         * \brief Add an io_data to the control law logs
    226         *
    227         * The io_data will be automatically logged among the Uz logs,
    228         * if logging is enabled (see IODevice::SetDataToLog, FrameworkManager::StartLog
    229         * and FrameworkManager::AddDeviceToLog). \n
    230         *
    231         * \param data io_data to log
    232         */
    233         void AddDataToControlLawLog(const core::io_data* data);
    234 
    235         const sensor::TargetController *GetJoystick(void) const;
    236 
    237         gui::Tab *setupLawTab,*graphLawTab;
    238 
    239     private:
    240         /*!
    241         \enum AltitudeState_t
    242         \brief States of the altitude state machine
    243         */
    244         enum class AltitudeState_t {
    245             Stopped,        /*!< the uav motors are stopped */
    246             TakingOff,      /*!< take off initiated. Motors accelerate progressively until the UAV lift up */
    247             Stabilized,     /*!< the uav is actively maintaining its altitude */
    248             StartLanding,   /*!< landing initiated. Altitude is required to reach the landing altitude (0 by default) */
    249             FinishLanding   /*!< motors are gradually stopped */
    250         };
    251         AltitudeState_t altitudeState;
    252         void ProcessAltitudeFiniteStateMachine();
    253         void ComputeReferenceAltitude(float &refAltitude, float &refVerticalVelocity);
    254 
    255 
    256         float groundAltitude; // effective altitude when the uav leaves the ground
    257         float currentAltitude,currentVerticalSpeed;
    258 
    259         bool failSafeMode;
    260         void SecurityCheck(void);
    261         void MandatorySecurityCheck(void);
    262         void CheckJoystick();
    263         void GenericCheckJoystick();
    264         void CheckPushButton(void);
    265         void GenericCheckPushButton(void);
    266         void Run(void);
    267         void StopMotors(void);
    268 
    269         meta::Uav *uav;
    270 
    271         core::Quaternion currentQuaternion;
    272         core::Vector3D currentAngularSpeed;
    273 
    274         const core::AhrsData *ComputeReferenceOrientation(void);
    275 
    276         void ComputeOrientation(void);
    277         void ComputeAltitude(void);
    278 
    279         void ComputeTorques(void);
    280         core::Euler currentTorques,savedDefaultTorques;
    281         bool needToComputeDefaultTorques;
    282 
    283         void ComputeThrust(void);
    284         float currentThrust,savedDefaultThrust;
    285         bool needToComputeDefaultThrust;
    286 
    287         gui::PushButton *button_kill,*button_take_off,*button_land,*button_start_log,*button_stop_log;
    288         gui::GridLayout *buttonslayout;
    289         gui::DoubleSpinBox *desiredTakeoffAltitude,*desiredLandingAltitude;
    290         AltitudeMode_t altitudeMode;
    291         OrientationMode_t orientationMode;
    292         ThrustMode_t thrustMode;
    293         TorqueMode_t torqueMode;
    294         bool flagBatteryLow;
    295         bool flagConnectionLost;
    296         bool flagZTrajectoryFinished;
    297         filter::NestedSat *uRoll,*uPitch;
    298         filter::Pid *uYaw;
    299         filter::PidThrust *uZ;
    300 
    301         MetaDualShock3 *joy;
    302         filter::TrajectoryGenerator1D *altitudeTrajectory;
     66class UavStateMachine : public core::Thread {
     67protected:
     68  enum class AltitudeMode_t { Manual, Custom };
     69  const AltitudeMode_t &GetAltitudeMode(void) const { return altitudeMode; }
     70  bool SetAltitudeMode(const AltitudeMode_t &altitudeMode);
     71
     72  // uses TrajectoryGenerator1D *altitudeTrajectory to go to desiredAltitude
     73  // available in mode AltitudeMode_t::Manual
     74  // return true if goto is possible
     75  bool GotoAltitude(float desiredAltitude);
     76
     77  enum class OrientationMode_t { Manual, Custom };
     78  const OrientationMode_t &GetOrientationMode(void) const {
     79    return orientationMode;
     80  }
     81  bool SetOrientationMode(const OrientationMode_t &orientationMode);
     82
     83  enum class ThrustMode_t { Default, Custom };
     84  const ThrustMode_t &GetThrustMode() const { return thrustMode; }
     85  bool SetThrustMode(const ThrustMode_t &thrustMode);
     86
     87  enum class TorqueMode_t { Default, Custom };
     88  const TorqueMode_t &GetTorqueMode(void) const { return torqueMode; }
     89  bool SetTorqueMode(const TorqueMode_t &torqueMode);
     90
     91  enum class Event_t {
     92    EnteringFailSafeMode,
     93    EnteringControlLoop,
     94    StartLanding,
     95    FinishLanding,
     96    Stopped,
     97    TakingOff,
     98    EmergencyStop,
     99    Stabilized, // as soon as uav is 3cm far from the ground
     100    ZTrajectoryFinished,
     101  };
     102
     103  UavStateMachine(meta::Uav *uav, uint16_t ds3Port = 20000);
     104  ~UavStateMachine();
     105
     106  const core::Quaternion &GetCurrentQuaternion(void) const;
     107
     108  const core::Vector3D &GetCurrentAngularSpeed(void) const;
     109
     110  const meta::Uav *GetUav(void) const;
     111
     112  void Land(void);
     113  void TakeOff(void);
     114  void EmergencyStop(void);
     115  //! Used to signal an event
     116  /*!
     117      \param event the event which occured
     118  */
     119  virtual void SignalEvent(Event_t event);
     120
     121  virtual const core::AhrsData *GetOrientation(void) const;
     122  const core::AhrsData *GetDefaultOrientation(void) const;
     123
     124  virtual void AltitudeValues(float &z, float &dz) const; // in uav coordinate!
     125  void EnterFailSafeMode(void);
     126  bool ExitFailSafeMode(void);
     127  void FailSafeAltitudeValues(float &z, float &dz) const; // in uav coordinate!
     128
     129  gui::GridLayout *GetButtonsLayout(void) const;
     130  virtual void ExtraSecurityCheck(void){};
     131  virtual void ExtraCheckJoystick(void){};
     132  virtual void ExtraCheckPushButton(void){};
     133
     134  void GetDefaultReferenceAltitude(float &refAltitude,
     135                                   float &refVerticalVelocity);
     136  virtual void GetReferenceAltitude(float &refAltitude,
     137                                    float &refVerticalVelocity);
     138  // float GetDefaultThrustOffset(void);
     139  const core::AhrsData *GetDefaultReferenceOrientation(void) const;
     140  virtual const core::AhrsData *GetReferenceOrientation(void);
     141
     142  /*!
     143  * \brief Compute Custom Torques
     144  *
     145  * Reimplement this method to use TorqueMode_t::Custom. \n
     146  * This method is called internally by UavStateMachine, do not call it by
     147  *yourself. \n
     148  * See GetTorques if you need torques values.
     149  *
     150  * \param torques custom torques
     151  */
     152  virtual void ComputeCustomTorques(core::Euler &torques);
     153
     154  /*!
     155  * \brief Compute Default Torques
     156  *
     157  * This method is called internally by UavStateMachine when using
     158  *TorqueMode_t::Default. \n
     159  * Torques are only computed once by loop, other calls to this method will use
     160  *previously computed torques.
     161  *
     162  * \param torques default torques
     163  */
     164  void ComputeDefaultTorques(core::Euler &torques);
     165
     166  /*!
     167  * \brief Get Torques
     168  *
     169  * \return torques current torques
     170  */
     171  // const core::Euler &GetTorques() const;
     172
     173  /*!
     174  * \brief Compute Custom Thrust
     175  *
     176  * Reimplement this method to use ThrustMode_t::Custom. \n
     177  * This method is called internally by UavStateMachine, do not call it by
     178  *yourself. \n
     179  * See GetThrust if you need thrust value.
     180  *
     181  * \return custom Thrust
     182  */
     183  virtual float ComputeCustomThrust(void);
     184
     185  /*!
     186  * \brief Compute Default Thrust
     187  *
     188  * This method is called internally by UavStateMachine when using
     189  *ThrustMode_t::Default. \n
     190  * Thrust is only computed once by loop, other calls to this method will use
     191  *previously computed thrust.
     192  *
     193  * \return default thrust
     194  */
     195  float ComputeDefaultThrust(void);
     196
     197  /*!
     198  * \brief Get Thrust
     199  *
     200  * \return current thrust
     201  */
     202  // float GetThrust() const;
     203
     204  /*!
     205  * \brief Add an IODevice to the control law logs
     206  *
     207  * The IODevice will be automatically logged among the Uz logs,
     208  * if logging is enabled (see IODevice::SetDataToLog,
     209  *FrameworkManager::StartLog
     210  * and FrameworkManager::AddDeviceToLog). \n
     211  *
     212  * \param device IODevice to log
     213  */
     214  void AddDeviceToControlLawLog(const core::IODevice *device);
     215
     216  /*!
     217  * \brief Add an io_data to the control law logs
     218  *
     219  * The io_data will be automatically logged among the Uz logs,
     220  * if logging is enabled (see IODevice::SetDataToLog,
     221  *FrameworkManager::StartLog
     222  * and FrameworkManager::AddDeviceToLog). \n
     223  *
     224  * \param data io_data to log
     225  */
     226  void AddDataToControlLawLog(const core::io_data *data);
     227
     228  const sensor::TargetController *GetJoystick(void) const;
     229
     230  gui::Tab *setupLawTab, *graphLawTab;
     231
     232private:
     233  /*!
     234  \enum AltitudeState_t
     235  \brief States of the altitude state machine
     236  */
     237  enum class AltitudeState_t {
     238    Stopped,      /*!< the uav motors are stopped */
     239    TakingOff,    /*!< take off initiated. Motors accelerate progressively until
     240                     the UAV lift up */
     241    Stabilized,   /*!< the uav is actively maintaining its altitude */
     242    StartLanding, /*!< landing initiated. Altitude is required to reach the
     243                     landing altitude (0 by default) */
     244    FinishLanding /*!< motors are gradually stopped */
     245  };
     246  AltitudeState_t altitudeState;
     247  void ProcessAltitudeFiniteStateMachine();
     248  void ComputeReferenceAltitude(float &refAltitude, float &refVerticalVelocity);
     249
     250  float groundAltitude; // effective altitude when the uav leaves the ground
     251  float currentAltitude, currentVerticalSpeed;
     252
     253  bool failSafeMode;
     254  void SecurityCheck(void);
     255  void MandatorySecurityCheck(void);
     256  void CheckJoystick();
     257  void GenericCheckJoystick();
     258  void CheckPushButton(void);
     259  void GenericCheckPushButton(void);
     260  void Run(void);
     261  void StopMotors(void);
     262
     263  meta::Uav *uav;
     264
     265  core::Quaternion currentQuaternion;
     266  core::Vector3D currentAngularSpeed;
     267
     268  const core::AhrsData *ComputeReferenceOrientation(void);
     269
     270  void ComputeOrientation(void);
     271  void ComputeAltitude(void);
     272
     273  void ComputeTorques(void);
     274  core::Euler currentTorques, savedDefaultTorques;
     275  bool needToComputeDefaultTorques;
     276
     277  void ComputeThrust(void);
     278  float currentThrust, savedDefaultThrust;
     279  bool needToComputeDefaultThrust;
     280
     281  gui::PushButton *button_kill, *button_take_off, *button_land,
     282      *button_start_log, *button_stop_log;
     283  gui::GridLayout *buttonslayout;
     284  gui::DoubleSpinBox *desiredTakeoffAltitude, *desiredLandingAltitude;
     285  AltitudeMode_t altitudeMode;
     286  OrientationMode_t orientationMode;
     287  ThrustMode_t thrustMode;
     288  TorqueMode_t torqueMode;
     289  bool flagBatteryLow;
     290  bool flagConnectionLost;
     291  bool flagZTrajectoryFinished;
     292  filter::NestedSat *uRoll, *uPitch;
     293  filter::Pid *uYaw;
     294  filter::PidThrust *uZ;
     295
     296  MetaDualShock3 *joy;
     297  filter::TrajectoryGenerator1D *altitudeTrajectory;
    303298};
    304 
    305299};
    306300};
  • trunk/include/FlairMeta/XAir.h

    r9 r13  
    1616#include "Uav.h"
    1717
    18 namespace flair
    19 {
    20 namespace meta
    21 {
    22     /*! \class XAir
    23     *
    24     * \brief Class defining an ardrone2 uav
    25     */
    26     class XAir : public Uav {
    27         public:
    28             XAir(core::FrameworkManager* parent,std::string uav_name,filter::UavMultiplex *multiplex=NULL);
    29             ~XAir();
    30             void StartSensors(void);
     18namespace flair {
     19namespace meta {
     20/*! \class XAir
     21*
     22* \brief Class defining an ardrone2 uav
     23*/
     24class XAir : public Uav {
     25public:
     26  XAir(core::FrameworkManager *parent, std::string uav_name,
     27       filter::UavMultiplex *multiplex = NULL);
     28  ~XAir();
     29  void StartSensors(void);
    3130
    32         private:
    33 
    34     };
     31private:
     32};
    3533} // end namespace meta
    3634} // end namespace flair
Note: See TracChangeset for help on using the changeset viewer.