XBotInterface  2.4.1
XBotInterface provides a generic API to model and control a robot.
Public Types | Public Member Functions | Friends | List of all members
XBot::ImuSensor Class Reference

#include <ImuSensor.h>

+ Inheritance diagram for XBot::ImuSensor:
+ Collaboration diagram for XBot::ImuSensor:

Public Types

typedef std::shared_ptr< ImuSensorPtr
 
typedef std::shared_ptr< const ImuSensorConstPtr
 
- Public Types inherited from XBot::GenericSensor
typedef std::shared_ptr< GenericSensorPtr
 
typedef std::shared_ptr< const GenericSensorConstPtr
 

Public Member Functions

 ImuSensor ()
 Default constructor. More...
 
 ImuSensor (urdf::LinkConstSharedPtr sensor_link, int sensor_id)
 Constructor with the sensor parent link. More...
 
void getOrientation (Eigen::Quaterniond &orientation) const
 Getter for the IMU orientation as a quaternion. More...
 
void getOrientation (Eigen::Matrix3d &orientation) const
 Getter for the IMU orientation as a rotation matrix. More...
 
void getLinearAcceleration (Eigen::Vector3d &acceleration) const
 Getter for the IMU linear acceleration. More...
 
void getAngularVelocity (Eigen::Vector3d &angular_velocity) const
 Getter for the IMU angular velocity. More...
 
void getImuData (Eigen::Quaterniond &orientation, Eigen::Vector3d &acceleration, Eigen::Vector3d &angular_velocity) const
 Getter for the IMU data i.e. More...
 
void getImuData (Eigen::Matrix3d &orientation, Eigen::Vector3d &acceleration, Eigen::Vector3d &angular_velocity) const
 Getter for the IMU data i.e. More...
 
void setImuData (Eigen::Quaterniond &orientation, Eigen::Vector3d &acceleration, Eigen::Vector3d &angular_velocity, double timestamp)
 Setter for the IMU data i.e. More...
 
void setImuData (Eigen::Matrix3d &orientation, Eigen::Vector3d &acceleration, Eigen::Vector3d &angular_velocity, double timestamp)
 Setter for the IMU data i.e. More...
 
- Public Member Functions inherited from XBot::GenericSensor
 GenericSensor ()
 Default constructor. More...
 
 GenericSensor (urdf::LinkConstSharedPtr sensor_link, int sensor_id)
 Constructor with the sensor parent link. More...
 
const std::string & getParentLinkName () const
 Getter for the sensor parent link name. More...
 
const std::string & getParentJointName () const
 Getter for the sensor parent joint name. More...
 
const std::string & getSensorName () const
 Getter for the sensor name. More...
 
const int getSensorId () const
 Getter for the sensor id. More...
 
const Eigen::Affine3d & getSensorPose () const
 Getter for the sensor pose w.r.t. More...
 
double getTimestamp () const
 Getter for the timestamp of the last sensor reading. More...
 
void setTimestamp (double timestamp)
 Setter for the timestamp of the sensor reading. More...
 

Friends

std::ostream & operator<< (std::ostream &os, const XBot::ImuSensor &j)
 

Member Typedef Documentation

◆ ConstPtr

typedef std::shared_ptr<const ImuSensor> XBot::ImuSensor::ConstPtr

◆ Ptr

typedef std::shared_ptr<ImuSensor> XBot::ImuSensor::Ptr

Constructor & Destructor Documentation

◆ ImuSensor() [1/2]

XBot::ImuSensor::ImuSensor ( )

Default constructor.

◆ ImuSensor() [2/2]

XBot::ImuSensor::ImuSensor ( urdf::LinkConstSharedPtr  sensor_link,
int  sensor_id 
)

Constructor with the sensor parent link.

Parameters
sensor_linkthe sensor parent link
sensor_idthe sensor id

Member Function Documentation

◆ getAngularVelocity()

void XBot::ImuSensor::getAngularVelocity ( Eigen::Vector3d &  angular_velocity) const

Getter for the IMU angular velocity.

Parameters
angular_velocitythe IMU angular velocity
Returns
void

◆ getImuData() [1/2]

void XBot::ImuSensor::getImuData ( Eigen::Matrix3d &  orientation,
Eigen::Vector3d &  acceleration,
Eigen::Vector3d &  angular_velocity 
) const

Getter for the IMU data i.e.

orientation(as a rotation matrix), linear acceleration and angular velocity

Parameters
orientationthe IMU orientation as a rotation matrix
accelerationthethe IMU linear acceleration
angular_velocitythe IMU angular velocity
Returns
void

◆ getImuData() [2/2]

void XBot::ImuSensor::getImuData ( Eigen::Quaterniond &  orientation,
Eigen::Vector3d &  acceleration,
Eigen::Vector3d &  angular_velocity 
) const

Getter for the IMU data i.e.

orientation(as a quaternion), linear acceleration and angular velocity

Parameters
orientationthe IMU orientation as a quaternion
accelerationthe IMU linear acceleration
angular_velocitythe IMU angular velocity
Returns
void

◆ getLinearAcceleration()

void XBot::ImuSensor::getLinearAcceleration ( Eigen::Vector3d &  acceleration) const

Getter for the IMU linear acceleration.

Parameters
accelerationthe IMU linear acceleration
Returns
void

◆ getOrientation() [1/2]

void XBot::ImuSensor::getOrientation ( Eigen::Matrix3d &  orientation) const

Getter for the IMU orientation as a rotation matrix.

Parameters
orientationthe IMU orientation as a rotation matrix
Returns
void

◆ getOrientation() [2/2]

void XBot::ImuSensor::getOrientation ( Eigen::Quaterniond &  orientation) const

Getter for the IMU orientation as a quaternion.

Parameters
orientationthe IMU orientation as a quaternion
Returns
void

◆ setImuData() [1/2]

void XBot::ImuSensor::setImuData ( Eigen::Matrix3d &  orientation,
Eigen::Vector3d &  acceleration,
Eigen::Vector3d &  angular_velocity,
double  timestamp 
)

Setter for the IMU data i.e.

orientation(as a rotation matrix), linear acceleration, angular velocity and a timestamp

Parameters
orientationthe IMU orientation as a rotation matrix to set
accelerationthe IMU linear acceleration to set
angular_velocitythe IMU angular velocity to set
timestampIMU data reading timestamp to set
Returns
void

◆ setImuData() [2/2]

void XBot::ImuSensor::setImuData ( Eigen::Quaterniond &  orientation,
Eigen::Vector3d &  acceleration,
Eigen::Vector3d &  angular_velocity,
double  timestamp 
)

Setter for the IMU data i.e.

orientation(as a quaternion), linear acceleration, angular velocity and a timestamp

Parameters
orientationthe IMU orientation as a quaternion to set
accelerationthe IMU linear acceleration to set
angular_velocitythe IMU angular velocity to set
timestampIMU data reading timestamp to set
Returns
void

Friends And Related Function Documentation

◆ operator<<

std::ostream& operator<< ( std::ostream &  os,
const XBot::ImuSensor j 
)
friend

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