42 #include <ar_track_alvar_msgs/AlvarMarker.h> 43 #include <ar_track_alvar_msgs/AlvarMarkers.h> 47 #include <sensor_msgs/PointCloud2.h> 49 #include <pcl/point_types.h> 50 #include <pcl/registration/icp.h> 51 #include <pcl/registration/registration.h> 53 #include <geometry_msgs/PoseStamped.h> 56 #include <pcl/ModelCoefficients.h> 57 #include <pcl/point_types.h> 58 #include <pcl/sample_consensus/method_types.h> 59 #include <pcl/sample_consensus/model_types.h> 60 #include <pcl/segmentation/sac_segmentation.h> 62 #include <pcl/filters/extract_indices.h> 63 #include <boost/lexical_cast.hpp> 72 #define VISIBLE_MARKER 2 73 #define GHOST_MARKER 3 81 using namespace alvar;
83 using boost::make_shared;
118 visualization_msgs::Marker rvizMarker;
120 rvizMarker.header.frame_id = frame;
123 rvizMarker.ns =
"3dpts";
125 rvizMarker.scale.x =
rad;
126 rvizMarker.scale.y =
rad;
127 rvizMarker.scale.z =
rad;
129 rvizMarker.type = visualization_msgs::Marker::SPHERE_LIST;
130 rvizMarker.action = visualization_msgs::Marker::ADD;
133 rvizMarker.color.r = 0.0f;
134 rvizMarker.color.g = 1.0f;
135 rvizMarker.color.b = 1.0f;
136 rvizMarker.color.a = 1.0;
139 rvizMarker.color.r = 1.0f;
140 rvizMarker.color.g = 0.0f;
141 rvizMarker.color.b = 1.0f;
142 rvizMarker.color.a = 1.0;
145 rvizMarker.color.r = 1.0f;
146 rvizMarker.color.g = 1.0f;
147 rvizMarker.color.b = 0.0f;
148 rvizMarker.color.a = 1.0;
152 for(
int i=0; i<cloud->points.size(); i++){
153 p.x = cloud->points[i].x;
154 p.y = cloud->points[i].y;
155 p.z = cloud->points[i].z;
156 rvizMarker.points.push_back(p);
160 rvizMarkerPub2_.
publish (rvizMarker);
166 visualization_msgs::Marker rvizMarker;
168 rvizMarker.header.frame_id = frame;
171 rvizMarker.ns =
"arrow";
173 rvizMarker.scale.x = 0.01;
174 rvizMarker.scale.y = 0.01;
175 rvizMarker.scale.z = 0.1;
177 rvizMarker.type = visualization_msgs::Marker::ARROW;
178 rvizMarker.action = visualization_msgs::Marker::ADD;
180 for(
int i=0; i<3; i++){
181 rvizMarker.points.clear();
182 rvizMarker.points.push_back(start);
184 end.x = start.x + mat[0][i];
185 end.y = start.y + mat[1][i];
186 end.z = start.z + mat[2][i];
187 rvizMarker.points.push_back(end);
188 rvizMarker.id += 10*i;
192 rvizMarker.color.r = 1.0f;
193 rvizMarker.color.g = 0.0f;
194 rvizMarker.color.b = 0.0f;
195 rvizMarker.color.a = 1.0;
198 rvizMarker.color.r = 0.0f;
199 rvizMarker.color.g = 1.0f;
200 rvizMarker.color.b = 0.0f;
201 rvizMarker.color.a = 1.0;
204 rvizMarker.color.r = 0.0f;
205 rvizMarker.color.g = 0.0f;
206 rvizMarker.color.b = 1.0f;
207 rvizMarker.color.a = 1.0;
211 rvizMarkerPub2_.
publish (rvizMarker);
219 bund_corners.clear();
220 bund_corners.resize(4);
221 for(
int i=0; i<4; i++){
222 bund_corners[i].x = 0;
223 bund_corners[i].y = 0;
224 bund_corners[i].z = 0;
235 for (
size_t i=0; i<marker_detector.
markers->size(); i++)
238 int id = marker->
GetId();
241 if (index < 0)
continue;
247 std::string marker_frame =
"ar_marker_";
248 std::stringstream mark_out;
250 std::string id_string = mark_out.str();
251 marker_frame += id_string;
254 for(
int j = 0; j < 4; ++j)
257 gm::PointStamped p, output_p;
258 p.header.frame_id = marker_frame;
259 p.point.x = corner_coord.
y()/100.0;
260 p.point.y = -corner_coord.
x()/100.0;
261 p.point.z = corner_coord.
z()/100.0;
268 ROS_ERROR(
"ERROR InferCorners: %s",ex.what());
272 bund_corners[j].x += output_p.point.x;
273 bund_corners[j].y += output_p.point.y;
274 bund_corners[j].z += output_p.point.z;
282 for(
int i=0; i<4; i++){
283 bund_corners[i].x /= n_est;
284 bund_corners[i].y /= n_est;
285 bund_corners[i].z /= n_est;
296 gm::PoseStamped pose;
298 pose.header.frame_id = cloud.header.frame_id;
301 draw3dPoints(selected_points, cloud.header.frame_id, 1,
id, 0.005);
305 if(isnan(corners_3D[0].
x) || isnan(corners_3D[0].
y) || isnan(corners_3D[0].
z) ||
306 isnan(corners_3D[3].x) || isnan(corners_3D[3].y) || isnan(corners_3D[3].z))
308 if(isnan(corners_3D[1].x) || isnan(corners_3D[1].y) || isnan(corners_3D[1].z) ||
309 isnan(corners_3D[2].x) || isnan(corners_3D[2].y) || isnan(corners_3D[2].z))
325 if(isnan(corners_3D[0].x) || isnan(corners_3D[0].y) || isnan(corners_3D[0].z) ||
326 isnan(corners_3D[1].x) || isnan(corners_3D[1].y) || isnan(corners_3D[1].z))
328 if(isnan(corners_3D[3].x) || isnan(corners_3D[3].y) || isnan(corners_3D[3].z) ||
329 isnan(corners_3D[2].x) || isnan(corners_3D[2].y) || isnan(corners_3D[2].z))
343 ARCloud::Ptr orient_points(
new ARCloud());
344 orient_points->points.push_back(corners_3D[i1]);
345 draw3dPoints(orient_points, cloud.header.frame_id, 3,
id+1000, 0.008);
347 orient_points->clear();
348 orient_points->points.push_back(corners_3D[i2]);
349 draw3dPoints(orient_points, cloud.header.frame_id, 2,
id+2000, 0.008);
353 if(succ < 0)
return -1;
357 if(succ < 0)
return -1;
359 drawArrow(pose.pose.position, mat, cloud.header.frame_id, 1,
id);
387 for (
size_t i=0; i<marker_detector.
markers->size(); i++)
389 vector<cv::Point, Eigen::aligned_allocator<cv::Point> > pixels;
421 if(ori >= 0 && ori < 4){
427 ROS_ERROR(
"FindMarkerBundles: Bad Orientation: %i for ID: %i", ori,
id);
451 pixels.push_back(cv::Point(p.x, p.y));
478 if(
InferCorners(cloud, *(multi_marker_bundles[i]), inferred_corners) >= 0){
479 ARCloud::Ptr inferred_cloud(
new ARCloud(inferred_corners));
493 med_filts[i]->
addPose(bundlePoses[i]);
495 bundlePoses[i] = ret_pose;
504 void makeMarkerMsgs(
int type,
int id,
Pose &p, sensor_msgs::ImageConstPtr image_msg,
tf::StampedTransform &CamToOutput, visualization_msgs::Marker *rvizMarker, ar_track_alvar_msgs::AlvarMarker *ar_pose_marker,
int confidence){
505 double px,py,pz,qx,qy,qz,qw;
525 std::string markerFrame =
"ar_marker_";
526 std::stringstream out;
528 std::string id_string = out.str();
529 markerFrame += id_string;
530 tf::StampedTransform camToMarker (t, image_msg->header.stamp, image_msg->header.frame_id, markerFrame.c_str());
535 rvizMarker->header.frame_id = image_msg->header.frame_id;
536 rvizMarker->header.stamp = image_msg->header.stamp;
544 rvizMarker->ns =
"main_shapes";
546 rvizMarker->ns =
"basic_shapes";
549 rvizMarker->type = visualization_msgs::Marker::CUBE;
550 rvizMarker->action = visualization_msgs::Marker::ADD;
554 rvizMarker->color.r = 1.0f;
555 rvizMarker->color.g = 0.0f;
556 rvizMarker->color.b = 0.0f;
557 rvizMarker->color.a = 1.0;
560 rvizMarker->color.r = 0.0f;
561 rvizMarker->color.g = 1.0f;
562 rvizMarker->color.b = 0.0f;
563 rvizMarker->color.a = 0.7;
566 rvizMarker->color.r = 0.0f;
567 rvizMarker->color.g = 0.0f;
568 rvizMarker->color.b = 1.0f;
569 rvizMarker->color.a = 0.5;
582 ar_pose_marker->header.stamp = image_msg->header.stamp;
583 ar_pose_marker->id = id;
584 ar_pose_marker->confidence = confidence;
587 ar_pose_marker = NULL;
595 sensor_msgs::ImagePtr image_msg(
new sensor_msgs::Image);
611 visualization_msgs::Marker rvizMarker;
612 ar_track_alvar_msgs::AlvarMarker ar_pose_marker;
621 image_msg->header.stamp = msg->header.stamp;
622 image_msg->header.frame_id = msg->header.frame_id;
632 IplImage ipl_image = cv_ptr_->image;
635 for (
size_t i=0; i<marker_detector.
markers->size(); i++)
637 int id = (*(marker_detector.
markers))[i].GetId();
643 bool should_draw =
true;
645 if(
id ==
master_id[j]) should_draw =
false;
647 if(should_draw && (*(marker_detector.
markers))[i].valid){
650 rvizMarkerPub_.
publish (rvizMarker);
660 rvizMarkerPub_.
publish (rvizMarker);
669 ROS_ERROR (
"ar_track_alvar: Image error: %s", image_msg->encoding.c_str ());
679 const CvPoint3D64f& p2,
const CvPoint3D64f& p3,
691 tf::Matrix3x3 m(v[0], v[1], v[2], w[0], w[1], w[2], n[0], n[1], n[2]);
699 Eigen::Matrix3f eig_m;
700 for(
int i=0; i<3; i++){
701 for(
int j=0; j<3; j++){
702 eig_m(i,j) = m[i][j];
705 Eigen::Quaternion<float> eig_quat(eig_m);
715 double qx = (q0.
x() + q1.
x() + q2.
x() + q3.
x()) / 4.0;
716 double qy = (q0.
y() + q1.
y() + q2.
y() + q3.
y()) / 4.0;
717 double qz = (q0.
z() + q1.
z() + q2.
z() + q3.
z()) / 4.0;
732 std::vector<tf::Vector3> rel_corner_coords;
737 rel_corner_coords.clear();
740 CvPoint3D64f mark_corners[4];
741 for(
int j=0; j<4; j++){
747 makeMasterTransform(mark_corners[0], mark_corners[1], mark_corners[2], mark_corners[3], tform);
750 for(
int j=0; j<4; j++){
753 double px = corner_coord.x;
754 double py = corner_coord.y;
755 double pz = corner_coord.z;
759 rel_corner_coords.push_back(ans);
769 int main(
int argc,
char *argv[])
775 std::cout << std::endl;
776 cout <<
"Not enough arguments provided." << endl;
777 cout <<
"Usage: ./findMarkerBundles <marker size in cm> <max new marker error> <max track error> <cam image topic> <cam info topic> <output frame> <median filt size> <list of bundle XML files...>" << endl;
778 std::cout << std::endl;
790 int n_args_before_list = 8;
808 bundlePoses[i].
Reset();
811 vector<int> id_vector = loadHelper.
getIndices();
819 cout<<
"Cannot load file "<< argv[i + n_args_before_list] << endl;
828 arMarkerPub_ = n.
advertise < ar_track_alvar_msgs::AlvarMarkers > (
"ar_pose_marker", 0);
829 rvizMarkerPub_ = n.
advertise < visualization_msgs::Marker > (
"visualization_marker", 0);
830 rvizMarkerPub2_ = n.
advertise < visualization_msgs::Marker > (
"ARmarker_points", 0);
837 ROS_INFO (
"Subscribing to image topic");
double max_new_marker_error
void GetMultiMarkerPoses(IplImage *image, ARCloud &cloud)
void makeMarkerMsgs(int type, int id, Pose &p, sensor_msgs::ImageConstPtr image_msg, tf::StampedTransform &CamToOutput, visualization_msgs::Marker *rvizMarker, ar_track_alvar_msgs::AlvarMarker *ar_pose_marker, int confidence)
void publish(const boost::shared_ptr< M > &message) const
std::string cam_info_topic
virtual unsigned long GetId() const
Get id for this marker This is used e.g. in MarkerDetector to associate a marker id with an appropria...
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void SetMarkerSize(double _edge_length=1, int _res=5, double _margin=2)
int extractOrientation(const pcl::ModelCoefficients &coeffs, const ARPoint &p1, const ARPoint &p2, const ARPoint &p3, const ARPoint &p4, geometry_msgs::Quaternion &retQ)
This file implements a generic marker detector.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::vector< int > marker_status
ARCloud::Ptr filterCloud(const ARCloud &cloud, const std::vector< cv::Point, Eigen::aligned_allocator< cv::Point > > &pixels)
void getPointCloudCallback(const sensor_msgs::PointCloud2ConstPtr &msg)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ros::Publisher rvizMarkerPub2_
Matrix3x3 inverse() const
image_transport::Subscriber cam_sub_
Base class for using MultiMarker.
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::map< int, CvPoint3D64f > pointcloud
int makeMasterTransform(const CvPoint3D64f &p0, const CvPoint3D64f &p1, const CvPoint3D64f &p2, const CvPoint3D64f &p3, tf::Transform &retT)
int get_id_index(int id, bool add_if_missing=false)
std::vector< int > marker_indices
Simple Camera class for calculating distortions, orientation or projections with pre-calibrated camer...
TFSIMD_FORCE_INLINE Vector3 cross(const Vector3 &v) const
ROSCPP_DECL void spin(Spinner &spinner)
std::vector< M, Eigen::aligned_allocator< M > > * markers
TFSIMD_FORCE_INLINE const tfScalar & x() const
TFSIMD_FORCE_INLINE Vector3 normalized() const
void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
MarkerDetector for detecting markers of type M
void draw3dPoints(ARCloud::Ptr cloud, string frame, int color, int id, double rad)
int pointcloud_index(int marker_id, int marker_corner, bool add_if_missing=false)
TFSIMD_FORCE_INLINE const tfScalar & z() const
Pose pose
The current marker Pose.
static const Quaternion & getIdentity()
tf::TransformBroadcaster * tf_broadcaster
geometry_msgs::Point centroid(const ARCloud &points)
Multi marker that uses bundle adjustment to refine the 3D positions of the markers (point cloud)...
void drawArrow(gm::Point start, tf::Matrix3x3 mat, string frame, int color, int id)
ros::Subscriber cloud_sub_
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
std::vector< int > * bundle_indices
TFSIMD_FORCE_INLINE const tfScalar & y() const
Pose representation derived from the Rotation class
EIGEN_MAKE_ALIGNED_OPERATOR_NEW bool valid
TFSIMD_FORCE_INLINE const tfScalar & x() const
std::vector< PointDouble > ros_marker_points_img
Marker points in image coordinates.
pcl::PointCloud< ARPoint > ARCloud
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
Basic 2D Marker functionality.
int main(int argc, char *argv[])
MultiMarkerBundle ** multi_marker_bundles
MarkerDetector< MarkerData > marker_detector
std::string cam_image_topic
TFSIMD_FORCE_INLINE const tfScalar & z() const
TFSIMD_FORCE_INLINE const tfScalar & w() const
int PlaneFitPoseImprovement(int id, const ARCloud &corners_3D, ARCloud::Ptr selected_points, const ARCloud &cloud, Pose &p)
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
This file implements a initialization algorithm to create a multi-marker field configuration.
ALVAR_EXPORT Point< CvPoint2D64f > PointDouble
The default double point type.
bool Load(const char *fname, FILE_FORMAT format=FILE_FORMAT_DEFAULT)
Loads multi marker configuration from a text file.
int calcAndSaveMasterCoords(MultiMarkerBundle &master)
tfScalar determinant() const
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
int Detect(IplImage *image, Camera *cam, bool track=false, bool visualize=false, double max_new_marker_error=0.08, double max_track_error=0.2, LabelingMethod labeling_method=CVSEQ, bool update_pose=true)
Detect Marker 's from image
int extractFrame(const pcl::ModelCoefficients &coeffs, const ARPoint &p1, const ARPoint &p2, const ARPoint &p3, const ARPoint &p4, tf::Matrix3x3 &retmat)
ar_track_alvar_msgs::AlvarMarkers arPoseMarkers_
pcl::ModelCoefficients coeffs
This file implements an algorithm to create a multi-marker field configuration.
cv_bridge::CvImagePtr cv_ptr_
tf::TransformListener * tf_listener
ROSCPP_DECL void spinOnce()
ros::Publisher arMarkerPub_
ar_track_alvar::ARCloud ros_corners_3D
std::vector< int > getIndices()
PlaneFitResult fitPlane(ARCloud::ConstPtr cloud)
int InferCorners(const ARCloud &cloud, MultiMarkerBundle &master, ARCloud &bund_corners)
Quaternion normalized() const
ros::Publisher rvizMarkerPub_
ata::MedianFilter ** med_filts
std::vector< std::vector< tf::Vector3 > > rel_corners