#include <autharl_ati_sensor.h>
|
| 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...
|
|
| Sensor () |
| Empty constructor. More...
|
|
| Sensor (const std::string &name="Unnamed") |
| Default constructor. More...
|
|
std::string | getName () |
| Returns the name of the sensor. More...
|
|
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
-
m | The value of the tool mass. |
name | The name of the sensor. Defaults to "Ati Sensor" |
frame_id | The frame ID. Defaults to "ati_sensor" |
void ati::sensor::Sensor::getData |
( |
KDL::JntArray & |
output | ) |
|
|
virtual |
Reads the current joint positions to the robot using KDL.
- Parameters
-
output | The output given by the robot sensor |
Reimplemented from arl::robot::Sensor.
void ati::sensor::Sensor::getData |
( |
arma::vec & |
output | ) |
|
|
virtual |
Reads the current joint positions from the robot using Armadillo.
- Parameters
-
output | The output given by the robot sensor |
Reimplemented from arl::robot::Sensor.
void ati::sensor::Sensor::getData |
( |
Eigen::VectorXd & |
output | ) |
|
|
virtual |
Reads the current joint positions from the robot using Eigen.
- Parameters
-
output | The output given by the robot sensor |
Reimplemented from arl::robot::Sensor.
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
-
rotation | The 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.
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.