Classes | Public Member Functions | Private Attributes
slam::Pose Class Reference

#include <pose.h>

List of all members.

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 &params)
void setParams (const Params &params)

Private Attributes

ros::Publisher graph_pub_
Params params_
ros::Publisher pose_pub_

Detailed Description

Definition at line 18 of file common/pose.h.


Constructor & Destructor Documentation

Class constructor.

Returns:

Definition at line 6 of file common/pose.cpp.


Member Function Documentation

Advertises the pose message.

Returns:
Parameters:
Nodehandle where pose will be advertised.

Definition at line 12 of file common/pose.cpp.

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.

Returns:
The corrected odometry.
Parameters:
Currentodometry.
Lastgraph pose.
Thecorresponding 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]
Returns:
current parameters

Definition at line 49 of file slam/pose.h.

Params slam::Pose::params ( ) const [inline]
Returns:
current parameters

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.

Returns:
Parameters:
originalodometry message.
Correctedodometry to be published.
trueto 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]
Parameters:
paramsnew parameters

Definition at line 41 of file slam/pose.h.

void slam::Pose::setParams ( const Params params) [inline]
Parameters:
paramsnew parameters

Definition at line 41 of file common/pose.h.


Member Data Documentation

Definition at line 67 of file common/pose.h.

Definition at line 63 of file common/pose.h.

Definition at line 66 of file common/pose.h.


The documentation for this class was generated from the following files:


stereo_slam
Author(s): Pep Lluis Negre
autogenerated on Thu Aug 27 2015 15:24:22