Classes | |
struct | InvalidGraphLocalizationException |
Typedefs | |
typedef boost::optional < gm::PoseStamped > | MaybePose |
typedef boost::optional < tf::StampedTransform > | MaybeTransform |
typedef std::map< unsigned, tf::Pose > | NodePoseMap |
Functions | |
tf::Pose | absolutePose (const tf::Pose &base, const gm::Pose &offset) |
Adjust a pose given a relative offset. | |
gm::Pose | absolutePose (const gm::Pose &base, const tf::Pose &offset) |
Adjust a pose given a relative offset. | |
btVector3 | barycenter (const sm::LaserScan &scan) |
btVector3 | barycenter (const sensor_msgs::LaserScan &scan) |
Return the barycenter of a laser scan (in the laser frame). | |
gm::Point | barycenter (const sensor_msgs::PointCloud &cloud) |
Return the barycenter of the cloud, in the same frame as the cloud itself. | |
template<class T > | |
std::string | concatenate (const std::string &s, const T &x) |
template<class Key , class Container > | |
bool | contains (const Container &container, const Key &key) |
void | doNothing (const ros::TimerEvent &e) |
ros::Duration | duration (const double rate) |
double | euclideanDistance (const gm::Point &p1, const gm::Point &p2) |
Return euclidean distance between two 3d-positions. | |
NodePoseMap | fromMsg (const NodePoses &poses) |
template<class P > | |
P | getParam (const ros::NodeHandle &nh, const string &name, const P &default_val) |
Get a parameter, with default values. | |
template<class P > | |
P | getParam (const ros::NodeHandle &nh, const string &name) |
Get a parameter. | |
MaybeTransform | getTransform (const tf::TransformListener &tf, const string &target_frame, const string &source_frame, const ros::Time &t, const ros::Duration &timeout) |
MaybeTransform | getTransform (const tf::Transformer &tf, const string &target_frame, const ros::Time &target_time, const string &source_frame, const ros::Time &source_time, const string &fixed_frame, const ros::Duration &timeout) |
unsigned | index (const unsigned i, const unsigned j) |
template<class K , class V , class C , class A > | |
const V & | keyValue (const std::map< K, V, C, A > &m, const K &key) |
double | length (const gm::Point &p) |
double | length (const btVector3 &v) |
Edge | makeEdge (unsigned e, unsigned from, unsigned to, const PoseWithPrecision &constraint) |
Node | makeNode (unsigned n) |
gm::Point | makePoint (const double x, const double y, const double z=0.0) |
Construct a geometry_msgs Point. | |
tf::Pose | makePose (double x, double y, double theta) |
Construct a tf::Pose from x,y,theta. | |
gm::Pose2D | makePose2D (double x, double y, double theta=0.0) |
Construct a pose2d. | |
boost::array< double, 36 > | makePrecisionMatrix (const double x, const double y, const double xy, const double theta) |
Create a precision matrix given the precisions of x, y, and theta, and the joint precision of x-y. | |
string | nodeFrame (const unsigned n) |
tf::Pose | optimizedPose (const gm::PoseStamped &loc, const std::map< unsigned, tf::Pose > &opt_poses) |
Get the optimized current pose given localization and optimized graph poses. | |
gm::Pose2D | projectToPose2D (const tf::Transform &pose) |
gm::Pose2D | projectToPose2D (const tf::Pose &pose) |
Project tf pose to pose2d. | |
gm::Pose2D | projectToPose2D (const gm::Pose &pose) |
Project Pose to Pose2D. | |
unsigned | refNode (const geometry_msgs::PoseStamped &p) |
tf::Pose | relativePose (const tf::Pose &pose1, const tf::Pose &pose2) |
template<class T > | |
std::set< T > | sampleSubset (const std::set< T > &s, const int n) |
Sample a subset of set s of size n. | |
template<class P > | |
P | searchParam (const ros::NodeHandle &nh, const string &name, const P &default_val) |
Search for a parameter in a namespace and its ancestors with default. | |
template<class P > | |
P | searchParam (const ros::NodeHandle &nh, const string &name) |
Search for a parameter in a namespace and its ancestors. | |
template<class F , class G > | |
ros::Timer | timerFromRate (const ros::NodeHandle &nh, const double rate, const F &fn, const G &obj_ptr) |
template<class MsgPtr > | |
ros::Time | timestamp (const MsgPtr &data) |
Get the timestamp given a shared pointer to a ROS message. | |
NodePoses::ConstPtr | toMsg (const NodePoseMap &poses) |
gm::Point | toPoint (const btVector3 &p) |
btVector3 | toPoint (const gm::Point &p) |
tf::Pose | toPose (const gm::Pose2D &p) |
Make a pose from a pose2d. | |
tf::Pose | toPose (const gm::Pose &p) |
gm::Pose | toPose (const tf::Pose &p) |
string | toString (const tf::Pose &pose) |
std::string | toString (const btQuaternion &q) |
std::string | toString (const btVector3 &v) |
std::string | toString (const btTransform &t) |
template<class T > | |
std::string | toString (const std::vector< T > &v) |
template<class T > | |
std::string | toString (const std::set< T > &set) |
string | toString (const gm::Pose &pose) |
string | toString (const gm::Point &p) |
string | toString (const gm::Pose2D &pose) |
string | toString2D (const tf::Pose &pose) |
string | toString2D (const gm::Pose &pose) |
tf::Transform | transformBetween (const tf::Pose &pose1, const tf::Pose &pose2) |
Return the transform that sends pose1 to pose2. | |
gm::Point | transformPoint (const tf::Transform &trans, const gm::Point &point) |
Apply Bullet transformation to a ROS point. | |
gm::Point32 | transformPoint (const tf::Transform &trans, const gm::Point32 &point) |
Apply Bullet transformation to a ROS point. | |
gm::Pose | transformPose (const tf::Transform &trans, const gm::Pose &pose) |
Apply Bullet transformation to a ROS pose. | |
MaybePose | waitAndTransform (const tf::TransformListener &tf, const gm::PoseStamped &pose_in, const string &target_frame, const ros::Time &target_time, const string &fixed_frame, const ros::Duration &timeout) |
typedef boost::optional<gm::PoseStamped> graph_mapping_utils::MaybePose |
typedef boost::optional<tf::StampedTransform> graph_mapping_utils::MaybeTransform |
typedef std::map<unsigned, tf::Pose> graph_mapping_utils::NodePoseMap |
tf::Pose graph_mapping_utils::absolutePose | ( | const tf::Pose & | base, | |
const gm::Pose & | offset | |||
) | [inline] |
Adjust a pose given a relative offset.
Definition at line 191 of file geometry.h.
gm::Pose graph_mapping_utils::absolutePose | ( | const gm::Pose & | base, | |
const tf::Pose & | offset | |||
) | [inline] |
Adjust a pose given a relative offset.
Definition at line 184 of file geometry.h.
btVector3 graph_mapping_utils::barycenter | ( | const sm::LaserScan & | scan | ) |
Definition at line 102 of file geometry.cpp.
btVector3 graph_mapping_utils::barycenter | ( | const sensor_msgs::LaserScan & | scan | ) |
Return the barycenter of a laser scan (in the laser frame).
gm::Point graph_mapping_utils::barycenter | ( | const sensor_msgs::PointCloud & | cloud | ) |
Return the barycenter of the cloud, in the same frame as the cloud itself.
Definition at line 83 of file geometry.cpp.
std::string graph_mapping_utils::concatenate | ( | const std::string & | s, | |
const T & | x | |||
) | [inline] |
Definition at line 72 of file to_string.h.
bool graph_mapping_utils::contains | ( | const Container & | container, | |
const Key & | key | |||
) | [inline] |
void graph_mapping_utils::doNothing | ( | const ros::TimerEvent & | e | ) | [inline] |
ros::Duration graph_mapping_utils::duration | ( | const double | rate | ) | [inline] |
double graph_mapping_utils::euclideanDistance | ( | const gm::Point & | p1, | |
const gm::Point & | p2 | |||
) | [inline] |
Return euclidean distance between two 3d-positions.
Definition at line 205 of file geometry.h.
NodePoseMap graph_mapping_utils::fromMsg | ( | const NodePoses & | poses | ) |
P graph_mapping_utils::getParam | ( | const ros::NodeHandle & | nh, | |
const string & | name, | |||
const P & | default_val | |||
) | [inline] |
P graph_mapping_utils::getParam | ( | const ros::NodeHandle & | nh, | |
const string & | name | |||
) | [inline] |
MaybeTransform graph_mapping_utils::getTransform | ( | const tf::TransformListener & | tf, | |
const string & | target_frame, | |||
const string & | source_frame, | |||
const ros::Time & | t, | |||
const ros::Duration & | timeout | |||
) | [inline] |
MaybeTransform graph_mapping_utils::getTransform | ( | const tf::Transformer & | tf, | |
const string & | target_frame, | |||
const ros::Time & | target_time, | |||
const string & | source_frame, | |||
const ros::Time & | source_time, | |||
const string & | fixed_frame, | |||
const ros::Duration & | timeout | |||
) | [inline] |
unsigned graph_mapping_utils::index | ( | const unsigned | i, | |
const unsigned | j | |||
) | [inline] |
const V& graph_mapping_utils::keyValue | ( | const std::map< K, V, C, A > & | m, | |
const K & | key | |||
) | [inline] |
double graph_mapping_utils::length | ( | const gm::Point & | p | ) | [inline] |
Definition at line 149 of file geometry.h.
double graph_mapping_utils::length | ( | const btVector3 & | v | ) | [inline] |
Definition at line 143 of file geometry.h.
Edge graph_mapping_utils::makeEdge | ( | unsigned | e, | |
unsigned | from, | |||
unsigned | to, | |||
const PoseWithPrecision & | constraint | |||
) | [inline] |
gm::Point graph_mapping_utils::makePoint | ( | const double | x, | |
const double | y, | |||
const double | z = 0.0 | |||
) | [inline] |
Construct a geometry_msgs Point.
Definition at line 172 of file geometry.h.
tf::Pose graph_mapping_utils::makePose | ( | double | x, | |
double | y, | |||
double | theta | |||
) |
Construct a tf::Pose from x,y,theta.
Definition at line 77 of file geometry.cpp.
gm::Pose2D graph_mapping_utils::makePose2D | ( | double | x, | |
double | y, | |||
double | theta = 0.0 | |||
) |
Construct a pose2d.
Definition at line 68 of file geometry.cpp.
boost::array<double, 36> graph_mapping_utils::makePrecisionMatrix | ( | const double | x, | |
const double | y, | |||
const double | xy, | |||
const double | theta | |||
) | [inline] |
string graph_mapping_utils::nodeFrame | ( | const unsigned | n | ) | [inline] |
tf::Pose graph_mapping_utils::optimizedPose | ( | const gm::PoseStamped & | loc, | |
const std::map< unsigned, tf::Pose > & | opt_poses | |||
) | [inline] |
gm::Pose2D graph_mapping_utils::projectToPose2D | ( | const tf::Transform & | pose | ) |
Definition at line 48 of file geometry.cpp.
gm::Pose2D graph_mapping_utils::projectToPose2D | ( | const tf::Pose & | pose | ) |
Project tf pose to pose2d.
gm::Pose2D graph_mapping_utils::projectToPose2D | ( | const gm::Pose & | pose | ) |
Project Pose to Pose2D.
Definition at line 57 of file geometry.cpp.
unsigned graph_mapping_utils::refNode | ( | const geometry_msgs::PoseStamped & | p | ) | [inline] |
A | localization wrt the graph, which is represented as a pose stamped where the frame_id looks like 'node24' |
Extracted | node id corresponding to the frame |
InvalidGraphLocalizationException | if frame_id isn't of the above form |
tf::Pose graph_mapping_utils::relativePose | ( | const tf::Pose & | pose1, | |
const tf::Pose & | pose2 | |||
) | [inline] |
pose1 and pose2 are poses specified in some reference frame. This function returns the representation of pose1 in the frame at pose2.
Definition at line 58 of file geometry.h.
std::set<T> graph_mapping_utils::sampleSubset | ( | const std::set< T > & | s, | |
const int | n | |||
) | [inline] |
P graph_mapping_utils::searchParam | ( | const ros::NodeHandle & | nh, | |
const string & | name, | |||
const P & | default_val | |||
) | [inline] |
P graph_mapping_utils::searchParam | ( | const ros::NodeHandle & | nh, | |
const string & | name | |||
) | [inline] |
ros::Timer graph_mapping_utils::timerFromRate | ( | const ros::NodeHandle & | nh, | |
const double | rate, | |||
const F & | fn, | |||
const G & | obj_ptr | |||
) | [inline] |
ros::Time graph_mapping_utils::timestamp | ( | const MsgPtr & | data | ) | [inline] |
NodePoses::ConstPtr graph_mapping_utils::toMsg | ( | const NodePoseMap & | poses | ) |
gm::Point graph_mapping_utils::toPoint | ( | const btVector3 & | p | ) | [inline] |
Definition at line 116 of file geometry.h.
btVector3 graph_mapping_utils::toPoint | ( | const gm::Point & | p | ) | [inline] |
Definition at line 110 of file geometry.h.
tf::Pose graph_mapping_utils::toPose | ( | const gm::Pose2D & | p | ) |
Make a pose from a pose2d.
Definition at line 122 of file geometry.cpp.
tf::Pose graph_mapping_utils::toPose | ( | const gm::Pose & | p | ) | [inline] |
Definition at line 134 of file geometry.h.
gm::Pose graph_mapping_utils::toPose | ( | const tf::Pose & | p | ) | [inline] |
Definition at line 126 of file geometry.h.
string graph_mapping_utils::toString | ( | const tf::Pose & | pose | ) |
Definition at line 88 of file to_string.cpp.
string graph_mapping_utils::toString | ( | const btQuaternion & | q | ) |
Definition at line 81 of file to_string.cpp.
string graph_mapping_utils::toString | ( | const btVector3 & | v | ) |
Definition at line 76 of file to_string.cpp.
std::string graph_mapping_utils::toString | ( | const btTransform & | t | ) |
std::string graph_mapping_utils::toString | ( | const std::vector< T > & | v | ) | [inline] |
Definition at line 86 of file to_string.h.
std::string graph_mapping_utils::toString | ( | const std::set< T > & | set | ) | [inline] |
Definition at line 79 of file to_string.h.
string graph_mapping_utils::toString | ( | const gm::Pose & | pose | ) |
Definition at line 50 of file to_string.cpp.
string graph_mapping_utils::toString | ( | const gm::Point & | p | ) |
Definition at line 57 of file to_string.cpp.
string graph_mapping_utils::toString | ( | const gm::Pose2D & | pose | ) |
Definition at line 45 of file to_string.cpp.
string graph_mapping_utils::toString2D | ( | const tf::Pose & | pose | ) |
Definition at line 71 of file to_string.cpp.
string graph_mapping_utils::toString2D | ( | const gm::Pose & | pose | ) |
Definition at line 63 of file to_string.cpp.
tf::Transform graph_mapping_utils::transformBetween | ( | const tf::Pose & | pose1, | |
const tf::Pose & | pose2 | |||
) | [inline] |
Return the transform that sends pose1 to pose2.
Definition at line 65 of file geometry.h.
gm::Point graph_mapping_utils::transformPoint | ( | const tf::Transform & | trans, | |
const gm::Point & | point | |||
) | [inline] |
Apply Bullet transformation to a ROS point.
Definition at line 86 of file geometry.h.
gm::Point32 graph_mapping_utils::transformPoint | ( | const tf::Transform & | trans, | |
const gm::Point32 & | point | |||
) | [inline] |
Apply Bullet transformation to a ROS point.
Definition at line 72 of file geometry.h.
gm::Pose graph_mapping_utils::transformPose | ( | const tf::Transform & | trans, | |
const gm::Pose & | pose | |||
) | [inline] |
Apply Bullet transformation to a ROS pose.
Definition at line 99 of file geometry.h.