#include <Eigen/Geometry>
#include <ignition/math/Vector3.hh>
#include <ignition/math/Quaternion.hh>
#include <ignition/math/Pose3.hh>
#include <gazebo/msgs/wrench_stamped.pb.h>
#include <orca/math/Utils.h>
#include <stdio.h>
Go to the source code of this file.
|
Eigen::Matrix< double, 6, 1 > & | gazeboMsgToEigen (const ::gazebo::msgs::WrenchStamped &w, Eigen::Matrix< double, 6, 1 > &e_out) |
|
Eigen::Matrix< double, 6, 1 > | gazeboMsgToEigen (const ::gazebo::msgs::WrenchStamped &w) |
|
Eigen::Quaterniond | quatFromRPY (double roll, double pitch, double yaw) |
|
Eigen::Vector3d | convVec3 (const ignition::math::Vector3d &_vec3) |
|
Eigen::Vector3d | convVec3 (const gazebo::msgs::Vector3d &_vec3) |
|
ignition::math::Vector3d | convVec3 (const Eigen::Vector3d &_vec3) |
|
Eigen::Quaterniond | convQuat (const ignition::math::Quaterniond &_quat) |
|
ignition::math::Quaterniond | convQuat (const Eigen::Quaterniond &_quat) |
|
Eigen::Affine3d | convPose (const ignition::math::Pose3d &_pose) |
|
ignition::math::Pose3d | convPose (const Eigen::Affine3d &_T) |
|
std::string | custom_exec (const std::string &_cmd) |
|
◆ convPose() [1/2]
Eigen::Affine3d convPose |
( |
const ignition::math::Pose3d & |
_pose | ) |
|
|
inline |
◆ convPose() [2/2]
ignition::math::Pose3d convPose |
( |
const Eigen::Affine3d & |
_T | ) |
|
|
inline |
◆ convQuat() [1/2]
Eigen::Quaterniond convQuat |
( |
const ignition::math::Quaterniond & |
_quat | ) |
|
|
inline |
◆ convQuat() [2/2]
ignition::math::Quaterniond convQuat |
( |
const Eigen::Quaterniond & |
_quat | ) |
|
|
inline |
◆ convVec3() [1/3]
Eigen::Vector3d convVec3 |
( |
const ignition::math::Vector3d & |
_vec3 | ) |
|
|
inline |
◆ convVec3() [2/3]
Eigen::Vector3d convVec3 |
( |
const gazebo::msgs::Vector3d & |
_vec3 | ) |
|
|
inline |
◆ convVec3() [3/3]
ignition::math::Vector3d convVec3 |
( |
const Eigen::Vector3d & |
_vec3 | ) |
|
|
inline |
◆ custom_exec()
std::string custom_exec |
( |
const std::string & |
_cmd | ) |
|
|
inline |
◆ gazeboMsgToEigen() [1/2]
Eigen::Matrix<double,6,1>& gazeboMsgToEigen |
( |
const ::gazebo::msgs::WrenchStamped & |
w, |
|
|
Eigen::Matrix< double, 6, 1 > & |
e_out |
|
) |
| |
|
inline |
◆ gazeboMsgToEigen() [2/2]
Eigen::Matrix<double,6,1> gazeboMsgToEigen |
( |
const ::gazebo::msgs::WrenchStamped & |
w | ) |
|
|
inline |
◆ quatFromRPY()
Eigen::Quaterniond quatFromRPY |
( |
double |
roll, |
|
|
double |
pitch, |
|
|
double |
yaw |
|
) |
| |
|
inline |