#include <pose.h>
| Classes | |
| struct | Params | 
| Public Member Functions | |
| void | advertisePoseMsg (ros::NodeHandle nh) | 
| Advertises the pose message. | |
| void | advertisePoseMsg (ros::NodeHandle nh) | 
| tf::Transform | correctOdom (tf::Transform current_odom, tf::Transform last_graph_pose, tf::Transform last_graph_odom) | 
| Correct the current odometry with the information of the graph. | |
| tf::Transform | correctOdom (tf::Transform current_odom, tf::Transform last_graph_pose, tf::Transform last_graph_odom) | 
| Params | params () const | 
| Params | params () const | 
| Pose () | |
| Pose () | |
| Class constructor. | |
| void | publish (nav_msgs::Odometry odom_msg, tf::Transform pose, bool publish_graph) | 
| void | publish (nav_msgs::Odometry odom_msg, tf::Transform pose, bool publish_graph=false) | 
| Publish pose. | |
| void | setParams (const Params ¶ms) | 
| void | setParams (const Params ¶ms) | 
| Private Attributes | |
| ros::Publisher | graph_pub_ | 
| Params | params_ | 
| ros::Publisher | pose_pub_ | 
Definition at line 18 of file common/pose.h.
| slam::Pose::Pose | ( | ) | 
| slam::Pose::Pose | ( | ) | 
| void slam::Pose::advertisePoseMsg | ( | ros::NodeHandle | nh | ) | 
Advertises the pose message.
| Node | handle where pose will be advertised. | 
Definition at line 12 of file common/pose.cpp.
| void slam::Pose::advertisePoseMsg | ( | ros::NodeHandle | nh | ) | 
| tf::Transform slam::Pose::correctOdom | ( | tf::Transform | current_odom, | 
| tf::Transform | last_graph_pose, | ||
| tf::Transform | last_graph_odom | ||
| ) | 
Correct the current odometry with the information of the graph.
| Current | odometry. | 
| Last | graph pose. | 
| The | corresponding original odometry for the last graph pose. | 
Definition at line 25 of file common/pose.cpp.
| tf::Transform slam::Pose::correctOdom | ( | tf::Transform | current_odom, | 
| tf::Transform | last_graph_pose, | ||
| tf::Transform | last_graph_odom | ||
| ) | 
| Params slam::Pose::params | ( | ) | const  [inline] | 
Definition at line 49 of file slam/pose.h.
| Params slam::Pose::params | ( | ) | const  [inline] | 
Definition at line 49 of file common/pose.h.
| void slam::Pose::publish | ( | nav_msgs::Odometry | odom_msg, | 
| tf::Transform | pose, | ||
| bool | publish_graph = false | ||
| ) | 
Publish pose.
| original | odometry message. | 
| Corrected | odometry to be published. | 
| true | to publish the graph pose. | 
Definition at line 42 of file common/pose.cpp.
| void slam::Pose::publish | ( | nav_msgs::Odometry | odom_msg, | 
| tf::Transform | pose, | ||
| bool | publish_graph | ||
| ) | 
| void slam::Pose::setParams | ( | const Params & | params | ) |  [inline] | 
| params | new parameters | 
Definition at line 41 of file slam/pose.h.
| void slam::Pose::setParams | ( | const Params & | params | ) |  [inline] | 
| params | new parameters | 
Definition at line 41 of file common/pose.h.
| ros::Publisher slam::Pose::graph_pub_  [private] | 
Definition at line 67 of file common/pose.h.
| Params slam::Pose::params_  [private] | 
Definition at line 63 of file common/pose.h.
| ros::Publisher slam::Pose::pose_pub_  [private] | 
Definition at line 66 of file common/pose.h.