TinyRobotics
Loading...
Searching...
No Matches
Public Member Functions | Public Attributes | List of all members
IMU2D< T > Class Template Reference

Basic 2D IMU dead-reckoning class. More...

#include <IMU2D.h>

Inheritance diagram for IMU2D< T >:
Inheritance graph
[legend]
Collaboration diagram for IMU2D< T >:
Collaboration graph
[legend]

Public Member Functions

bool begin (T initialAngleDeg, Coordinate< DistanceM > initialPosition)
 
bool begin (Transform2D transform) override
 
void end ()
 
void update (T accelX, T accelY, T gyroZ_in, unsigned long nowMillis)
 
Delta2D getLastDelta () const
 Get the last delta update (dx, dy, dtheta)
 
float getAngularVelocity () const
 Get the current angular velocity (radians/second)
 
float getLinearVelocity () const
 Get the current linear velocity (meters/second)
 
float getTheta () const
 Get the current orientation (radians)
 
Coordinate< DistanceM > getPosition () const
 get position
 
Angle getHeading () const
 get heading as Angle
 
Speed getSpeed () const
 get speed as Speed
 
Distance getTotalDistance () const
 Get the total distance traveled.
 
uint32_t getTimestamp () const
 Get time of last update.
 
Transform2D getTransform () const
 
void publish ()
 
virtual Coordinate< DistanceM > getPosition () const =0
 
virtual Angle getHeading () const =0
 
virtual Speed getSpeed () const =0
 
virtual Transform2D getTransform () const =0
 
virtual bool begin (Transform2D transform)=0
 
virtual void end ()=0
 
- Public Member Functions inherited from MessageSource
void subscribe (MessageHandler &handler, MessageOrigin origin=MessageOrigin::Undefined, MessageContent content=MessageContent::Undefined)
 Subscribe a message handler to this source, with optional filtering.
 
void unsubscribeAll ()
 Remove all registered message handlers.
 
void sendMessage (Message< float > &msg)
 Publish a message to all registered handlers.
 
void sendMessage (const Message< Coordinate< float > > &msg)
 Publish a message to all registered handlers.
 
void sendMessage (const Message< GPSCoordinate > &msg)
 Publish a message to all registered handlers.
 
void sendMessage (const Message< MotionState3D > &msg)
 Overload for MotionState3D messages.
 

Public Attributes

bool is_active = false
 
float headingRad = 0
 
float speedMPS = 0
 
Coordinate< DistanceM > position
 
unsigned long lastUpdateMillis = 0
 
Delta2D lastDelta = {0.0f, 0.0f, 0.0f}
 
float lastAngularVelocity = 0.0f
 
float totalDistanceM = 0.0f
 
uint32_t timestamp = 0
 

Additional Inherited Members

- Protected Attributes inherited from MessageSource
std::vector< MessageHandlerEntrymessageHandlers_
 

Detailed Description

template<typename T = float>
class tinyrobotics::IMU2D< T >

Basic 2D IMU dead-reckoning class.

This class estimates 2D position, velocity, and heading (yaw angle) for robotics applications by integrating gyroscope and accelerometer data over time.

Limitations:

Example usage:

imu.begin(initialAngle, initialPosition);
imu.update(accelX, accelY, gyroZ, millis());
auto pos = imu.getPosition();
auto heading = imu.getHeading();
auto speed = imu.getSpeed();
Basic 2D IMU dead-reckoning class.
Definition: IMU2D.h:47
void update(T accelX, T accelY, T gyroZ_in, unsigned long nowMillis)
Definition: IMU2D.h:68
Angle getHeading() const
get heading as Angle
Definition: IMU2D.h:121
Speed getSpeed() const
get speed as Speed
Definition: IMU2D.h:123
Coordinate< DistanceM > getPosition() const
get position
Definition: IMU2D.h:119
Template Parameters
TNumeric type (float or double recommended)

Member Function Documentation

◆ begin()

bool begin ( Transform2D  transform)
inlineoverridevirtual

Implements IMotionState2D.

◆ end()

void end ( )
inlinevirtual

Implements IMotionState2D.

◆ getHeading()

Angle getHeading ( ) const
inlinevirtual

get heading as Angle

Implements IMotionState2D.

◆ getPosition()

Coordinate< DistanceM > getPosition ( ) const
inlinevirtual

get position

Implements IMotionState2D.

◆ getSpeed()

Speed getSpeed ( ) const
inlinevirtual

get speed as Speed

Implements IMotionState2D.

◆ getTransform()

Transform2D getTransform ( ) const
inlinevirtual

Implements IMotionState2D.

◆ update()

void update ( accelX,
accelY,
gyroZ_in,
unsigned long  nowMillis 
)
inline

Update with accelerometer and gyro measurements (accelX, accelY in sensor frame, gyroZ in rad/s)


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