Changeset 15 in flair-src for trunk/lib/FlairSensorActuator/src/unexported
- Timestamp:
- Apr 8, 2016, 3:40:57 PM (9 years ago)
- Location:
- trunk/lib/FlairSensorActuator/src/unexported
- Files:
-
- 8 edited
Legend:
- Unmodified
- Added
- Removed
-
trunk/lib/FlairSensorActuator/src/unexported/AfroBldc_impl.h
r3 r15 16 16 /*********************************************************************/ 17 17 18 19 18 #ifndef AFROBLDC_IMPL_H 20 19 #define AFROBLDC_IMPL_H … … 25 24 #define MAX_MOTORS 8 26 25 27 namespace flair 28 { 29 namespace core 30 { 31 class I2cPort; 32 } 33 namespace gui 34 { 35 class SpinBox; 36 class GroupBox; 37 class Layout; 38 } 39 namespace actuator 40 { 41 class AfroBldc; 42 } 43 namespace sensor 44 { 45 class BatteryMonitor; 46 } 26 namespace flair { 27 namespace core { 28 class I2cPort; 29 } 30 namespace gui { 31 class SpinBox; 32 class GroupBox; 33 class Layout; 34 } 35 namespace actuator { 36 class AfroBldc; 37 } 38 namespace sensor { 39 class BatteryMonitor; 40 } 47 41 } 48 42 49 class AfroBldc_impl 50 { 51 public:52 AfroBldc_impl(flair::actuator::AfroBldc* self,flair::gui::Layout *layout,flair::core::I2cPort*i2cport);53 54 void SetMotors(float*value);43 class AfroBldc_impl { 44 public: 45 AfroBldc_impl(flair::actuator::AfroBldc *self, flair::gui::Layout *layout, 46 flair::core::I2cPort *i2cport); 47 ~AfroBldc_impl(); 48 void SetMotors(float *value); 55 49 56 private: 57 void WriteValue(uint16_t value);//I2cPort mutex must be taken before calling this function 58 int nb_mot; 59 flair::core::I2cPort* i2cport; 60 flair::actuator::AfroBldc* self; 50 private: 51 void WriteValue(uint16_t value); // I2cPort mutex must be taken before calling 52 // this function 53 int nb_mot; 54 flair::core::I2cPort *i2cport; 55 flair::actuator::AfroBldc *self; 61 56 }; 62 57 -
trunk/lib/FlairSensorActuator/src/unexported/BlCtrlV2_impl.h
r3 r15 16 16 /*********************************************************************/ 17 17 18 19 18 #ifndef BLCTRLV2_IMPL_H 20 19 #define BLCTRLV2_IMPL_H … … 25 24 #define MAX_MOTORS 8 26 25 27 namespace flair 28 { 29 namespace core 30 { 31 class I2cPort; 32 } 33 namespace gui 34 { 35 class SpinBox; 36 class GroupBox; 37 class Layout; 38 } 39 namespace actuator 40 { 41 class BlCtrlV2; 42 } 43 namespace sensor 44 { 45 class BatteryMonitor; 46 } 26 namespace flair { 27 namespace core { 28 class I2cPort; 29 } 30 namespace gui { 31 class SpinBox; 32 class GroupBox; 33 class Layout; 34 } 35 namespace actuator { 36 class BlCtrlV2; 37 } 38 namespace sensor { 39 class BatteryMonitor; 40 } 47 41 } 48 42 49 class BlCtrlV2_impl 50 { 51 public:52 BlCtrlV2_impl(flair::actuator::BlCtrlV2* self,flair::gui::Layout *layout,flair::core::I2cPort*i2cport);53 54 void SetMotors(float*value);55 56 43 class BlCtrlV2_impl { 44 public: 45 BlCtrlV2_impl(flair::actuator::BlCtrlV2 *self, flair::gui::Layout *layout, 46 flair::core::I2cPort *i2cport); 47 ~BlCtrlV2_impl(); 48 void SetMotors(float *value); 49 flair::sensor::BatteryMonitor *battery; 50 flair::gui::SpinBox *poles; 57 51 58 private: 59 void WriteValue(uint16_t value);//I2cPort mutex must be taken before calling this function 60 void DetectMotors(void); 61 void GetCurrentSpeedAndVoltage(float ¤t,float &speed,float &voltage);//I2cPort mutex must be taken before calling this function 62 void GetCurrentAndSpeed(float ¤t,float &speed);//I2cPort mutex must be taken before calling this function 63 flair::core::Time last_voltage_time; 64 int nb_mot; 65 flair::core::I2cPort* i2cport; 66 flair::actuator::BlCtrlV2* self; 52 private: 53 void WriteValue(uint16_t value); // I2cPort mutex must be taken before calling 54 // this function 55 void DetectMotors(void); 56 void GetCurrentSpeedAndVoltage(float ¤t, float &speed, 57 float &voltage); // I2cPort mutex must be taken 58 // before calling this 59 // function 60 void GetCurrentAndSpeed( 61 float ¤t, 62 float &speed); // I2cPort mutex must be taken before calling this function 63 flair::core::Time last_voltage_time; 64 int nb_mot; 65 flair::core::I2cPort *i2cport; 66 flair::actuator::BlCtrlV2 *self; 67 67 }; 68 68 -
trunk/lib/FlairSensorActuator/src/unexported/Bldc_impl.h
r3 r15 22 22 #include <stdint.h> 23 23 24 namespace flair 25 { 26 namespace gui 27 { 28 class DoubleSpinBox; 29 class Layout; 30 class Label; 31 class DataPlot1D; 32 class TabWidget; 33 class PushButton; 34 } 35 namespace actuator 36 { 37 class Bldc; 38 } 24 namespace flair { 25 namespace gui { 26 class DoubleSpinBox; 27 class Layout; 28 class Label; 29 class DataPlot1D; 30 class TabWidget; 31 class PushButton; 32 } 33 namespace actuator { 34 class Bldc; 35 } 39 36 } 40 37 41 class Bldc_impl 42 { 43 public:44 Bldc_impl(flair::actuator::Bldc* self,flair::gui::Layout* layout,std::string name,uint8_t motors_count);45 Bldc_impl(flair::actuator::Bldc* self,uint8_t motors_count);//simulation46 47 48 49 50 51 float*power;52 void UseDefaultPlot(flair::gui::TabWidget*tab);53 54 flair::gui::Layout*layout;38 class Bldc_impl { 39 public: 40 Bldc_impl(flair::actuator::Bldc *self, flair::gui::Layout *layout, 41 std::string name, uint8_t motors_count); 42 Bldc_impl(flair::actuator::Bldc *self, uint8_t motors_count); // simulation 43 ~Bldc_impl(); 44 void UpdateFrom(const flair::core::io_data *data); 45 void LockUserInterface(void) const; 46 void UnlockUserInterface(void) const; 47 bool are_enabled; 48 float *power; 49 void UseDefaultPlot(flair::gui::TabWidget *tab); 50 uint8_t motors_count; 51 flair::gui::Layout *layout; 55 52 56 57 58 59 flair::actuator::Bldc*self;60 flair::gui::DoubleSpinBox *min_value,*max_value,*test_value;61 62 63 64 65 66 67 68 int tested_motor;//=-1 if no motor is tested53 private: 54 float *values; 55 float Sat(float value); 56 flair::actuator::Bldc *self; 57 flair::gui::DoubleSpinBox *min_value, *max_value, *test_value; 58 flair::gui::Label *flight_time; 59 flair::gui::DataPlot1D *plots; 60 flair::core::Time flight_start_time; 61 flair::gui::PushButton **button_test; 62 int time_sec; 63 bool is_running; 64 flair::core::Time test_start_time; 65 int tested_motor; //=-1 if no motor is tested 69 66 }; 70 67 -
trunk/lib/FlairSensorActuator/src/unexported/Gx3_25_imu_impl.h
r3 r15 18 18 19 19 namespace flair { 20 21 22 23 24 25 26 27 28 29 30 20 namespace core { 21 class FrameworkManager; 22 class SerialPort; 23 class AhrsData; 24 } 25 namespace gui { 26 class SpinBox; 27 class CheckBox; 28 class PushButton; 29 class Label; 30 } 31 31 } 32 32 … … 38 38 class Gx3_25_imu_impl { 39 39 40 public: 41 Gx3_25_imu_impl(flair::sensor::Gx3_25_imu* self,std::string name,flair::core::SerialPort *serialport,flair::sensor::Gx3_25_imu::Command_t command,flair::gui::GroupBox* setupgroupbox); 42 ~Gx3_25_imu_impl(); 43 void Run(void); 40 public: 41 Gx3_25_imu_impl(flair::sensor::Gx3_25_imu *self, std::string name, 42 flair::core::SerialPort *serialport, 43 flair::sensor::Gx3_25_imu::Command_t command, 44 flair::gui::GroupBox *setupgroupbox); 45 ~Gx3_25_imu_impl(); 46 void Run(void); 44 47 45 46 47 void GetData(uint8_t* buf,ssize_t buf_size,flair::core::Time *time);48 float Dequeue(uint8_t**buf);49 50 51 52 bool CalcChecksum(uint8_t *buf,int size);53 54 55 void RealignUpNorth(bool realign_up,bool realign_north);48 private: 49 void DeviceReset(void); 50 void GetData(uint8_t *buf, ssize_t buf_size, flair::core::Time *time); 51 float Dequeue(uint8_t **buf); 52 void GyrosBias(void); 53 void SamplingSettings(void); 54 void SetBaudrate(int value); 55 bool CalcChecksum(uint8_t *buf, int size); 56 int FirmwareNumber(void); 57 void PrintModelInfo(void); 58 void RealignUpNorth(bool realign_up, bool realign_north); 56 59 57 60 void SetContinuousMode(uint8_t continuous_command); 58 61 59 flair::gui::GroupBox *setupgroupbox; 60 flair::gui::SpinBox *data_rate,*gyro_acc_size,*mag_size,*up_comp,*north_comp; 61 flair::gui::CheckBox *coning,*disable_magn,*disable_north_comp,*disable_grav_comp; 62 flair::gui::PushButton *button_bias; 63 flair::gui::Label *data_rate_label; 62 flair::gui::GroupBox *setupgroupbox; 63 flair::gui::SpinBox *data_rate, *gyro_acc_size, *mag_size, *up_comp, 64 *north_comp; 65 flair::gui::CheckBox *coning, *disable_magn, *disable_north_comp, 66 *disable_grav_comp; 67 flair::gui::PushButton *button_bias; 68 flair::gui::Label *data_rate_label; 64 69 65 66 67 68 70 flair::core::SerialPort *serialport; 71 uint8_t command; 72 flair::sensor::Gx3_25_imu *self; 73 flair::core::AhrsData *ahrsData; 69 74 }; 70 75 -
trunk/lib/FlairSensorActuator/src/unexported/VrpnClient_impl.h
r3 r15 22 22 #include <vector> 23 23 24 namespace flair 25 { 26 namespace core 27 { 28 class OneAxisRotation; 29 class Vector3D; 30 class Quaternion; 31 class Mutex; 32 class SerialPort; 33 } 34 namespace gui 35 { 36 class TabWidget; 37 class Tab; 38 class Layout; 39 } 40 namespace sensor 41 { 42 class VrpnClient; 43 class VrpnObject; 44 } 24 namespace flair { 25 namespace core { 26 class OneAxisRotation; 27 class Vector3D; 28 class Quaternion; 29 class Mutex; 30 class SerialPort; 31 } 32 namespace gui { 33 class TabWidget; 34 class Tab; 35 class Layout; 36 } 37 namespace sensor { 38 class VrpnClient; 39 class VrpnObject; 40 } 45 41 } 46 42 … … 48 44 class vrpn_Connection; 49 45 50 class VrpnClient_impl 51 { 52 public: 53 VrpnClient_impl(flair::sensor::VrpnClient* self,std::string name,std::string address,uint16_t us_period); 54 VrpnClient_impl(flair::sensor::VrpnClient* self,std::string name,flair::core::SerialPort* serialport,uint16_t us_period); 55 ~VrpnClient_impl(); 56 void AddTrackable(flair::sensor::VrpnObject* obj);//normal 57 void RemoveTrackable(flair::sensor::VrpnObject* obj);//normal 58 void AddTrackable(VrpnObject_impl* obj,uint8_t id);//xbee 59 void RemoveTrackable(VrpnObject_impl* obj);//xbee 60 void ComputeRotations(flair::core::Vector3D& point); 61 void ComputeRotations(flair::core::Quaternion& quat); 62 bool UseXbee(void); 63 void Run(void); 64 flair::gui::Tab* setup_tab; 65 flair::gui::TabWidget* tab; 66 vrpn_Connection *connection; 46 class VrpnClient_impl { 47 public: 48 VrpnClient_impl(flair::sensor::VrpnClient *self, std::string name, 49 std::string address, uint16_t us_period); 50 VrpnClient_impl(flair::sensor::VrpnClient *self, std::string name, 51 flair::core::SerialPort *serialport, uint16_t us_period); 52 ~VrpnClient_impl(); 53 void AddTrackable(flair::sensor::VrpnObject *obj); // normal 54 void RemoveTrackable(flair::sensor::VrpnObject *obj); // normal 55 void AddTrackable(VrpnObject_impl *obj, uint8_t id); // xbee 56 void RemoveTrackable(VrpnObject_impl *obj); // xbee 57 void ComputeRotations(flair::core::Vector3D &point); 58 void ComputeRotations(flair::core::Quaternion &quat); 59 bool UseXbee(void); 60 void Run(void); 61 flair::gui::Tab *setup_tab; 62 flair::gui::TabWidget *tab; 63 vrpn_Connection *connection; 67 64 68 69 flair::sensor::VrpnClient*self;70 flair::core::Mutex*mutex;71 72 std::vector<flair::sensor::VrpnObject*> trackables;73 typedef struct xbee_object{74 VrpnObject_impl*vrpnobject;75 76 65 private: 66 flair::sensor::VrpnClient *self; 67 flair::core::Mutex *mutex; 68 uint16_t us_period; 69 std::vector<flair::sensor::VrpnObject *> trackables; 70 typedef struct xbee_object { 71 VrpnObject_impl *vrpnobject; 72 uint8_t id; 73 } xbee_object; 77 74 78 79 flair::gui::Tab*main_tab;80 flair::core::OneAxisRotation *rotation_1,*rotation_2;81 flair::core::SerialPort*serialport;75 std::vector<xbee_object> xbee_objects; 76 flair::gui::Tab *main_tab; 77 flair::core::OneAxisRotation *rotation_1, *rotation_2; 78 flair::core::SerialPort *serialport; 82 79 }; 83 80 -
trunk/lib/FlairSensorActuator/src/unexported/VrpnObject_impl.h
r3 r15 25 25 #include "Quaternion.h" 26 26 27 namespace flair 28 { 29 namespace core 30 { 31 class cvmatrix; 32 class Vector3D; 33 class Euler; 34 } 35 namespace gui 36 { 37 class TabWidget; 38 class Tab; 39 class DataPlot1D; 40 } 41 namespace sensor 42 { 43 class VrpnClient; 44 class VrpnObject; 45 } 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 } 46 42 } 47 43 48 class VrpnObject_impl 49 { 50 friend class VrpnClient_impl; 44 class VrpnObject_impl { 45 friend class VrpnClient_impl; 51 46 52 public: 53 VrpnObject_impl(flair::sensor::VrpnObject* self,const flair::sensor::VrpnClient *parent,std::string name,int id,const flair::gui::TabWidget* tab); 54 ~VrpnObject_impl(void); 47 public: 48 VrpnObject_impl(flair::sensor::VrpnObject *self, 49 const flair::sensor::VrpnClient *parent, std::string name, 50 int id, const flair::gui::TabWidget *tab); 51 ~VrpnObject_impl(void); 55 52 56 57 58 59 60 53 void mainloop(void); 54 void GetEuler(flair::core::Euler &euler); 55 void GetQuaternion(flair::core::Quaternion &quaternion); 56 void GetPosition(flair::core::Vector3D &point); 57 bool IsTracked(unsigned int timeout_ms); 61 58 62 flair::gui::Tab*plot_tab;63 flair::gui::DataPlot1D*x_plot;64 flair::gui::DataPlot1D*y_plot;65 flair::gui::DataPlot1D*z_plot;66 flair::core::cvmatrix *output,*state;59 flair::gui::Tab *plot_tab; 60 flair::gui::DataPlot1D *x_plot; 61 flair::gui::DataPlot1D *y_plot; 62 flair::gui::DataPlot1D *z_plot; 63 flair::core::cvmatrix *output, *state; 67 64 68 static voidVRPN_CALLBACK handle_pos(void *userdata, const vrpn_TRACKERCB t);65 static void VRPN_CALLBACK handle_pos(void *userdata, const vrpn_TRACKERCB t); 69 66 70 private: 71 flair::sensor::VrpnObject* self; 72 const flair::sensor::VrpnClient *parent; 73 vrpn_Tracker_Remote* tracker; 74 flair::core::Quaternion quaternion;//todo: quaternion should be included in the output to replace euler angles 75 void Update(void); 67 private: 68 flair::sensor::VrpnObject *self; 69 const flair::sensor::VrpnClient *parent; 70 vrpn_Tracker_Remote *tracker; 71 flair::core::Quaternion quaternion; // todo: quaternion should be included in 72 // the output to replace euler angles 73 void Update(void); 76 74 }; 77 75 -
trunk/lib/FlairSensorActuator/src/unexported/XBldc_impl.h
r3 r15 16 16 /*********************************************************************/ 17 17 18 19 18 #ifndef XBLDC_IMPL_H 20 19 #define XBLDC_IMPL_H … … 23 22 #include <stdint.h> 24 23 25 namespace flair 26 { 27 namespace core 28 { 29 class I2cPort; 30 } 31 namespace actuator 32 { 33 class XBldc; 34 } 24 namespace flair { 25 namespace core { 26 class I2cPort; 27 } 28 namespace actuator { 29 class XBldc; 30 } 35 31 } 36 32 33 class XBldc_impl { 37 34 38 class XBldc_impl 39 { 35 public: 36 XBldc_impl(flair::actuator::XBldc *self, flair::core::I2cPort *i2cport); 37 ~XBldc_impl(); 38 void UpdateFrom(flair::core::io_data *data); 39 void SetMotors(float *value); 40 40 41 public: 42 XBldc_impl(flair::actuator::XBldc* self,flair::core::I2cPort* i2cport); 43 ~XBldc_impl(); 44 void UpdateFrom(flair::core::io_data *data); 45 void SetMotors(float* value); 46 47 private: 48 uint8_t Sat(float value,uint8_t min,uint8_t max); 49 //void StartTest(uint8_t moteur); 50 void ChangeDirection(uint8_t moteur); 51 void ChangeAdress(uint8_t old_add,uint8_t new_add); 52 flair::actuator::XBldc* self; 53 flair::core::I2cPort* i2cport; 41 private: 42 uint8_t Sat(float value, uint8_t min, uint8_t max); 43 // void StartTest(uint8_t moteur); 44 void ChangeDirection(uint8_t moteur); 45 void ChangeAdress(uint8_t old_add, uint8_t new_add); 46 flair::actuator::XBldc *self; 47 flair::core::I2cPort *i2cport; 54 48 }; 55 49 -
trunk/lib/FlairSensorActuator/src/unexported/geodesie.h
r3 r15 13 13 14 14 #ifndef M_PI 15 # 15 #define M_PI 3.14159265358979323846 16 16 #endif 17 17 #ifndef M_PI_2 18 # 18 #define M_PI_2 1.57079632679489661923 19 19 #endif 20 20 #ifndef M_PI_4 21 # 21 #define M_PI_4 0.78539816339744830962 22 22 #endif 23 23 24 24 //////////////////////////////////////////////////////////////////////// 25 25 struct Matrice { 26 Matrice(const Matrice & A); 27 Matrice(); 28 void Apply(double v0, double v1, double v2, double & Mv0, double & Mv1, double & Mv2); 29 double c0_l0;double c1_l0;double c2_l0; 30 double c0_l1;double c1_l1;double c2_l1; 31 double c0_l2;double c1_l2;double c2_l2; 26 Matrice(const Matrice &A); 27 Matrice(); 28 void Apply(double v0, double v1, double v2, double &Mv0, double &Mv1, 29 double &Mv2); 30 double c0_l0; 31 double c1_l0; 32 double c2_l0; 33 double c0_l1; 34 double c1_l1; 35 double c2_l1; 36 double c0_l2; 37 double c1_l2; 38 double c2_l2; 32 39 }; // class 33 40 34 41 Matrice TransMat(const Matrice A); 35 42 36 Matrice ProdMat(const Matrice A, const Matrice B);37 void Write(const Matrice A, std::ostream&out);43 Matrice ProdMat(const Matrice A, const Matrice B); 44 void Write(const Matrice A, std::ostream &out); 38 45 39 46 //////////////////////////////////////////////////////////////////////// 40 47 class Raf98 { 41 private : 42 std::vector<double> m_dvalues; 43 double LitGrille(unsigned int c,unsigned int l) const; 44 public : 45 ~Raf98(); 46 Raf98() {} 47 bool Load(const std::string & s); 48 bool Interpol(double longitude/*deg*/, double latitude/*deg*/, double* Hwgs84) const; 48 private: 49 std::vector<double> m_dvalues; 50 double LitGrille(unsigned int c, unsigned int l) const; 51 52 public: 53 ~Raf98(); 54 Raf98() {} 55 bool Load(const std::string &s); 56 bool Interpol(double longitude /*deg*/, double latitude /*deg*/, 57 double *Hwgs84) const; 49 58 }; // class 50 59 //////////////////////////////////////////////////////////////////////// 51 60 52 61 //////////////////////////////////////////////////////////////////////// 53 inline double Deg2Rad(double deg) { return deg*M_PI/180.0;}54 inline double Rad2Deg(double rad) { return rad*180.0/M_PI;}62 inline double Deg2Rad(double deg) { return deg * M_PI / 180.0; } 63 inline double Rad2Deg(double rad) { return rad * 180.0 / M_PI; } 55 64 //////////////////////////////////////////////////////////////////////// 56 65 57 const double a_Lambert93 =6378137;58 const double f_Lambert93 =1 / 298.257222101;59 const double e_Lambert93 =sqrt(f_Lambert93*(2-f_Lambert93));60 const double lambda0_Lambert93 =Deg2Rad(3.0);//degres61 const double phi0_Lambert93 =Deg2Rad(46.5);62 const double phi1_Lambert93 =Deg2Rad(44.0);63 const double phi2_Lambert93 =Deg2Rad(49.0);//degres64 const double X0_Lambert93 =700000;//65 const double Y0_Lambert93 =6600000;//66 const double a_Lambert93 = 6378137; 67 const double f_Lambert93 = 1 / 298.257222101; 68 const double e_Lambert93 = sqrt(f_Lambert93 * (2 - f_Lambert93)); 69 const double lambda0_Lambert93 = Deg2Rad(3.0); // degres 70 const double phi0_Lambert93 = Deg2Rad(46.5); 71 const double phi1_Lambert93 = Deg2Rad(44.0); 72 const double phi2_Lambert93 = Deg2Rad(49.0); // degres 73 const double X0_Lambert93 = 700000; // 74 const double Y0_Lambert93 = 6600000; // 66 75 const double n_Lambert93 = 0.7256077650; 67 76 const double c_Lambert93 = 11754255.426; … … 70 79 71 80 const double GRS_a = 6378137; 72 const double GRS_f = 1 /298.257222101;73 const double GRS_b = GRS_a *(1-GRS_f);74 const double GRS_e = sqrt((pow(GRS_a, 2) - pow(GRS_b,2)) / pow(GRS_a,2));81 const double GRS_f = 1 / 298.257222101; 82 const double GRS_b = GRS_a * (1 - GRS_f); 83 const double GRS_e = sqrt((pow(GRS_a, 2) - pow(GRS_b, 2)) / pow(GRS_a, 2)); 75 84 76 85 //////////////////////////////////////////////////////////////////////// 77 void Geographique_2_Lambert93(const Raf98& raf98,double lambda,double phi,double he,Matrice in,double& E,double& N,double& h,Matrice& out); 78 void Geographique_2_Lambert93(const Raf98& raf98,double lambda,double phi,double he,double& E,double& N,double& h); 79 void Lambert93_2_Geographique(const Raf98& raf98,double E,double N,double h,double& lambda,double& phi,double& he); 80 void Lambert93_2_Geographique(const Raf98& raf98,double E,double N,double h,Matrice in,double& lambda,double& phi,double& he,Matrice& out); 86 void Geographique_2_Lambert93(const Raf98 &raf98, double lambda, double phi, 87 double he, Matrice in, double &E, double &N, 88 double &h, Matrice &out); 89 void Geographique_2_Lambert93(const Raf98 &raf98, double lambda, double phi, 90 double he, double &E, double &N, double &h); 91 void Lambert93_2_Geographique(const Raf98 &raf98, double E, double N, double h, 92 double &lambda, double &phi, double &he); 93 void Lambert93_2_Geographique(const Raf98 &raf98, double E, double N, double h, 94 Matrice in, double &lambda, double &phi, 95 double &he, Matrice &out); 81 96 /** Convert from geographique to ECEF. 82 97 * @param[in] longitude Longitude in radian. … … 84 99 * @param[in] he Height in meter. 85 100 */ 86 void Geographique_2_ECEF(double longitude, double latitude, double he, double& x, double& y, double& z); 101 void Geographique_2_ECEF(double longitude, double latitude, double he, 102 double &x, double &y, double &z); 87 103 /** Convert from ECEF two ENU. 88 104 * @param[in] lon0 Longitude of the origin in radian. … … 90 106 * @param[in] he0 Height of the origin in radian. 91 107 */ 92 void ECEF_2_ENU(double x,double y,double z,double& e,double& n,double& u,double lon0,double lat0,double he0); 108 void ECEF_2_ENU(double x, double y, double z, double &e, double &n, double &u, 109 double lon0, double lat0, double he0); 93 110 //////////////////////////////////////////////////////////////////////// 94 111 95 // ALGO000196 double LatitueIsometrique(double latitude, double e);97 // ALGO000298 double LatitueIsometrique2Lat(double latitude_iso, double e,double epsilon);112 // ALGO0001 113 double LatitueIsometrique(double latitude, double e); 114 // ALGO0002 115 double LatitueIsometrique2Lat(double latitude_iso, double e, double epsilon); 99 116 100 //ALGO0003 101 void Geo2ProjLambert( 102 double lambda,double phi, 103 double n, double c,double e, 104 double lambdac,double xs,double ys, 105 double& X,double& Y); 106 //ALGO0004 107 void Proj2GeoLambert( 108 double X,double Y, 109 double n, double c,double e, 110 double lambdac,double xs,double ys, 111 double epsilon, 112 double& lambda,double& phi); 117 // ALGO0003 118 void Geo2ProjLambert(double lambda, double phi, double n, double c, double e, 119 double lambdac, double xs, double ys, double &X, 120 double &Y); 121 // ALGO0004 122 void Proj2GeoLambert(double X, double Y, double n, double c, double e, 123 double lambdac, double xs, double ys, double epsilon, 124 double &lambda, double &phi); 113 125 114 126 double ConvMerApp(double longitude); … … 118 130 */ 119 131 template <typename _T1, typename _T2> 120 void cartesianToPolar(const _T1 x, const _T1 y, _T2 & r, _T2 &theta) {121 r = std::sqrt(x*x + y*y);122 132 void cartesianToPolar(const _T1 x, const _T1 y, _T2 &r, _T2 &theta) { 133 r = std::sqrt(x * x + y * y); 134 theta = std::atan2(x, y); 123 135 } 124 136 … … 127 139 */ 128 140 template <typename _T1, typename _T2> 129 void polarToCartesian(const _T1 r, const _T1 theta, _T2 & x, _T2 &y) {130 131 141 void polarToCartesian(const _T1 r, const _T1 theta, _T2 &x, _T2 &y) { 142 x = r * std::cos(theta); 143 y = r * std::sin(theta); 132 144 } 133 145 134 146 /** 135 Converts Cartesian (x, y, z) coordinates to spherical coordinates (r, theta, phi) 147 Converts Cartesian (x, y, z) coordinates to spherical coordinates (r, theta, 148 phi) 136 149 Angles expressed in radians. 137 150 */ 138 151 template <typename _T1, typename _T2> 139 void cartesianToSpherical(const _T1 x, const _T1 y, const _T1 z, _T2 & r, _T2 & theta, _T2 & phi) { 140 r = std::sqrt(x*x + y*y + z*z); 141 theta = std::acos(z / r); 142 phi = std::atan2(y, x); 152 void cartesianToSpherical(const _T1 x, const _T1 y, const _T1 z, _T2 &r, 153 _T2 &theta, _T2 &phi) { 154 r = std::sqrt(x * x + y * y + z * z); 155 theta = std::acos(z / r); 156 phi = std::atan2(y, x); 143 157 } 144 158 145 159 /** 146 Converts spherical coordinates (r, theta, phi) to Cartesian (x, y, z) coordinates. 160 Converts spherical coordinates (r, theta, phi) to Cartesian (x, y, z) 161 coordinates. 147 162 Angles expressed in radians. 148 163 */ 149 164 template <typename _T1, typename _T2> 150 void sphericalToCartesian(const _T1 r, const _T1 theta, const _T1 phi, _T2 & x, _T2 & y, _T2 & z) { 151 x = r * std::sin(theta) * std::cos(phi); 152 y = r * std::sin(theta) * std::sin(phi); 153 z = r * std::cos(theta); 165 void sphericalToCartesian(const _T1 r, const _T1 theta, const _T1 phi, _T2 &x, 166 _T2 &y, _T2 &z) { 167 x = r * std::sin(theta) * std::cos(phi); 168 y = r * std::sin(theta) * std::sin(phi); 169 z = r * std::cos(theta); 154 170 } 155 171
Note:
See TracChangeset
for help on using the changeset viewer.