Odometry for the kobuki node. More...
#include <odometry.hpp>
Public Member Functions | |
bool | commandTimeout () const |
void | init (ros::NodeHandle &nh, const std::string &name) |
Odometry () | |
void | resetOdometry () |
void | resetTimeout () |
const ros::Duration & | timeout () const |
void | update (const ecl::LegacyPose2D< double > &pose_update, ecl::linear_algebra::Vector3d &pose_update_rates, double imu_heading, double imu_angular_velocity) |
Private Member Functions | |
void | publishOdometry (const geometry_msgs::Quaternion &odom_quat, const ecl::linear_algebra::Vector3d &pose_update_rates) |
void | publishTransform (const geometry_msgs::Quaternion &odom_quat) |
Private Attributes | |
std::string | base_frame |
ros::Duration | cmd_vel_timeout |
ros::Time | last_cmd_time |
tf::TransformBroadcaster | odom_broadcaster |
std::string | odom_frame |
ros::Publisher | odom_publisher |
geometry_msgs::TransformStamped | odom_trans |
ecl::LegacyPose2D< double > | pose |
bool | publish_tf |
bool | use_imu_heading |
Odometry for the kobuki node.
Definition at line 39 of file odometry.hpp.
kobuki::Odometry::Odometry | ( | ) |
Definition at line 26 of file odometry.cpp.
bool kobuki::Odometry::commandTimeout | ( | ) | const |
Definition at line 79 of file odometry.cpp.
void kobuki::Odometry::init | ( | ros::NodeHandle & | nh, |
const std::string & | name | ||
) |
Definition at line 33 of file odometry.cpp.
|
private |
Definition at line 123 of file odometry.cpp.
|
private |
Definition at line 110 of file odometry.cpp.
|
inline |
Definition at line 46 of file odometry.hpp.
|
inline |
Definition at line 48 of file odometry.hpp.
|
inline |
Definition at line 47 of file odometry.hpp.
void kobuki::Odometry::update | ( | const ecl::LegacyPose2D< double > & | pose_update, |
ecl::linear_algebra::Vector3d & | pose_update_rates, | ||
double | imu_heading, | ||
double | imu_angular_velocity | ||
) |
Definition at line 87 of file odometry.cpp.
|
private |
Definition at line 54 of file odometry.hpp.
|
private |
Definition at line 55 of file odometry.hpp.
|
private |
Definition at line 56 of file odometry.hpp.
|
private |
Definition at line 59 of file odometry.hpp.
|
private |
Definition at line 53 of file odometry.hpp.
|
private |
Definition at line 60 of file odometry.hpp.
|
private |
Definition at line 51 of file odometry.hpp.
|
private |
Definition at line 52 of file odometry.hpp.
|
private |
Definition at line 57 of file odometry.hpp.
|
private |
Definition at line 58 of file odometry.hpp.