30 #include <std_msgs/Float32MultiArray.h> 31 #include "find_object_2d/ObjectsStamped.h" 39 objFramePrefix_(
"object")
47 pub_ = nh.advertise<std_msgs::Float32MultiArray>(
"objects", 1);
48 pubStamped_ = nh.advertise<find_object_2d::ObjectsStamped>(
"objectsStamped", 1);
58 std::vector<tf::StampedTransform> transforms;
59 QMultiMap<int, QSize>::const_iterator iterSizes=info.
objDetectedSizes_.constBegin();
60 for(QMultiMap<int, QTransform>::const_iterator iter=info.
objDetected_.constBegin();
66 float objectWidth = iterSizes->width();
67 float objectHeight = iterSizes->height();
70 QPointF center = iter->map(QPointF(objectWidth/2, objectHeight/2));
71 QPointF xAxis = iter->map(QPointF(3*objectWidth/4, objectHeight/2));
72 QPointF yAxis = iter->map(QPointF(objectWidth/2, 3*objectHeight/4));
75 center.x()+0.5f, center.y()+0.5f,
80 xAxis.x()+0.5f, xAxis.y()+0.5f,
85 yAxis.x()+0.5f, yAxis.y()+0.5f,
89 if(std::isfinite(center3D.val[0]) && std::isfinite(center3D.val[1]) && std::isfinite(center3D.val[2]) &&
90 std::isfinite(axisEndX.val[0]) && std::isfinite(axisEndX.val[1]) && std::isfinite(axisEndX.val[2]) &&
91 std::isfinite(axisEndY.val[0]) && std::isfinite(axisEndY.val[1]) && std::isfinite(axisEndY.val[2]))
101 tf::Vector3 xAxis(axisEndX.val[0] - center3D.val[0], axisEndX.val[1] - center3D.val[1], axisEndX.val[2] - center3D.val[2]);
103 tf::Vector3 yAxis(axisEndY.val[0] - center3D.val[0], axisEndY.val[1] - center3D.val[1], axisEndY.val[2] - center3D.val[2]);
107 xAxis.
x(), yAxis.x() ,zAxis.
x(),
108 xAxis.
y(), yAxis.y(), zAxis.
y(),
109 xAxis.
z(), yAxis.z(), zAxis.
z());
111 rotationMatrix.getRotation(q);
116 transforms.push_back(transform);
120 ROS_WARN(
"Object %d detected, center 2D at (%f,%f), but invalid depth, cannot set frame \"%s\"! " 121 "(maybe object is too near of the camera or bad depth image)\n",
123 center.x(), center.y(),
124 QString(
"%1_%2").arg(
objFramePrefix_.c_str()).arg(
id).toStdString().c_str());
127 if(transforms.size())
135 std_msgs::Float32MultiArray msg;
136 find_object_2d::ObjectsStamped msgStamped;
137 msg.data = std::vector<float>(info.
objDetected_.size()*12);
138 msgStamped.objects.data = std::vector<float>(info.
objDetected_.size()*12);
140 QMultiMap<int, QSize>::const_iterator iterSizes=info.
objDetectedSizes_.constBegin();
141 for(QMultiMap<int, QTransform>::const_iterator iter=info.
objDetected_.constBegin();
145 msg.data[i] = msgStamped.objects.data[i] = iter.key(); ++i;
146 msg.data[i] = msgStamped.objects.data[i] = iterSizes->width(); ++i;
147 msg.data[i] = msgStamped.objects.data[i] = iterSizes->height(); ++i;
148 msg.data[i] = msgStamped.objects.data[i] = iter->m11(); ++i;
149 msg.data[i] = msgStamped.objects.data[i] = iter->m12(); ++i;
150 msg.data[i] = msgStamped.objects.data[i] = iter->m13(); ++i;
151 msg.data[i] = msgStamped.objects.data[i] = iter->m21(); ++i;
152 msg.data[i] = msgStamped.objects.data[i] = iter->m22(); ++i;
153 msg.data[i] = msgStamped.objects.data[i] = iter->m23(); ++i;
154 msg.data[i] = msgStamped.objects.data[i] = iter->m31(); ++i;
155 msg.data[i] = msgStamped.objects.data[i] = iter->m32(); ++i;
156 msg.data[i] = msgStamped.objects.data[i] = iter->m33(); ++i;
165 msgStamped.header.frame_id =
frameId_;
166 msgStamped.header.stamp =
stamp_;
174 const cv::Mat & depth,
188 if(!(x >=0 && x<depthImage.cols && y >=0 && y<depthImage.rows))
190 ROS_ERROR(
"Point must be inside the image (x=%d, y=%d), image size=(%d,%d)",
192 depthImage.cols, depthImage.rows);
194 std::numeric_limits<float>::quiet_NaN (),
195 std::numeric_limits<float>::quiet_NaN (),
196 std::numeric_limits<float>::quiet_NaN ());
206 bool isInMM = depthImage.type() == CV_16UC1;
209 float unit_scaling = isInMM?0.001f:1.0f;
210 float constant_x = unit_scaling / fx;
211 float constant_y = unit_scaling / fy;
212 float bad_point = std::numeric_limits<float>::quiet_NaN ();
218 depth = (float)depthImage.at<uint16_t>(y,x);
219 isValid = depth != 0.0f;
223 depth = depthImage.at<
float>(y,x);
224 isValid = std::isfinite(depth);
230 pt.val[0] = pt.val[1] = pt.val[2] = bad_point;
235 pt.val[0] = (float(x) - center_x) * depth * constant_x;
236 pt.val[1] = (float(y) - center_y) * depth * constant_y;
237 pt.val[2] = depth*unit_scaling;
static tf::Quaternion createQuaternionFromRPY(double roll, double pitch, double yaw)
tf::TransformBroadcaster tfBroadcaster_
void publish(const find_object::DetectionInfo &info)
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher pubStamped_
QMultiMap< int, QSize > objDetectedSizes_
void objectsFound(const find_object::DetectionInfo &)
TFSIMD_FORCE_INLINE const tfScalar & x() const
TFSIMD_FORCE_INLINE const tfScalar & z() const
FindObjectROS(QObject *parent=0)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
QMultiMap< int, QTransform > objDetected_
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::string objFramePrefix_
TFSIMD_FORCE_INLINE Vector3 & normalize()
cv::Vec3f getDepth(const cv::Mat &depthImage, int x, int y, float cx, float cy, float fx, float fy)
uint32_t getNumSubscribers() const
void setDepthData(const std::string &frameId, const ros::Time &stamp, const cv::Mat &depth, float depthConstant)