Functions
helpers.h File Reference
#include <ros/ros.h>
#include <tf/tf.h>
#include <std_msgs/ColorRGBA.h>
#include <geometry_msgs/Vector3.h>
#include <geometry_msgs/Point.h>
#include <geometry_msgs/Quaternion.h>
#include <geometry_msgs/Pose.h>
#include <geometry_msgs/Transform.h>
#include "pcl/io/pcd_io.h"
#include "pcl/point_types.h"
#include "pcl/filters/passthrough.h"
#include <pcl/features/normal_3d.h>
#include <pcl_ros/transforms.h>
#include <object_manipulator/tools/shape_tools.h>
Include dependency graph for helpers.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Functions

template<class PointT >
void box_filter (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const object_manipulator::shapes::Box &box, bool transform_cloud=false, bool restore_frame=true)
template<class PointT >
void floating_box_filter (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const object_manipulator::shapes::Box &box)
geometry_msgs::PoseStamped generateAlignedPose (const geometry_msgs::PoseStamped original_pose, const geometry_msgs::Vector3 &axis, const geometry_msgs::Vector3 &up)
geometry_msgs::PoseStamped generateRelativePose (geometry_msgs::PoseStamped original_pose, double roll, double pitch, double yaw, double xdist, double ydist, double zdist)
void setMatrixColumns (tf::Matrix3x3 &mat, tf::Vector3 &X, tf::Vector3 &Y, tf::Vector3 &Z)

Function Documentation

template<class PointT >
void box_filter ( const pcl::PointCloud< PointT > &  cloud_in,
pcl::PointCloud< PointT > &  cloud_out,
const object_manipulator::shapes::Box box,
bool  transform_cloud = false,
bool  restore_frame = true 
)

Definition at line 84 of file helpers.h.

template<class PointT >
void floating_box_filter ( const pcl::PointCloud< PointT > &  cloud_in,
pcl::PointCloud< PointT > &  cloud_out,
const object_manipulator::shapes::Box box 
)

Definition at line 130 of file helpers.h.

geometry_msgs::PoseStamped generateAlignedPose ( const geometry_msgs::PoseStamped  original_pose,
const geometry_msgs::Vector3 &  axis,
const geometry_msgs::Vector3 &  up 
) [inline]

Generate a new PoseStamped message with the same origina but specified alignment.

Definition at line 34 of file helpers.h.

geometry_msgs::PoseStamped generateRelativePose ( geometry_msgs::PoseStamped  original_pose,
double  roll,
double  pitch,
double  yaw,
double  xdist,
double  ydist,
double  zdist 
) [inline]

Generate a new PoseStamped message whose pose is relative to original_pose

Definition at line 68 of file helpers.h.

void setMatrixColumns ( tf::Matrix3x3 mat,
tf::Vector3 &  X,
tf::Vector3 &  Y,
tf::Vector3 &  Z 
) [inline]

Definition at line 24 of file helpers.h.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends


pr2_grasp_adjust
Author(s): Adam Leeper
autogenerated on Wed Jan 23 2013 15:27:54