Class robot_dart::sensor::ForceTorque¶
ClassList > robot_dart > sensor > ForceTorque
Inherits the following classes: robot_dart::sensor::Sensor
Public Functions¶
| Type | Name |
|---|---|
| ForceTorque (dart::dynamics::Joint * joint, size_t frequency=1000, const std::string & direction="child_to_parent") |
|
| ForceTorque (const std::shared_ptr< Robot > & robot, const std::string & joint_name, size_t frequency=1000, const std::string & direction="child_to_parent") |
|
| virtual void | attach_to_body (dart::dynamics::BodyNode *, const Eigen::Isometry3d &) override |
| virtual void | calculate (double) override |
| Eigen::Vector3d | force () const |
| virtual void | init () override |
| Eigen::Vector3d | torque () const |
| virtual std::string | type () override const |
| const Eigen::Vector6d & | wrench () 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 |
|---|---|
| std::string | _direction |
| Eigen::Vector6d | _wrench |
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 ForceTorque [½]¶
robot_dart::sensor::ForceTorque::ForceTorque (
dart::dynamics::Joint * joint,
size_t frequency=1000,
const std::string & direction="child_to_parent"
)
function ForceTorque [2/2]¶
inline robot_dart::sensor::ForceTorque::ForceTorque (
const std::shared_ptr< Robot > & robot,
const std::string & joint_name,
size_t frequency=1000,
const std::string & direction="child_to_parent"
)
function attach_to_body¶
inline virtual void robot_dart::sensor::ForceTorque::attach_to_body (
dart::dynamics::BodyNode *,
const Eigen::Isometry3d &
) override
Implements robot_dart::sensor::Sensor::attach_to_body
function calculate¶
Implements robot_dart::sensor::Sensor::calculate
function force¶
function init¶
Implements robot_dart::sensor::Sensor::init
function torque¶
function type¶
Implements robot_dart::sensor::Sensor::type
function wrench¶
Protected Attributes Documentation¶
variable _direction¶
variable _wrench¶
The documentation for this class was generated from the following file robot_dart/sensor/force_torque.hpp