hinted_handle_estimator.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 
37 #ifndef JSK_PCL_ROS_HINTED_HANDLE_ESTIMATOR_H_
38 #define JSK_PCL_ROS_HINTED_HANDLE_ESTIMATOR_H_
39 
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>
54 #include <tf/transform_listener.h>
55 #include <tf/tf.h>
56 
57 
59 {
60 public:
61  double finger_l;
62  double finger_d;
63  double finger_w;
64  double arm_l;
65  double arm_d;
66  double arm_w;
68  }
69 };
70 
71 tf::Transform pose_to_tf(geometry_msgs::Pose pose){
72  return tf::Transform(tf::Quaternion(pose.orientation.x, pose.orientation.y, pose.orientation.z, pose.orientation.w), tf::Vector3(pose.position.x, pose.position.y, pose.position.z));
73 }
74 geometry_msgs::Pose tf_to_pose(tf::Transform transform){
75  geometry_msgs::Pose pose;
77  transform.getBasis().getRotation(q);
78  pose.orientation.x = q.getX(); pose.orientation.y=q.getY(); pose.orientation.z=q.getZ(), pose.orientation.w=q.getW();
79  pose.position.x=transform.getOrigin().getX(), pose.position.y=transform.getOrigin().getY(), pose.position.z=transform.getOrigin().getZ();
80  return pose;
81 }
82 geometry_msgs::Pose change_pose(geometry_msgs::Pose base_pose, geometry_msgs::Pose child_pose){
83  return tf_to_pose(pose_to_tf(base_pose)*pose_to_tf(child_pose));
84 }
85 
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)
87 {
88  visualization_msgs::Marker marker;
89  marker.type = visualization_msgs::Marker::CUBE;
90  marker.scale.x = s_x;
91  marker.scale.y = s_y;
92  marker.scale.z = s_z;
93  marker.color.r = r;
94  marker.color.g = g;
95  marker.color.b = b;
96  marker.color.a = 1.0;
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;
102  return marker;
103 }
104 
105 visualization_msgs::MarkerArray make_handle_array(geometry_msgs::PoseStamped pose, handle_model handle){
106  visualization_msgs::MarkerArray markerArray_msg;
107  visualization_msgs::Marker marker_msg = make_box(handle.finger_l, handle.finger_w, handle.finger_d, 1.0, 0, 0, handle.finger_l*0.5, handle.arm_w*0.5 -handle.finger_w*0.5, 0);
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");
111  marker_msg.id = 1;
112  markerArray_msg.markers.push_back(marker_msg);
113  marker_msg = make_box(handle.finger_l, handle.finger_w, handle.finger_d, 0, 1.0, 0, handle.finger_l*0.5, -handle.arm_w*0.5 +handle.finger_w*0.5, 0);
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");
117  marker_msg.id = 2;
118  markerArray_msg.markers.push_back(marker_msg);
119  marker_msg = make_box(handle.arm_l-handle.finger_l, handle.arm_w, handle.arm_d, 0, 0, 1.0, -(handle.arm_l-handle.finger_l)*0.5, 0, 0);
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");
123  marker_msg.id = 3;
124  markerArray_msg.markers.push_back(marker_msg);
125  return markerArray_msg;
126 }
127 
128 namespace jsk_pcl_ros
129 {
131  {
132  public:
133  HintedHandleEstimator(): DiagnosticNodelet("HintedHandleEstimator") {}
135  sensor_msgs::PointCloud2,
136  geometry_msgs::PointStamped
140  protected:
141  virtual void onInit();
142  virtual void subscribe();
143  virtual void unsubscribe();
144  virtual void estimate(
145  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
146  const geometry_msgs::PointStampedConstPtr &point_msg);
147 
157  private:
158 
159  };
160 }
161 
162 #endif
TFSIMD_FORCE_INLINE Matrix3x3 & getBasis()
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
TFSIMD_FORCE_INLINE const tfScalar & getY() const
geometry_msgs::Pose tf_to_pose(tf::Transform transform)
TFSIMD_FORCE_INLINE const tfScalar & getW() const
pose
TFSIMD_FORCE_INLINE const tfScalar & getZ() const
void getRotation(Quaternion &q) const
q
void subscribe()
geometry_msgs::Pose change_pose(geometry_msgs::Pose base_pose, geometry_msgs::Pose child_pose)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
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)
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
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
message_filters::Subscriber< geometry_msgs::PointStamped > sub_point_


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:46