#include <visualization_msgs/MarkerArray.h>#include <pcl/point_types.h>#include <pcl/point_cloud.h>#include <cv_bridge/cv_bridge.h>#include <sensor_msgs/PointCloud2.h>#include <omip_msgs/RigidBodyPosesAndVelsMsg.h>#include <omip_msgs/RigidBodyPoseAndVelMsg.h>#include <omip_msgs/JointMsg.h>#include <omip_msgs/KinematicStructureMsg.h>

Go to the source code of this file.
Classes | |
| struct | omip::_FeaturePCLwc |
| struct | omip::FeaturePCLwc |
Namespaces | |
| namespace | omip |
Defines | |
| #define | OMIP_ADD_POINT4D |
Typedefs | |
| typedef pcl::PointCloud < FeaturePCL > | omip::FeatureCloudPCL |
| typedef pcl::PointCloud < FeaturePCLwc > | omip::FeatureCloudPCLwc |
| typedef pcl::PointXYZL | omip::FeaturePCL |
| typedef void | omip::ft_measurement_ros_t |
| typedef std::pair < cv_bridge::CvImagePtr, cv_bridge::CvImagePtr > | omip::ft_measurement_t |
| typedef sensor_msgs::PointCloud2 | omip::ft_state_ros_t |
| typedef FeatureCloudPCLwc::Ptr | omip::ft_state_t |
| typedef long int | omip::Joint_id_t |
| typedef std::pair < omip_msgs::RigidBodyPoseAndVelMsg, omip_msgs::RigidBodyPoseAndVelMsg > | omip::joint_measurement_t |
| typedef std::map< std::pair < int, int > , boost::shared_ptr < JointCombinedFilter > > | omip::KinematicModel |
| typedef omip_msgs::RigidBodyPosesAndVelsMsg | omip::ks_measurement_ros_t |
| typedef omip_msgs::RigidBodyPosesAndVelsMsg | omip::ks_measurement_t |
| typedef omip_msgs::KinematicStructureMsg::Ptr | omip::ks_state_ros_t |
| typedef KinematicModel | omip::ks_state_t |
| typedef pcl::PointCloud < pcl::PointXYZRGB > | omip::PointCloudPCL |
| typedef pcl::PointCloud< PointPCL > | omip::PointCloudPCLNoColor |
| typedef pcl::PointXYZ | omip::PointPCL |
| typedef long int | omip::RB_id_t |
| typedef sensor_msgs::PointCloud2 | omip::rbt_measurement_ros_t |
| typedef FeatureCloudPCLwc::Ptr | omip::rbt_measurement_t |
| typedef omip_msgs::RigidBodyPosesAndVelsMsg | omip::rbt_state_ros_t |
| typedef omip_msgs::RigidBodyPosesAndVelsMsg | omip::rbt_state_t |
| typedef pcl::PointCloud< PointPCL > | omip::RigidBodyShape |
Enumerations | |
| enum | omip::shape_model_selector_t { omip::BASED_ON_DEPTH = 1, omip::BASED_ON_COLOR = 2, omip::BASED_ON_EXT_DEPTH = 3, omip::BASED_ON_EXT_COLOR = 4, omip::BASED_ON_EXT_DEPTH_AND_COLOR = 5 } |
| enum | omip::static_environment_tracker_t { omip::STATIC_ENVIRONMENT_EKF_TRACKER = 1, omip::STATIC_ENVIRONMENT_ICP_TRACKER = 2 } |
| #define OMIP_ADD_POINT4D |
union { \ float data[4]; \ struct { \ float x; \ float y; \ float z; \ }; \ } EIGEN_ALIGN16; \ inline Eigen::Map<Eigen::Vector3f> getVector3fMap () { return (Eigen::Vector3f::Map (data)); } \ inline const Eigen::Map<const Eigen::Vector3f> getVector3fMap () const { return (Eigen::Vector3f::Map (data)); } \ inline Eigen::Map<Eigen::Vector4f, Eigen::Aligned> getVector4fMap () { return (Eigen::Vector4f::MapAligned (data)); } \ inline const Eigen::Map<const Eigen::Vector4f, Eigen::Aligned> getVector4fMap () const { return (Eigen::Vector4f::MapAligned (data)); } \ inline Eigen::Map<Eigen::Array3f> getArray3fMap () { return (Eigen::Array3f::Map (data)); } \ inline const Eigen::Map<const Eigen::Array3f> getArray3fMap () const { return (Eigen::Array3f::Map (data)); } \ inline Eigen::Map<Eigen::Array4f, Eigen::Aligned> getArray4fMap () { return (Eigen::Array4f::MapAligned (data)); } \ inline const Eigen::Map<const Eigen::Array4f, Eigen::Aligned> getArray4fMap () const { return (Eigen::Array4f::MapAligned (data)); }
Definition at line 48 of file OMIPTypeDefs.h.