Public Member Functions | Protected Member Functions | Protected Attributes | Private Types | Private Member Functions | List of all members
dynamicgraph::sot::MadgwickAHRS Class Reference

#include <madgwickahrs.hh>

Inheritance diagram for dynamicgraph::sot::MadgwickAHRS:
Inheritance graph
[legend]

Public Member Functions

 DECLARE_SIGNAL_IN (accelerometer, dynamicgraph::Vector)
 ax ay az in m.s-2 More...
 
 DECLARE_SIGNAL_IN (gyroscope, dynamicgraph::Vector)
 gx gy gz in rad.s-1 More...
 
 DECLARE_SIGNAL_OUT (imu_quat, dynamicgraph::Vector)
 Estimated orientation of IMU as a quaternion. More...
 
void init (const double &dt)
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW MadgwickAHRS (const std::string &name)
 
void set_beta (const double &beta)
 
void set_imu_quat (const dynamicgraph::Vector &imu_quat)
 Set the quaternion as [w,x,y,z]. More...
 
- Public Member Functions inherited from dynamicgraph::Entity
std::ostream & displaySignalList (std::ostream &os) const
 
 Entity (const std::string &name)
 
virtual const std::string & getClassName () const
 
const std::string & getCommandList () const
 
virtual std::string getDocString () const
 
LoggerVerbosity getLoggerVerbosityLevel ()
 
LoggerVerbosity getLoggerVerbosityLevel ()
 
const std::string & getName () const
 
command::CommandgetNewStyleCommand (const std::string &cmdName)
 
CommandMap_t getNewStyleCommandMap ()
 
SignalBase< int > & getSignal (const std::string &signalName)
 
const SignalBase< int > & getSignal (const std::string &signalName) const
 
SignalMap getSignalMap () const
 
double getStreamPrintPeriod ()
 
double getStreamPrintPeriod ()
 
double getTimeSample ()
 
double getTimeSample ()
 
bool hasSignal (const std::string &signame) const
 
Loggerlogger ()
 
Logger const & logger () const
 
Loggerlogger ()
 
Logger const & logger () const
 
void sendMsg (const std::string &msg, MsgType t=MSG_TYPE_INFO, const std::string &lineId="")
 
void sendMsg (const std::string &msg, MsgType t=MSG_TYPE_INFO, const std::string &lineId="")
 
void setLoggerVerbosityLevel (LoggerVerbosity lv)
 
void setLoggerVerbosityLevel (LoggerVerbosity lv)
 
bool setStreamPrintPeriod (double t)
 
bool setStreamPrintPeriod (double t)
 
bool setTimeSample (double t)
 
bool setTimeSample (double t)
 
virtual SignalBase< int > * test ()
 
virtual void test2 (SignalBase< int > *)
 
virtual std::ostream & writeCompletionList (std::ostream &os) const
 
virtual std::ostream & writeGraph (std::ostream &os) const
 
virtual ~Entity ()
 

Protected Member Functions

virtual void display (std::ostream &os) const
 
double invSqrt (double x)
 
void madgwickAHRSupdateIMU (double gx, double gy, double gz, double ax, double ay, double az)
 
- Protected Member Functions inherited from dynamicgraph::Entity
void addCommand (const std::string &name, command::Command *command)
 
void entityDeregistration ()
 
void entityRegistration ()
 
void signalDeregistration (const std::string &name)
 
void signalRegistration (const SignalArray< int > &signals)
 

Protected Attributes

double m_beta
 2 * proportional gain (Kp) More...
 
bool m_initSucceeded
 true if the entity has been successfully initialized More...
 
double m_q0
 quaternion of sensor frame More...
 
double m_q1
 
double m_q2
 
double m_q3
 
double m_sampleFreq
 sample frequency in Hz More...
 
- Protected Attributes inherited from dynamicgraph::Entity
CommandMap_t commandMap
 
Logger logger_
 
std::string name
 
SignalMap signalMap
 

Private Types

typedef MadgwickAHRS EntityClassName
 

Private Member Functions

 DYNAMIC_GRAPH_ENTITY_DECL ()
 

Additional Inherited Members

- Public Types inherited from dynamicgraph::Entity
typedef std::map< const std::string, command::Command *> CommandMap_t
 
