40 #include <visualization_msgs/Marker.h> 42 #include <opencv2/aruco.hpp> 43 #include <opencv2/calib3d.hpp> 44 #include <opencv2/highgui.hpp> 46 #include <fiducial_msgs/FiducialMapEntry.h> 47 #include <fiducial_msgs/FiducialMapEntryArray.h> 52 #include <geometry_msgs/PoseWithCovarianceStamped.h> 56 #include <std_srvs/Empty.h> 57 #include <fiducial_slam/AddFiducial.h> 96 std::unique_ptr<tf2_ros::TransformListener>
listener;
105 bool clearCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res);
106 bool addFiducialCallback(fiducial_slam::AddFiducial::Request &req,
107 fiducial_slam::AddFiducial::Response &res);
139 void autoInit(
const std::vector<Observation> &obs,
const ros::Time &time);
140 int updatePose(std::vector<Observation> &obs,
const ros::Time &time,
142 void updateMap(
const std::vector<Observation> &obs,
const ros::Time &time,
144 void handleAddFiducial(
const std::vector<Observation> &obs);
147 bool loadMap(std::string filename);
149 bool saveMap(std::string filename);
154 void publishMarkers();
155 void drawLine(
const tf2::Vector3 &p0,
const tf2::Vector3 &p1);
157 bool lookupTransform(
const std::string &from,
const std::string &to,
const ros::Time &time,
ros::Publisher cameraPosePub
double future_date_transforms
tf2::Stamped< TransformWithVariance > T_fidCam
ros::ServiceServer clearSrv
std::vector< double > covarianceDiagonal
std::unique_ptr< tf2_ros::TransformListener > listener
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
geometry_msgs::TransformStamped poseTf
ros::ServiceServer addSrv
std::map< int, Fiducial > fiducials
ros::Publisher robotPosePub
bool overridePublishedCovariance
tf2_ros::TransformBroadcaster broadcaster
tf2::Stamped< TransformWithVariance > pose
double multiErrorThreshold
tf2::Stamped< TransformWithVariance > T_camFid