The namespace having miscellaneous code which does not have a specific category.
More...
|
void | armaToEigen (const arma::mat &arma, Eigen::MatrixXd *eigen) |
|
void | armaToEigen (const arma::vec &arma, Eigen::VectorXd *eigen) |
|
void | eigenToArma (const Eigen::MatrixXd &eigen, arma::mat *arma) |
|
void | eigenToArma (const Eigen::VectorXd &eigen, arma::vec *arma) |
|
void | 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 | 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 | rosToArma (const sensor_msgs::PointCloud &ros, arma::mat *arma) |
| Converts a ROS PointCloud msg to an arma matrix. More...
|
|
void | rosToArma (const geometry_msgs::PolygonStamped &ros, arma::mat *arma) |
| Converts a PolygonStamped message to an arma matrix. More...
|
|
void | rosToArma (const geometry_msgs::TransformStamped &ros, arma::mat *arma) |
| Converts a geometry_msgs/TransformStamped message to an arma matrix. More...
|
|
void | rosToArma (const geometry_msgs::PoseStamped &ros, arma::mat *arma) |
| Converts a geometry_msgs/PoseStamped message to an arma matrix. More...
|
|
void | 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...
|
|
void | armaToKdl (const arma::vec &arma, KDL::Vector *kdl) |
| Converts an arma vector to a KDL Vector. More...
|
|
void | armaToKdl (const arma::mat &arma, KDL::Rotation *kdl) |
| Converts a armadillo 3D matrix to a KDL Rotation matrix. More...
|
|
void | armaToKdl (const arma::mat &arma, KDL::Frame *kdl) |
| Converts an arma homogeneous transformation (4x4 matrix) to a KDL Frame. More...
|
|
void | armaToKdl (const arma::vec &arma, KDL::Wrench *kdl) |
|
void | armaToKdl (const arma::vec &arma, KDL::Twist *kdl) |
|
void | armaToKdl (const arma::mat &arma, KDL::Jacobian *kdl) |
|
void | armaToKdl (const arma::vec &arma, KDL::JntArray *kdl) |
|
void | kdlToArma (const KDL::Vector &kdl, arma::vec *arma) |
| Converts a KDL vector to an arma vector. More...
|
|
void | kdlToArma (const KDL::Rotation &kdl, arma::mat *arma) |
| Converts a KDL Rotation to an arma matrix. More...
|
|
void | kdlToArma (const KDL::Frame &kdl, arma::mat *arma) |
| Converts a KDL Frame to an arma homogeneous transformation (4x4 matrix). More...
|
|
void | kdlToArma (const KDL::Wrench &kdl, arma::vec *arma) |
|
void | kdlToArma (const KDL::Twist &kdl, arma::vec *arma) |
|
void | kdlToArma (const KDL::Jacobian &kdl, arma::mat *arma) |
|
void | kdlToArma (const KDL::JntArray &kdl, arma::vec *arma) |
|
void | kdlToEigen (const KDL::Vector &kdl, Eigen::Vector3d *eigen) |
|
void | kdlToEigen (const KDL::Rotation &kdl, Eigen::Matrix3d *eigen) |
|
void | kdlToEigen (const KDL::JntArray &kdl, Eigen::VectorXd *eigen) |
|
void | rosToKdl (const geometry_msgs::Vector3 &ros, KDL::Vector *kdl) |
| Converts a ROS vector (geometry_msgs Vector3) to a KDL Vector. More...
|
|
void | rosToKdl (const geometry_msgs::Point &ros, KDL::Vector *kdl) |
| Converts a ROS Point (geometry_msgs Point) to a KDL Vector. More...
|
|
bool | rosToKdl (const geometry_msgs::Quaternion &ros, KDL::Rotation *kdl, double eps=1e-6) |
| Converts a ROS Quaternion (geometry_msgs Quaternion) to a KDL Rotation. It will perform the conversion even if the quaternion is not unit. More...
|
|
bool | rosToKdl (const geometry_msgs::Pose &ros, KDL::Frame *kdl, double eps=1e-6) |
| Converts a ROS Pose (geometry_msgs Pose) to a KDL Frame. It will perform the conversion even if the quaternion of the pose is not unit. More...
|
|
void | kdlToRos (const KDL::Vector &kdl, geometry_msgs::Vector3 *ros) |
| Converts a KDL vector to a ROS Vector (geometry_msgs Vector3) More...
|
|
void | kdlToRos (const KDL::Vector &kdl, geometry_msgs::Point *ros) |
| Converts a KDL vector to a ROS Point (geometry_msgs Point) More...
|
|
bool | kdlToRos (const KDL::Rotation &kdl, geometry_msgs::Quaternion *ros, double eps=1e-6) |
| Converts a KDL Rotation to a ROS Quaternion (geometry_msgs Quaternion). It will perform the conversion even if the rotation is not legit. More...
|
|
bool | kdlToRos (const KDL::Frame &kdl, geometry_msgs::Pose *ros, double eps=1e-6) |
| Converts a KDL Frame to a ROS pose (geometry_msgs Pose). It will perform the conversion even if the rotation matrix of the frame is not legit. More...
|
|
std::string | getAlias (const std::string &name) |
|
The namespace having miscellaneous code which does not have a specific category.
For example transformation between different data types (from KDL to Armadillo).