42 #include <ar_track_alvar_msgs/AlvarMarker.h> 43 #include <ar_track_alvar_msgs/AlvarMarkers.h> 48 #include <dynamic_reconfigure/server.h> 49 #include <ar_track_alvar/ParamsConfig.h> 50 #include <Eigen/StdVector> 58 using namespace alvar;
60 using boost::make_shared;
91 void draw3dPoints(ARCloud::Ptr cloud,
string frame,
int color,
int id,
double rad)
93 visualization_msgs::Marker rvizMarker;
95 rvizMarker.header.frame_id = frame;
98 rvizMarker.ns =
"3dpts";
100 rvizMarker.scale.x =
rad;
101 rvizMarker.scale.y =
rad;
102 rvizMarker.scale.z =
rad;
104 rvizMarker.type = visualization_msgs::Marker::SPHERE_LIST;
105 rvizMarker.action = visualization_msgs::Marker::ADD;
108 rvizMarker.color.r = 0.0f;
109 rvizMarker.color.g = 1.0f;
110 rvizMarker.color.b = 1.0f;
111 rvizMarker.color.a = 1.0;
114 rvizMarker.color.r = 1.0f;
115 rvizMarker.color.g = 0.0f;
116 rvizMarker.color.b = 1.0f;
117 rvizMarker.color.a = 1.0;
120 rvizMarker.color.r = 1.0f;
121 rvizMarker.color.g = 1.0f;
122 rvizMarker.color.b = 0.0f;
123 rvizMarker.color.a = 1.0;
127 for(
int i=0; i<cloud->points.size(); i++){
128 p.x = cloud->points[i].x;
129 p.y = cloud->points[i].y;
130 p.z = cloud->points[i].z;
131 rvizMarker.points.push_back(p);
135 rvizMarkerPub2_.
publish (rvizMarker);
141 visualization_msgs::Marker rvizMarker;
143 rvizMarker.header.frame_id = frame;
146 rvizMarker.ns =
"arrow";
148 rvizMarker.scale.x = 0.01;
149 rvizMarker.scale.y = 0.01;
150 rvizMarker.scale.z = 0.1;
152 rvizMarker.type = visualization_msgs::Marker::ARROW;
153 rvizMarker.action = visualization_msgs::Marker::ADD;
155 for(
int i=0; i<3; i++){
156 rvizMarker.points.clear();
157 rvizMarker.points.push_back(start);
159 end.x = start.x + mat[0][i];
160 end.y = start.y + mat[1][i];
161 end.z = start.z + mat[2][i];
162 rvizMarker.points.push_back(end);
163 rvizMarker.id += 10*i;
167 rvizMarker.color.r = 1.0f;
168 rvizMarker.color.g = 0.0f;
169 rvizMarker.color.b = 0.0f;
170 rvizMarker.color.a = 1.0;
173 rvizMarker.color.r = 0.0f;
174 rvizMarker.color.g = 1.0f;
175 rvizMarker.color.b = 0.0f;
176 rvizMarker.color.a = 1.0;
179 rvizMarker.color.r = 0.0f;
180 rvizMarker.color.g = 0.0f;
181 rvizMarker.color.b = 1.0f;
182 rvizMarker.color.a = 1.0;
186 rvizMarkerPub2_.
publish (rvizMarker);
194 gm::PoseStamped pose;
196 pose.header.frame_id = cloud.header.frame_id;
199 draw3dPoints(selected_points, cloud.header.frame_id, 1,
id, 0.005);
203 if(isnan(corners_3D[0].
x) || isnan(corners_3D[0].
y) || isnan(corners_3D[0].
z) ||
204 isnan(corners_3D[3].x) || isnan(corners_3D[3].y) || isnan(corners_3D[3].z))
206 if(isnan(corners_3D[1].x) || isnan(corners_3D[1].y) || isnan(corners_3D[1].z) ||
207 isnan(corners_3D[2].x) || isnan(corners_3D[2].y) || isnan(corners_3D[2].z))
223 if(isnan(corners_3D[0].x) || isnan(corners_3D[0].y) || isnan(corners_3D[0].z) ||
224 isnan(corners_3D[1].x) || isnan(corners_3D[1].y) || isnan(corners_3D[1].z))
226 if(isnan(corners_3D[3].x) || isnan(corners_3D[3].y) || isnan(corners_3D[3].z) ||
227 isnan(corners_3D[2].x) || isnan(corners_3D[2].y) || isnan(corners_3D[2].z))
241 ARCloud::Ptr orient_points(
new ARCloud());
242 orient_points->points.push_back(corners_3D[i1]);
243 draw3dPoints(orient_points, cloud.header.frame_id, 3,
id+1000, 0.008);
245 orient_points->clear();
246 orient_points->points.push_back(corners_3D[i2]);
247 draw3dPoints(orient_points, cloud.header.frame_id, 2,
id+2000, 0.008);
251 if(succ < 0)
return -1;
255 if(succ < 0)
return -1;
257 drawArrow(pose.pose.position, mat, cloud.header.frame_id, 1,
id);
278 for (
size_t i=0; i<marker_detector.
markers->size(); i++)
280 vector<cv::Point, Eigen::aligned_allocator<cv::Point> > pixels;
299 if(ori >= 0 && ori < 4){
305 ROS_ERROR(
"FindMarkerBundles: Bad Orientation: %i for ID: %i", ori,
id);
309 pixels.push_back(cv::Point(p.x, p.y));
322 sensor_msgs::ImagePtr image_msg(
new sensor_msgs::Image);
336 image_msg->header.stamp = msg->header.stamp;
337 image_msg->header.frame_id = msg->header.frame_id;
348 IplImage ipl_image = cv_ptr_->image;
363 image_msg->header.stamp, CamToOutput);
373 for (
size_t i=0; i<marker_detector.
markers->size(); i++)
376 int id = (*(marker_detector.
markers))[i].GetId();
395 std::string markerFrame =
"ar_marker_";
396 std::stringstream out;
398 std::string id_string = out.str();
399 markerFrame += id_string;
400 tf::StampedTransform camToMarker (t, image_msg->header.stamp, image_msg->header.frame_id, markerFrame.c_str());
405 rvizMarker_.header.frame_id = image_msg->header.frame_id;
406 rvizMarker_.header.stamp = image_msg->header.stamp;
413 rvizMarker_.type = visualization_msgs::Marker::CUBE;
414 rvizMarker_.action = visualization_msgs::Marker::ADD;
461 ar_track_alvar_msgs::AlvarMarker ar_pose_marker;
464 ar_pose_marker.header.stamp = image_msg->header.stamp;
465 ar_pose_marker.id = id;
472 ROS_ERROR (
"Could not convert from '%s' to 'rgb8'.", image_msg->encoding.c_str ());
479 ROS_INFO(
"AR tracker reconfigured: %s %.2f %.2f %.2f %.2f", config.enabled ?
"ENABLED" :
"DISABLED",
480 config.max_frequency, config.marker_size, config.max_new_marker_error, config.max_track_error);
491 int main(
int argc,
char *argv[])
497 ROS_WARN(
"Command line arguments are deprecated. Consider using ROS parameters and remappings.");
500 std::cout << std::endl;
501 cout <<
"Not enough arguments provided." << endl;
502 cout <<
"Usage: ./individualMarkers <marker size in cm> <max new marker error> <max track error> " 503 <<
"<cam image topic> <cam info topic> <output frame> [ <max frequency> <marker_resolution> <marker_margin>]";
504 std::cout << std::endl;
537 ROS_ERROR(
"Param 'output_frame' has to be set if the output frame is not " 538 "derived from the point cloud message.");
561 arMarkerPub_ = n.
advertise < ar_track_alvar_msgs::AlvarMarkers > (
"ar_pose_marker", 0);
562 rvizMarkerPub_ = n.
advertise < visualization_msgs::Marker > (
"visualization_marker", 0);
563 rvizMarkerPub2_ = n.
advertise < visualization_msgs::Marker > (
"ARmarker_points", 0);
566 dynamic_reconfigure::Server < ar_track_alvar::ParamsConfig > server;
567 dynamic_reconfigure::Server<ar_track_alvar::ParamsConfig>::CallbackType
f;
570 server.setCallback(f);
580 ROS_INFO(
"Subscribing to image topic");
bool output_frame_from_msg
double max_new_marker_error
std::string cam_info_topic
ros::Subscriber cloud_sub_
void publish(const boost::shared_ptr< M > &message) const
int main(int argc, char *argv[])
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())
pcl::PointCloud< ARPoint > ARCloud
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)
image_transport::Subscriber cam_sub_
This file implements a generic marker detector.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ARCloud::Ptr filterCloud(const ARCloud &cloud, const std::vector< cv::Point, Eigen::aligned_allocator< cv::Point > > &pixels)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
int PlaneFitPoseImprovement(int id, const ARCloud &corners_3D, ARCloud::Ptr selected_points, const ARCloud &cloud, Pose &p)
TFSIMD_FORCE_INLINE const tfScalar & y() const
Simple Camera class for calculating distortions, orientation or projections with pre-calibrated camer...
MarkerDetector< MarkerData > marker_detector
tf::TransformBroadcaster * tf_broadcaster
std::vector< M, Eigen::aligned_allocator< M > > * markers
std::string cam_image_topic
void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
MarkerDetector for detecting markers of type M
Pose pose
The current marker Pose.
Duration expectedCycleTime() const
static const Quaternion & getIdentity()
tf::TransformListener * tf_listener
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
geometry_msgs::Point centroid(const ARCloud &points)
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
Pose representation derived from the Rotation class
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.
#define ROS_DEBUG_STREAM(args)
TFSIMD_FORCE_INLINE const tfScalar & z() const
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
void drawArrow(gm::Point start, tf::Matrix3x3 mat, string frame, int color, int id)
ALVAR_EXPORT Point< CvPoint2D64f > PointDouble
The default double point type.
bool getParam(const std::string &key, std::string &s) const
void draw3dPoints(ARCloud::Ptr cloud, string frame, int color, int id, double rad)
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)
pcl::ModelCoefficients coeffs
cv_bridge::CvImagePtr cv_ptr_
void GetMarkerPoses(IplImage *image, ARCloud &cloud)
ar_track_alvar_msgs::AlvarMarkers arPoseMarkers_
ROSCPP_DECL void spinOnce()
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
ros::Publisher rvizMarkerPub_
ros::Publisher arMarkerPub_
ros::Publisher rvizMarkerPub2_
visualization_msgs::Marker rvizMarker_
void configCallback(ar_track_alvar::ParamsConfig &config, uint32_t level)
ar_track_alvar::ARCloud ros_corners_3D
PlaneFitResult fitPlane(ARCloud::ConstPtr cloud)
void getPointCloudCallback(const sensor_msgs::PointCloud2ConstPtr &msg)