XBotInterface
2.4.1
XBotInterface provides a generic API to model and control a robot.
|
#include <ImuSensor.h>
Public Types | |
typedef std::shared_ptr< ImuSensor > | Ptr |
typedef std::shared_ptr< const ImuSensor > | ConstPtr |
Public Types inherited from XBot::GenericSensor | |
typedef std::shared_ptr< GenericSensor > | Ptr |
typedef std::shared_ptr< const GenericSensor > | ConstPtr |
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) |
typedef std::shared_ptr<const ImuSensor> XBot::ImuSensor::ConstPtr |
typedef std::shared_ptr<ImuSensor> XBot::ImuSensor::Ptr |
XBot::ImuSensor::ImuSensor | ( | ) |
Default constructor.
XBot::ImuSensor::ImuSensor | ( | urdf::LinkConstSharedPtr | sensor_link, |
int | sensor_id | ||
) |
Constructor with the sensor parent link.
sensor_link | the sensor parent link |
sensor_id | the sensor id |
void XBot::ImuSensor::getAngularVelocity | ( | Eigen::Vector3d & | angular_velocity | ) | const |
Getter for the IMU angular velocity.
angular_velocity | the IMU angular velocity |
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
orientation | the IMU orientation as a rotation matrix |
accelerationthe | the IMU linear acceleration |
angular_velocity | the IMU angular velocity |
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
orientation | the IMU orientation as a quaternion |
acceleration | the IMU linear acceleration |
angular_velocity | the IMU angular velocity |
void XBot::ImuSensor::getLinearAcceleration | ( | Eigen::Vector3d & | acceleration | ) | const |
Getter for the IMU linear acceleration.
acceleration | the IMU linear acceleration |
void XBot::ImuSensor::getOrientation | ( | Eigen::Matrix3d & | orientation | ) | const |
Getter for the IMU orientation as a rotation matrix.
orientation | the IMU orientation as a rotation matrix |
void XBot::ImuSensor::getOrientation | ( | Eigen::Quaterniond & | orientation | ) | const |
Getter for the IMU orientation as a quaternion.
orientation | the IMU orientation as a quaternion |
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
orientation | the IMU orientation as a rotation matrix to set |
acceleration | the IMU linear acceleration to set |
angular_velocity | the IMU angular velocity to set |
timestamp | IMU data reading timestamp to set |
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
orientation | the IMU orientation as a quaternion to set |
acceleration | the IMU linear acceleration to set |
angular_velocity | the IMU angular velocity to set |
timestamp | IMU data reading timestamp to set |
|
friend |