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¶
function activate¶
function active¶
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¶
function calculate¶
function detach¶
function frequency¶
function init¶
function pose¶
function refresh¶
function set_frequency¶
function set_pose¶
function set_simu¶
function simu¶
function type¶
function ~Sensor¶
Protected Attributes Documentation¶
variable _active¶
variable _attached_tf¶
variable _attached_to_body¶
variable _attached_to_joint¶
variable _attaching_to_body¶
variable _attaching_to_joint¶
variable _body_attached¶
variable _frequency¶
variable _joint_attached¶
variable _simu¶
variable _world_pose¶
The documentation for this class was generated from the following file robot_dart/sensor/sensor.hpp