#include <cassert>#include <boost/foreach.hpp>#include <gazebo/sensors/SensorManager.hh>#include <urdf_parser/urdf_parser.h>#include <pluginlib/class_list_macros.h>#include <angles/angles.h>#include <Eigen/Core>#include <Eigen/Geometry>#include <joint_limits_interface/joint_limits_urdf.h>#include <transmission_interface/transmission_interface_loader.h>#include <pal_hardware_gazebo/pal_hardware_gazebo.h>
Go to the source code of this file.
Classes | |
| class | xh::XmlrpcHelperException |
Namespaces | |
| namespace | gazebo_ros_control |
| namespace | xh |
Typedefs | |
| typedef XmlRpc::XmlRpcValue | xh::Array |
| typedef Eigen::Isometry3d | eMatrixHom |
| typedef Eigen::Matrix3d | eMatrixRot |
| typedef Eigen::Quaternion< double > | eQuaternion |
| typedef Eigen::Vector3d | eVector3 |
| typedef XmlRpc::XmlRpcValue | xh::Struct |
Functions | |
| void | convert (const urdf::Vector3 &in, eVector3 &out) |
| void | convert (const urdf::Rotation &in, eMatrixRot &out) |
| void | convert (const urdf::Pose &in, eMatrixHom &out) |
| eMatrixHom | createMatrix (eMatrixRot const &rot, eVector3 const &trans) |
| template<class T > | |
| void | xh::fetchParam (ros::NodeHandle nh, const std::string ¶m_name, T &output) |
| std::vector< std::string > | getIds (const ros::NodeHandle &nh, const std::string &key) |
| template<typename T > | |
| Eigen::Matrix< T, 3, 3 > | skew (const Eigen::Matrix< T, 3, 1 > &vec) |
| typedef Eigen::Isometry3d eMatrixHom |
Definition at line 45 of file pal_hardware_gazebo.cpp.
| typedef Eigen::Matrix3d eMatrixRot |
Definition at line 46 of file pal_hardware_gazebo.cpp.
| typedef Eigen::Quaternion<double> eQuaternion |
Definition at line 47 of file pal_hardware_gazebo.cpp.
| typedef Eigen::Vector3d eVector3 |
Definition at line 44 of file pal_hardware_gazebo.cpp.
| void convert | ( | const urdf::Vector3 & | in, |
| eVector3 & | out | ||
| ) |
Definition at line 112 of file pal_hardware_gazebo.cpp.
| void convert | ( | const urdf::Rotation & | in, |
| eMatrixRot & | out | ||
| ) |
Definition at line 116 of file pal_hardware_gazebo.cpp.
| void convert | ( | const urdf::Pose & | in, |
| eMatrixHom & | out | ||
| ) |
Definition at line 129 of file pal_hardware_gazebo.cpp.
| eMatrixHom createMatrix | ( | eMatrixRot const & | rot, |
| eVector3 const & | trans | ||
| ) | [inline] |
Definition at line 120 of file pal_hardware_gazebo.cpp.
| std::vector<std::string> getIds | ( | const ros::NodeHandle & | nh, |
| const std::string & | key | ||
| ) | [inline] |
Definition at line 89 of file pal_hardware_gazebo.cpp.
Definition at line 138 of file pal_hardware_gazebo.cpp.