#include <jsk_topic_tools/diagnostic_nodelet.h>
#include <jsk_recognition_msgs/ClusterPointIndices.h>
#include <jsk_recognition_msgs/SimpleHandle.h>
#include <geometry_msgs/PointStamped.h>
#include <geometry_msgs/PoseStamped.h>
#include <geometry_msgs/Pose.h>
#include <std_msgs/Float64.h>
#include <sensor_msgs/PointCloud2.h>
#include <visualization_msgs/Marker.h>
#include <visualization_msgs/MarkerArray.h>
#include <message_filters/subscriber.h>
#include <message_filters/time_synchronizer.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>
#include <tf/transform_listener.h>
#include <tf/tf.h>
Go to the source code of this file.
Classes | |
class | handle_model |
class | jsk_pcl_ros::HintedHandleEstimator |
Namespaces | |
namespace | jsk_pcl_ros |
Functions | |
geometry_msgs::Pose | change_pose (geometry_msgs::Pose base_pose, geometry_msgs::Pose child_pose) |
visualization_msgs::Marker | make_box (float s_x, float s_y, float s_z, float r, float g, float b, float x, float y, float z) |
visualization_msgs::MarkerArray | make_handle_array (geometry_msgs::PoseStamped pose, handle_model handle) |
tf::Transform | pose_to_tf (geometry_msgs::Pose pose) |
geometry_msgs::Pose | tf_to_pose (tf::Transform transform) |
geometry_msgs::Pose change_pose | ( | geometry_msgs::Pose | base_pose, |
geometry_msgs::Pose | child_pose | ||
) |
Definition at line 82 of file hinted_handle_estimator.h.
visualization_msgs::Marker make_box | ( | float | s_x, |
float | s_y, | ||
float | s_z, | ||
float | r, | ||
float | g, | ||
float | b, | ||
float | x, | ||
float | y, | ||
float | z | ||
) |
Definition at line 86 of file hinted_handle_estimator.h.
visualization_msgs::MarkerArray make_handle_array | ( | geometry_msgs::PoseStamped | pose, |
handle_model | handle | ||
) |
Definition at line 105 of file hinted_handle_estimator.h.
Definition at line 71 of file hinted_handle_estimator.h.
geometry_msgs::Pose tf_to_pose | ( | tf::Transform | transform | ) |
Definition at line 74 of file hinted_handle_estimator.h.