typedef std::map< std::string, SignalBase< int > *> SignalMap
 

Detailed Description

Definition at line 85 of file madgwickahrs.hh.

Member Typedef Documentation

◆ EntityClassName

Definition at line 86 of file madgwickahrs.hh.

Constructor & Destructor Documentation

◆ MadgwickAHRS()

dynamicgraph::sot::MadgwickAHRS::MadgwickAHRS ( const std::string &  name)

Definition at line 44 of file madgwickahrs.cpp.

Member Function Documentation

◆ DECLARE_SIGNAL_IN() [1/2]

dynamicgraph::sot::MadgwickAHRS::DECLARE_SIGNAL_IN ( accelerometer  ,
dynamicgraph::Vector   
)

ax ay az in m.s-2

◆ DECLARE_SIGNAL_IN() [2/2]

dynamicgraph::sot::MadgwickAHRS::DECLARE_SIGNAL_IN ( gyroscope  ,
dynamicgraph::Vector   
)

gx gy gz in rad.s-1

◆ DECLARE_SIGNAL_OUT()

dynamicgraph::sot::MadgwickAHRS::DECLARE_SIGNAL_OUT ( imu_quat  ,
dynamicgraph::Vector   
)

Estimated orientation of IMU as a quaternion.

◆ display()

void dynamicgraph::sot::MadgwickAHRS::display ( std::ostream &  os) const
protectedvirtual

Reimplemented from dynamicgraph::Entity.

Definition at line 226 of file madgwickahrs.cpp.

◆ DYNAMIC_GRAPH_ENTITY_DECL()

dynamicgraph::sot::MadgwickAHRS::DYNAMIC_GRAPH_ENTITY_DECL ( )
private

◆ init()

void dynamicgraph::sot::MadgwickAHRS::init ( const double dt)

Definition at line 77 of file madgwickahrs.cpp.

◆ invSqrt()

double dynamicgraph::sot::MadgwickAHRS::invSqrt ( double  x)
protected

Definition at line 134 of file madgwickahrs.cpp.

◆ madgwickAHRSupdateIMU()

void dynamicgraph::sot::MadgwickAHRS::madgwickAHRSupdateIMU ( double  gx,
double  gy,
double  gz,
double  ax,
double  ay,
double  az 
)
protected

Definition at line 147 of file madgwickahrs.cpp.

◆ set_beta()

void dynamicgraph::sot::MadgwickAHRS::set_beta ( const double beta)

Definition at line 83 of file madgwickahrs.cpp.

◆ set_imu_quat()

void dynamicgraph::sot::MadgwickAHRS::set_imu_quat ( const dynamicgraph::Vector imu_quat)

Set the quaternion as [w,x,y,z].

Definition at line 89 of file madgwickahrs.cpp.

Member Data Documentation

◆ m_beta

double dynamicgraph::sot::MadgwickAHRS::m_beta
protected

2 * proportional gain (Kp)

Definition at line 123 of file madgwickahrs.hh.

◆ m_initSucceeded

bool dynamicgraph::sot::MadgwickAHRS::m_initSucceeded
protected

true if the entity has been successfully initialized

Definition at line 121 of file madgwickahrs.hh.

◆ m_q0

double dynamicgraph::sot::MadgwickAHRS::m_q0
protected

quaternion of sensor frame

Definition at line 125 of file madgwickahrs.hh.

◆ m_q1

double dynamicgraph::sot::MadgwickAHRS::m_q1
protected

Definition at line 125 of file madgwickahrs.hh.

◆ m_q2

double dynamicgraph::sot::MadgwickAHRS::m_q2
protected

Definition at line 125 of file madgwickahrs.hh.

◆ m_q3

double dynamicgraph::sot::MadgwickAHRS::m_q3
protected

Definition at line 125 of file madgwickahrs.hh.

◆ m_sampleFreq

double dynamicgraph::sot::MadgwickAHRS::m_sampleFreq
protected

sample frequency in Hz

Definition at line 127 of file madgwickahrs.hh.


The documentation for this class was generated from the following files:


sot-core
Author(s): Olivier Stasse, ostasse@laas.fr
autogenerated on Wed Jun 21 2023 02:51:27