Skip to content

Class robot_dart::sensor::Sensor

ClassList > robot_dart > sensor > Sensor

Inherited by the following classes: robot_dart::gui::magnum::sensor::Camera, robot_dart::sensor::ForceTorque, robot_dart::sensor::IMU, robot_dart::sensor::Torque

Public Functions

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
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 Sensor

robot_dart::sensor::Sensor::Sensor (
    size_t freq=40
) 

function activate

void robot_dart::sensor::Sensor::activate (
    bool enable=true
) 

function active

bool robot_dart::sensor::Sensor::active () const

function attach_to_body [½]

virtual void robot_dart::sensor::Sensor::attach_to_body (
    dart::dynamics::BodyNode * body,
    const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()
) 

function attach_to_body [2/2]

inline void robot_dart::sensor::Sensor::attach_to_body (
    const std::shared_ptr< Robot > & robot,
    const std::string & body_name,
    const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()
) 

function attach_to_joint [½]

virtual void robot_dart::sensor::Sensor::attach_to_joint (
    dart::dynamics::Joint * joint,
    const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()
) 

function attach_to_joint [2/2]

inline void robot_dart::sensor::Sensor::attach_to_joint (
    const std::shared_ptr< Robot > & robot,
    const std::string & joint_name,
    const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()
) 

function attached_to

const std::string & robot_dart::sensor::Sensor::attached_to () const

function calculate

virtual void robot_dart::sensor::Sensor::calculate (
    double
) = 0

function detach

void robot_dart::sensor::Sensor::detach () 

function frequency

size_t robot_dart::sensor::Sensor::frequency () const

function init

virtual void robot_dart::sensor::Sensor::init () = 0

function pose

const Eigen::Isometry3d & robot_dart::sensor::Sensor::pose () const

function refresh

void robot_dart::sensor::Sensor::refresh (
    double t
) 

function set_frequency

void robot_dart::sensor::Sensor::set_frequency (
    size_t freq
) 

function set_pose

void robot_dart::sensor::Sensor::set_pose (
    const Eigen::Isometry3d & tf
) 

function set_simu

void robot_dart::sensor::Sensor::set_simu (
    RobotDARTSimu * simu
) 

function simu

const RobotDARTSimu * robot_dart::sensor::Sensor::simu () const

function type

virtual std::string robot_dart::sensor::Sensor::type () const = 0

function ~Sensor

inline virtual robot_dart::sensor::Sensor::~Sensor () 

Protected Attributes Documentation

variable _active

bool robot_dart::sensor::Sensor::_active;

variable _attached_tf

Eigen::Isometry3d robot_dart::sensor::Sensor::_attached_tf;

variable _attached_to_body

bool robot_dart::sensor::Sensor::_attached_to_body;

variable _attached_to_joint

bool robot_dart::sensor::Sensor::_attached_to_joint;

variable _attaching_to_body

bool robot_dart::sensor::Sensor::_attaching_to_body;

variable _attaching_to_joint

bool robot_dart::sensor::Sensor::_attaching_to_joint;

variable _body_attached

dart::dynamics::BodyNode* robot_dart::sensor::Sensor::_body_attached;

variable _frequency

size_t robot_dart::sensor::Sensor::_frequency;

variable _joint_attached

dart::dynamics::Joint* robot_dart::sensor::Sensor::_joint_attached;

variable _simu

RobotDARTSimu* robot_dart::sensor::Sensor::_simu;

variable _world_pose

Eigen::Isometry3d robot_dart::sensor::Sensor::_world_pose;


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