#include <map.h>
Public Member Functions | |
bool | addFiducialCallback (fiducial_slam::AddFiducial::Request &req, fiducial_slam::AddFiducial::Response &res) |
void | autoInit (const std::vector< Observation > &obs, const ros::Time &time) |
bool | clearCallback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) |
void | drawLine (const tf2::Vector3 &p0, const tf2::Vector3 &p1) |
void | handleAddFiducial (const std::vector< Observation > &obs) |
bool | loadMap () |
bool | loadMap (std::string filename) |
bool | lookupTransform (const std::string &from, const std::string &to, const ros::Time &time, tf2::Transform &T) const |
Map (ros::NodeHandle &nh) | |
void | publishMap () |
void | publishMarker (Fiducial &fid) |
void | publishMarkers () |
void | publishTf () |
bool | saveMap () |
bool | saveMap (std::string filename) |
void | update () |
void | update (std::vector< Observation > &obs, const ros::Time &time) |
void | updateMap (const std::vector< Observation > &obs, const ros::Time &time, const tf2::Stamped< TransformWithVariance > &cameraPose) |
int | updatePose (std::vector< Observation > &obs, const ros::Time &time, tf2::Stamped< TransformWithVariance > &cameraPose) |
Public Attributes | |
ros::ServiceServer | addSrv |
std::string | baseFrame |
tf2_ros::TransformBroadcaster | broadcaster |
std::string | cameraFrame |
ros::Publisher | cameraPosePub |
ros::ServiceServer | clearSrv |
std::vector< double > | covarianceDiagonal |
std::map< int, Fiducial > | fiducials |
int | fiducialToAdd |
int | frameNum |
double | future_date_transforms |
bool | havePose |
int | initialFrameNum |
bool | isInitializingMap |
std::unique_ptr< tf2_ros::TransformListener > | listener |
std::string | mapFilename |
std::string | mapFrame |
ros::Publisher | mapPub |
ros::Publisher | markerPub |
double | multiErrorThreshold |
std::string | odomFrame |
int | originFid |
bool | overridePublishedCovariance |
geometry_msgs::TransformStamped | poseTf |
bool | publish_6dof_pose |
bool | publishPoseTf |
bool | readOnly |
ros::Publisher | robotPosePub |
tf2_ros::Buffer | tfBuffer |
float | tfPublishInterval |
ros::Time | tfPublishTime |
Map::Map | ( | ros::NodeHandle & | nh | ) |
bool Map::addFiducialCallback | ( | fiducial_slam::AddFiducial::Request & | req, |
fiducial_slam::AddFiducial::Response & | res | ||
) |
void Map::autoInit | ( | const std::vector< Observation > & | obs, |
const ros::Time & | time | ||
) |
bool Map::clearCallback | ( | std_srvs::Empty::Request & | req, |
std_srvs::Empty::Response & | res | ||
) |
void Map::drawLine | ( | const tf2::Vector3 & | p0, |
const tf2::Vector3 & | p1 | ||
) |
void Map::handleAddFiducial | ( | const std::vector< Observation > & | obs | ) |
bool Map::lookupTransform | ( | const std::string & | from, |
const std::string & | to, | ||
const ros::Time & | time, | ||
tf2::Transform & | T | ||
) | const |
void Map::update | ( | std::vector< Observation > & | obs, |
const ros::Time & | time | ||
) |
void Map::updateMap | ( | const std::vector< Observation > & | obs, |
const ros::Time & | time, | ||
const tf2::Stamped< TransformWithVariance > & | cameraPose | ||
) |
int Map::updatePose | ( | std::vector< Observation > & | obs, |
const ros::Time & | time, | ||
tf2::Stamped< TransformWithVariance > & | cameraPose | ||
) |
ros::ServiceServer Map::addSrv |
tf2_ros::TransformBroadcaster Map::broadcaster |
ros::Publisher Map::cameraPosePub |
ros::ServiceServer Map::clearSrv |
std::unique_ptr<tf2_ros::TransformListener> Map::listener |
ros::Publisher Map::mapPub |
ros::Publisher Map::markerPub |
ros::Publisher Map::robotPosePub |
tf2_ros::Buffer Map::tfBuffer |