AUTh-ARL Core Stack  0.7
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Groups Pages
ati::sensor::Sensor Class Reference

#include <autharl_ati_sensor.h>

Inheritance diagram for ati::sensor::Sensor:
Collaboration diagram for ati::sensor::Sensor:

Public Member Functions

 Sensor (bool set_bias=true, const std::string &name="Ati Sensor", const std::string &frame_id="ati_mini_40")
 
 Sensor (double m, const std::string &name="Ati Sensor", const std::string &frame_id="ati_sensor")
 Constructor that can be used when you need to read force data which compensate the weight of the tool. More...
 
void getData (KDL::JntArray &output)
 Reads the current joint positions to the robot using KDL. More...
 
void getData (arma::vec &output)
 Reads the current joint positions from the robot using Armadillo. More...
 
void getData (Eigen::VectorXd &output)
 Reads the current joint positions from the robot using Eigen. More...
 
template<typename T >
void getDataTemplate (T &output)
 
Eigen::Vector6d getData (const Eigen::Matrix3d &rotation)
 Function for reading data after the mass compensation of the mounted tool. More...
 
bool isOk ()
 Returns if the robot sensor is ok and operable. Should be implemented according to the robot in use. More...
 
- Public Member Functions inherited from arl::robot::Sensor
 Sensor ()
 Empty constructor. More...
 
 Sensor (const std::string &name="Unnamed")
 Default constructor. More...
 
std::string getName ()
 Returns the name of the sensor. More...
 

Additional Inherited Members

- Public Types inherited from arl::robot::Sensor
enum  Type { FT_SENSOR, FORCE_SENSOR }
 Different sensor types. More...
 
- Public Attributes inherited from arl::robot::Sensor
double cycle
 The control cycle of the robot sensor. More...
 
std::string alias
 The alias of the robot sensor, which is the name in lower case without spaces. More...
 
Type type
 
std::string frame_id
 
- Protected Member Functions inherited from arl::robot::Sensor
void throwFunctionIsNotImplemented (std::string function_name)
 
- Protected Attributes inherited from arl::robot::Sensor
std::string sensor_name
 The name of the robot sensor. More...
 

Constructor & Destructor Documentation

ati::sensor::Sensor::Sensor ( bool  set_bias = true,
const std::string &  name = "Ati Sensor",
const std::string &  frame_id = "ati_mini_40" 
)
explicit
ati::sensor::Sensor::Sensor ( double  m,
const std::string &  name = "Ati Sensor",
const std::string &  frame_id = "ati_sensor" 
)
explicit

Constructor that can be used when you need to read force data which compensate the weight of the tool.

Follow the following steps in order to use the tool compensation:

Parameters
mThe value of the tool mass.
nameThe name of the sensor. Defaults to "Ati Sensor"
frame_idThe frame ID. Defaults to "ati_sensor"

Member Function Documentation

void ati::sensor::Sensor::getData ( KDL::JntArray &  output)
virtual

Reads the current joint positions to the robot using KDL.

Parameters
outputThe output given by the robot sensor

Reimplemented from arl::robot::Sensor.

Here is the call graph for this function:

void ati::sensor::Sensor::getData ( arma::vec &  output)
virtual

Reads the current joint positions from the robot using Armadillo.

Parameters
outputThe output given by the robot sensor

Reimplemented from arl::robot::Sensor.

Here is the call graph for this function:

void ati::sensor::Sensor::getData ( Eigen::VectorXd &  output)
virtual

Reads the current joint positions from the robot using Eigen.

Parameters
outputThe output given by the robot sensor

Reimplemented from arl::robot::Sensor.

Here is the call graph for this function:

Eigen::Vector6d ati::sensor::Sensor::getData ( const Eigen::Matrix3d &  rotation)
virtual

Function for reading data after the mass compensation of the mounted tool.

Warning
Right now this provide compensate values only for the force measurements and the class is aware only for the value of the mass. It is not aware of the center of mass and thus the torque measurements are not compensated yet.
Todo:
Compensate for the torques
Parameters
rotationThe orientation of the sensor (the arm) with respect the base frame.
Returns
The wrench of the tool mass compensated F/T measurements

Reimplemented from arl::robot::Sensor.

Here is the call graph for this function:

template<typename T >
void ati::sensor::Sensor::getDataTemplate ( T &  output)
inline
bool ati::sensor::Sensor::isOk ( )
virtual

Returns if the robot sensor is ok and operable. Should be implemented according to the robot in use.

Returns
True if the robot haven't returns any errors. False otherwise.

Reimplemented from arl::robot::Sensor.