Utilities like timers, mappings between libraries etc.
More...
|
| class | arl::utils::Timer |
| | Provides timing capabilities, like measure the time elapsed since the last call (e.g. useful in a control loop). More...
|
| |
|
| void | arl::utils::armaToEigen (const arma::mat &arma, Eigen::MatrixXd *eigen) |
| |
| void | arl::utils::armaToEigen (const arma::vec &arma, Eigen::VectorXd *eigen) |
| |
| void | arl::utils::eigenToArma (const Eigen::MatrixXd &eigen, arma::mat *arma) |
| |
| void | arl::utils::eigenToArma (const Eigen::VectorXd &eigen, arma::vec *arma) |
| |
| void | arl::utils::armaToRos (const arma::mat &arma, sensor_msgs::PointCloud *ros, const std::string &frame_id="world") |
| | Converts an arma matrix to a PointCloud ROS msg. More...
|
| |
| void | arl::utils::armaToRos (const arma::mat &arma, geometry_msgs::PolygonStamped *ros, const std::string &frame_id="world") |
| | Converts an arma matrix to a PolygonStamped message. More...
|
| |
| void | arl::utils::rosToArma (const sensor_msgs::PointCloud &ros, arma::mat *arma) |
| | Converts a ROS PointCloud msg to an arma matrix. More...
|
| |
| void | arl::utils::rosToArma (const geometry_msgs::PolygonStamped &ros, arma::mat *arma) |
| | Converts a PolygonStamped message to an arma matrix. More...
|
| |
| void | arl::utils::rosToArma (const geometry_msgs::TransformStamped &ros, arma::mat *arma) |
| | Converts a geometry_msgs/TransformStamped message to an arma matrix. More...
|
| |
| void | arl::utils::rosToArma (const geometry_msgs::PoseStamped &ros, arma::mat *arma) |
| | Converts a geometry_msgs/PoseStamped message to an arma matrix. More...
|
| |
| void | arl::utils::armaToRos (const arma::mat &arma, geometry_msgs::PoseStamped *ros, const std::string &frame_id="world") |
| | Converts an arma matrix to a geometry_msgs/PoseStamped. More...
|
| |
| std::string | arl::utils::getAlias (const std::string &name) |
| |
Utilities like timers, mappings between libraries etc.
| void arl::utils::armaToEigen |
( |
const arma::mat & |
arma, |
|
|
Eigen::MatrixXd * |
eigen |
|
) |
| |
|
inline |
| void arl::utils::armaToEigen |
( |
const arma::vec & |
arma, |
|
|
Eigen::VectorXd * |
eigen |
|
) |
| |
|
inline |
| void arl::utils::armaToRos |
( |
const arma::mat & |
arma, |
|
|
sensor_msgs::PointCloud * |
ros, |
|
|
const std::string & |
frame_id = "world" |
|
) |
| |
|
inline |
Converts an arma matrix to a PointCloud ROS msg.
The armadillo matrix is assumed to be nx3, for a point cloud with n 3D points.
- Parameters
-
| kdl | The arma matrix as input |
| ros | The point cloud as ouput |
| void arl::utils::armaToRos |
( |
const arma::mat & |
arma, |
|
|
geometry_msgs::PolygonStamped * |
ros, |
|
|
const std::string & |
frame_id = "world" |
|
) |
| |
|
inline |
Converts an arma matrix to a PolygonStamped message.
The armadillo matrix is assumed to be nx3, for a point cloud with n 3D points.
- Parameters
-
| kdl | The arma matrix as input |
| ros | The polygon as ouput |
| frame_id | The name of the reference frame |
| void arl::utils::armaToRos |
( |
const arma::mat & |
arma, |
|
|
geometry_msgs::PoseStamped * |
ros, |
|
|
const std::string & |
frame_id = "world" |
|
) |
| |
|
inline |
Converts an arma matrix to a geometry_msgs/PoseStamped.
The armadillo matrix is assumed to be 4x4 homogeneous matrix
- Parameters
-
| arma | The arma matrix as input |
| ros | The PoseStamped as output |
| frame_id | The name of the reference frame |
| void arl::utils::eigenToArma |
( |
const Eigen::MatrixXd & |
eigen, |
|
|
arma::mat * |
arma |
|
) |
| |
|
inline |
| void arl::utils::eigenToArma |
( |
const Eigen::VectorXd & |
eigen, |
|
|
arma::vec * |
arma |
|
) |
| |
|
inline |
| std::string arl::utils::getAlias |
( |
const std::string & |
name | ) |
|
Returns the alias of a robot. In general tranforms a string to lower case and replace the space with underscores. E.g. the string "KUKA LBR" will be returned as "kuka_lbr".
- Parameters
-
| name | The initial string as input |
| alias | The final string as output. |
| void arl::utils::rosToArma |
( |
const sensor_msgs::PointCloud & |
ros, |
|
|
arma::mat * |
arma |
|
) |
| |
|
inline |
Converts a ROS PointCloud msg to an arma matrix.
The armadillo matrix will be returned as nx3, for a point cloud with n 3D points.
- Parameters
-
| ros | The point cloud as input |
| kdl | The arma matrix as output |
| void arl::utils::rosToArma |
( |
const geometry_msgs::PolygonStamped & |
ros, |
|
|
arma::mat * |
arma |
|
) |
| |
|
inline |
Converts a PolygonStamped message to an arma matrix.
The armadillo matrix is returned as a nx3 matrix, for a point cloud with n 3D points.
- Parameters
-
| ros | The polygon as input |
| kdl | The arma matrix as output |
| void arl::utils::rosToArma |
( |
const geometry_msgs::TransformStamped & |
ros, |
|
|
arma::mat * |
arma |
|
) |
| |
|
inline |
Converts a geometry_msgs/TransformStamped message to an arma matrix.
The armadillo matrix is returned as a 4x4 matrix which is a homogeneous transformation.
- Parameters
-
| ros | The TransformStamped |
| arma | The arma matrix as output |
| void arl::utils::rosToArma |
( |
const geometry_msgs::PoseStamped & |
ros, |
|
|
arma::mat * |
arma |
|
) |
| |
|
inline |
Converts a geometry_msgs/PoseStamped message to an arma matrix.
The armadillo matrix is returned as a 4x4 matrix which is a homogeneous transformation.
- Parameters
-
| ros | The PoseStamped |
| arma | The arma matrix as output |