Skip to content

Class robot_dart::sensor::IMU

ClassList > robot_dart > sensor > IMU

Inherits the following classes: robot_dart::sensor::Sensor

Public Functions

Type Name
IMU (const IMUConfig & config)
const Eigen::AngleAxisd & angular_position () const
Eigen::Vector3d angular_position_vec () const
const Eigen::Vector3d & angular_velocity () const
virtual void attach_to_joint (dart::dynamics::Joint *, const Eigen::Isometry3d &) override
virtual void calculate (double) override
virtual void init () override
const Eigen::Vector3d & linear_acceleration () const
virtual std::string type () override const

Public Functions inherited from robot_dart::sensor::Sensor

See robot_dart::sensor::Sensor

Type Name
Sensor (size_t freq=40)
void activate (bool enable=true)
bool active () const
virtual void attach_to_body (dart::dynamics::BodyNode * body, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity())
void attach_to_body (const std::shared_ptr< Robot > & robot, const std::string & body_name, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity())
virtual void attach_to_joint (dart::dynamics::Joint * joint, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity())
void attach_to_joint (const std::shared_ptr< Robot > & robot, const std::string & joint_name, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity())
const std::string & attached_to () const
virtual void calculate (double) = 0
void detach ()
size_t frequency () const
virtual void init () = 0
const Eigen::Isometry3d & pose () const
void refresh (double t)
void set_frequency (size_t freq)
void set_pose (const Eigen::Isometry3d & tf)
void set_simu (RobotDARTSimu * simu)
const RobotDARTSimu * simu () const
virtual std::string type () const = 0
virtual ~Sensor ()

Protected Attributes

Type Name
Eigen::AngleAxisd _angular_pos
Eigen::Vector3d _angular_vel
IMUConfig _config
Eigen::Vector3d _linear_accel

Protected Attributes inherited from robot_dart::sensor::Sensor

See robot_dart::sensor::Sensor

Type Name
bool _active
Eigen::Isometry3d _attached_tf
bool _attached_to_body = = false
bool _attached_to_joint = = false
bool _attaching_to_body = = false
bool _attaching_to_joint = = false
dart::dynamics::BodyNode * _body_attached
size_t _frequency
dart::dynamics::Joint * _joint_attached
RobotDARTSimu * _simu = = nullptr
Eigen::Isometry3d _world_pose

Public Functions Documentation

function IMU

robot_dart::sensor::IMU::IMU (
    const IMUConfig & config
) 

function angular_position

const Eigen::AngleAxisd & robot_dart::sensor::IMU::angular_position () const

function angular_position_vec

Eigen::Vector3d robot_dart::sensor::IMU::angular_position_vec () const

function angular_velocity

const Eigen::Vector3d & robot_dart::sensor::IMU::angular_velocity () const

function attach_to_joint

inline virtual void robot_dart::sensor::IMU::attach_to_joint (
    dart::dynamics::Joint *,
    const Eigen::Isometry3d &
) override

Implements robot_dart::sensor::Sensor::attach_to_joint


function calculate

virtual void robot_dart::sensor::IMU::calculate (
    double
) override

Implements robot_dart::sensor::Sensor::calculate


function init

virtual void robot_dart::sensor::IMU::init () override

Implements robot_dart::sensor::Sensor::init


function linear_acceleration

const Eigen::Vector3d & robot_dart::sensor::IMU::linear_acceleration () const

function type

virtual std::string robot_dart::sensor::IMU::type () override const

Implements robot_dart::sensor::Sensor::type


Protected Attributes Documentation

variable _angular_pos

Eigen::AngleAxisd robot_dart::sensor::IMU::_angular_pos;

variable _angular_vel

Eigen::Vector3d robot_dart::sensor::IMU::_angular_vel;

variable _config

IMUConfig robot_dart::sensor::IMU::_config;

variable _linear_accel

Eigen::Vector3d robot_dart::sensor::IMU::_linear_accel;


The documentation for this class was generated from the following file robot_dart/sensor/imu.hpp