44 #include <ar_track_alvar_msgs/AlvarMarker.h> 45 #include <ar_track_alvar_msgs/AlvarMarkers.h> 50 using namespace alvar;
54 #define VISIBLE_MARKER 2 55 #define GHOST_MARKER 3 82 void getCapCallback (
const sensor_msgs::ImageConstPtr & image_msg);
83 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);
91 multi_marker_bundles[i]->Update(marker_detector.
markers, cam, bundlePoses[i]);
95 if ((multi_marker_bundles[i]->SetTrackMarkers(marker_detector, cam, bundlePoses[i], image) > 0))
96 multi_marker_bundles[i]->Update(marker_detector.
markers, cam, bundlePoses[i]);
104 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){
105 double px,py,pz,qx,qy,qz,qw;
126 std::string markerFrame =
"ar_marker_";
127 std::stringstream out;
129 std::string id_string = out.str();
130 markerFrame += id_string;
131 tf::StampedTransform camToMarker (t, image_msg->header.stamp, image_msg->header.frame_id, markerFrame.c_str());
137 rvizMarker->header.frame_id = image_msg->header.frame_id;
138 rvizMarker->header.stamp = image_msg->header.stamp;
146 rvizMarker->ns =
"main_shapes";
148 rvizMarker->ns =
"basic_shapes";
151 rvizMarker->type = visualization_msgs::Marker::CUBE;
152 rvizMarker->action = visualization_msgs::Marker::ADD;
156 rvizMarker->color.r = 1.0f;
157 rvizMarker->color.g = 0.0f;
158 rvizMarker->color.b = 0.0f;
159 rvizMarker->color.a = 1.0;
162 rvizMarker->color.r = 0.0f;
163 rvizMarker->color.g = 1.0f;
164 rvizMarker->color.b = 0.0f;
165 rvizMarker->color.a = 0.7;
168 rvizMarker->color.r = 0.0f;
169 rvizMarker->color.g = 0.0f;
170 rvizMarker->color.b = 1.0f;
171 rvizMarker->color.a = 0.5;
184 ar_pose_marker->header.stamp = image_msg->header.stamp;
185 ar_pose_marker->id = id;
188 ar_pose_marker = NULL;
208 visualization_msgs::Marker rvizMarker;
209 ar_track_alvar_msgs::AlvarMarker ar_pose_marker;
221 IplImage ipl_image = cv_ptr_->image;
228 for (
size_t i=0; i<marker_detector.
markers->size(); i++)
230 int id = (*(marker_detector.
markers))[i].GetId();
246 bool should_draw =
true;
248 if(
id ==
master_id[i]) should_draw =
false;
253 rvizMarkerPub_.
publish (rvizMarker);
263 rvizMarkerPub_.
publish (rvizMarker);
272 ROS_ERROR (
"Could not convert from '%s' to 'rgb8'.", image_msg->encoding.c_str ());
279 int main(
int argc,
char *argv[])
285 std::cout << std::endl;
286 cout <<
"Not enough arguments provided." << endl;
287 cout <<
"Usage: ./findMarkerBundles <marker size in cm> <max new marker error> <max track error> <cam image topic> <cam info topic> <output frame> <list of bundle XML files...>" << endl;
288 std::cout << std::endl;
299 int n_args_before_list = 7;
311 bundlePoses[i].
Reset();
314 vector<int> id_vector = loadHelper.
getIndices();
321 cout<<
"Cannot load file "<< argv[i + n_args_before_list] << endl;
330 arMarkerPub_ = n.
advertise < ar_track_alvar_msgs::AlvarMarkers > (
"ar_pose_marker", 0);
331 rvizMarkerPub_ = n.
advertise < visualization_msgs::Marker > (
"visualization_marker", 0);
338 ROS_INFO (
"Subscribing to image topic");
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
std::string cam_info_topic
void publish(const boost::shared_ptr< M > &message) const
void getCapCallback(const sensor_msgs::ImageConstPtr &image_msg)
void SetMarkerSize(double _edge_length=1, int _res=5, double _margin=2)
This file implements a generic marker detector.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void GetMultiMarkerPoses(IplImage *image)
Base class for using MultiMarker.
int DetectAdditional(IplImage *image, Camera *cam, bool visualize=false, double max_track_error=0.2)
Simple Camera class for calculating distortions, orientation or projections with pre-calibrated camer...
MarkerDetector< MarkerData > marker_detector
ROSCPP_DECL void spin(Spinner &spinner)
std::vector< M, Eigen::aligned_allocator< M > > * markers
std::string cam_image_topic
ar_track_alvar_msgs::AlvarMarkers arPoseMarkers_
MarkerDetector for detecting markers of type M
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)
static const Quaternion & getIdentity()
double max_new_marker_error
std::vector< int > * bundle_indices
Multi marker that uses bundle adjustment to refine the 3D positions of the markers (point cloud)...
MultiMarkerBundle ** multi_marker_bundles
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
Pose representation derived from the Rotation class
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
tf::TransformListener * tf_listener
ros::Publisher arMarkerPub_
tf::TransformBroadcaster * tf_broadcaster
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
This file implements a initialization algorithm to create a multi-marker field configuration.
bool Load(const char *fname, FILE_FORMAT format=FILE_FORMAT_DEFAULT)
Loads multi marker configuration from a text file.
ros::Publisher rvizMarkerPub_
int main(int argc, char *argv[])
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
image_transport::Subscriber cam_sub_
This file implements an algorithm to create a multi-marker field configuration.
cv_bridge::CvImagePtr cv_ptr_
ROSCPP_DECL void spinOnce()
std::vector< int > getIndices()