odometry.hpp
Go to the documentation of this file.
1 
9 /*****************************************************************************
10 ** Ifdefs
11 *****************************************************************************/
12 
13 #ifndef KOBUKI_NODE_ODOMETRY_HPP_
14 #define KOBUKI_NODE_ODOMETRY_HPP_
15 
16 /*****************************************************************************
17 ** Includes
18 *****************************************************************************/
19 
20 #include <string>
21 #include <geometry_msgs/Twist.h>
22 #include <nav_msgs/Odometry.h>
25 
26 /*****************************************************************************
27 ** Namespaces
28 *****************************************************************************/
29 
30 namespace kobuki {
31 
32 /*****************************************************************************
33 ** Interfaces
34 *****************************************************************************/
35 
39 class Odometry {
40 public:
41  Odometry();
42  void init(ros::NodeHandle& nh, const std::string& name);
43  bool commandTimeout() const;
44  void update(const ecl::LegacyPose2D<double> &pose_update, ecl::linear_algebra::Vector3d &pose_update_rates,
45  double imu_heading, double imu_angular_velocity);
46  void resetOdometry() { pose.setIdentity(); }
47  const ros::Duration& timeout() const { return cmd_vel_timeout; }
49 
50 private:
51  geometry_msgs::TransformStamped odom_trans;
53  std::string odom_frame;
54  std::string base_frame;
57  bool publish_tf;
61 
62  void publishTransform(const geometry_msgs::Quaternion &odom_quat);
63  void publishOdometry(const geometry_msgs::Quaternion &odom_quat, const ecl::linear_algebra::Vector3d &pose_update_rates);
64 };
65 
66 } // namespace kobuki
67 
68 #endif /* KOBUKI_NODE_ODOMETRY_HPP_ */
void resetOdometry()
Definition: odometry.hpp:46
std::string base_frame
Definition: odometry.hpp:54
void resetTimeout()
Definition: odometry.hpp:48
void publishTransform(const geometry_msgs::Quaternion &odom_quat)
Definition: odometry.cpp:110
void init(ros::NodeHandle &nh, const std::string &name)
Definition: odometry.cpp:33
const ros::Duration & timeout() const
Definition: odometry.hpp:47
Odometry for the kobuki node.
Definition: odometry.hpp:39
std::string odom_frame
Definition: odometry.hpp:53
void update(const ecl::LegacyPose2D< double > &pose_update, ecl::linear_algebra::Vector3d &pose_update_rates, double imu_heading, double imu_angular_velocity)
Definition: odometry.cpp:87
tf::TransformBroadcaster odom_broadcaster
Definition: odometry.hpp:59
ros::Duration cmd_vel_timeout
Definition: odometry.hpp:55
geometry_msgs::TransformStamped odom_trans
Definition: odometry.hpp:51
bool commandTimeout() const
Definition: odometry.cpp:79
ros::Publisher odom_publisher
Definition: odometry.hpp:60
ros::Time last_cmd_time
Definition: odometry.hpp:56
bool use_imu_heading
Definition: odometry.hpp:58
static Time now()
void publishOdometry(const geometry_msgs::Quaternion &odom_quat, const ecl::linear_algebra::Vector3d &pose_update_rates)
Definition: odometry.cpp:123
ecl::LegacyPose2D< double > pose
Definition: odometry.hpp:52


kobuki_node
Author(s): Daniel Stonier, Younghun Ju, Jorge Santos Simon
autogenerated on Mon Jun 10 2019 13:45:13