37 #ifndef JSK_PCL_ROS_HINTED_HANDLE_ESTIMATOR_H_ 38 #define JSK_PCL_ROS_HINTED_HANDLE_ESTIMATOR_H_ 41 #include <jsk_recognition_msgs/ClusterPointIndices.h> 42 #include <jsk_recognition_msgs/SimpleHandle.h> 43 #include <geometry_msgs/PointStamped.h> 44 #include <geometry_msgs/PoseStamped.h> 45 #include <geometry_msgs/Pose.h> 46 #include <std_msgs/Float64.h> 47 #include <sensor_msgs/PointCloud2.h> 48 #include <visualization_msgs/Marker.h> 49 #include <visualization_msgs/MarkerArray.h> 75 geometry_msgs::Pose
pose;
78 pose.orientation.x = q.getX(); pose.orientation.y=q.getY(); pose.orientation.z=q.getZ(), pose.orientation.w=q.
getW();
82 geometry_msgs::Pose
change_pose(geometry_msgs::Pose base_pose, geometry_msgs::Pose child_pose){
86 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)
88 visualization_msgs::Marker
marker;
89 marker.type = visualization_msgs::Marker::CUBE;
97 marker.pose.position.x =
x;
98 marker.pose.position.y =
y;
99 marker.pose.position.z =
z;
100 marker.pose.orientation.x = marker.pose.orientation.y = marker.pose.orientation.z = 0;
101 marker.pose.orientation.w = 1.0;
106 visualization_msgs::MarkerArray markerArray_msg;
108 marker_msg.pose =
change_pose(pose.pose, marker_msg.pose);
109 marker_msg.header = pose.header;
110 marker_msg.ns = std::string(
"debug_grasp_model");
112 markerArray_msg.markers.push_back(marker_msg);
114 marker_msg.pose =
change_pose(pose.pose, marker_msg.pose);
115 marker_msg.header = pose.header;
116 marker_msg.ns = std::string(
"debug_grasp_model");
118 markerArray_msg.markers.push_back(marker_msg);
120 marker_msg.pose =
change_pose(pose.pose, marker_msg.pose);
121 marker_msg.header = pose.header;
122 marker_msg.ns = std::string(
"debug_grasp_model");
124 markerArray_msg.markers.push_back(marker_msg);
125 return markerArray_msg;
135 sensor_msgs::PointCloud2,
136 geometry_msgs::PointStamped
141 virtual void onInit();
143 virtual void unsubscribe();
144 virtual void estimate(
145 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
146 const geometry_msgs::PointStampedConstPtr &point_msg);
ros::Publisher pub_debug_marker_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
ros::Publisher pub_handle_
TFSIMD_FORCE_INLINE const tfScalar & getY() const
geometry_msgs::Pose tf_to_pose(tf::Transform transform)
TFSIMD_FORCE_INLINE const tfScalar & getW() const
TFSIMD_FORCE_INLINE const tfScalar & getZ() const
void getRotation(Quaternion &q) const
ros::Publisher pub_length_
geometry_msgs::Pose change_pose(geometry_msgs::Pose base_pose, geometry_msgs::Pose child_pose)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
tf::TransformListener listener_
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)
tf::Transform pose_to_tf(geometry_msgs::Pose pose)
boost::mutex mutex
global mutex.
visualization_msgs::MarkerArray make_handle_array(geometry_msgs::PoseStamped pose, handle_model handle)
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, geometry_msgs::PointStamped > SyncPolicy
TFSIMD_FORCE_INLINE const tfScalar & getX() const
ros::Publisher pub_debug_marker_array_
message_filters::Subscriber< geometry_msgs::PointStamped > sub_point_