Go to the documentation of this file.00001
00010
00011
00012
00013
00014 #include "../../include/kobuki_node/odometry.hpp"
00015
00016
00017
00018
00019
00020 namespace kobuki {
00021
00022
00023
00024
00025
00026 Odometry::Odometry () :
00027 odom_frame("odom"),
00028 base_frame("base_footprint"),
00029 publish_tf(false)
00030 {};
00031
00032 void Odometry::init(ros::NodeHandle& nh, const std::string& name) {
00033 double timeout;
00034 nh.param("cmd_vel_timeout", timeout, 0.6);
00035 cmd_vel_timeout.fromSec(timeout);
00036 ROS_INFO_STREAM("Kobuki : Velocity commands timeout: " << cmd_vel_timeout << " seconds [" << name << "].");
00037
00038 if (!nh.getParam("odom_frame", odom_frame)) {
00039 ROS_WARN_STREAM("Kobuki : no param server setting for odom_frame, using default [" << odom_frame << "][" << name << "].");
00040 } else {
00041 ROS_INFO_STREAM("Kobuki : using odom_frame [" << odom_frame << "][" << name << "].");
00042 }
00043
00044 if (!nh.getParam("base_frame", base_frame)) {
00045 ROS_WARN_STREAM("Kobuki : no param server setting for base_frame, using default [" << base_frame << "][" << name << "].");
00046 } else {
00047 ROS_INFO_STREAM("Kobuki : using base_frame [" << base_frame << "][" << name << "].");
00048 }
00049
00050 if (!nh.getParam("publish_tf", publish_tf)) {
00051 ROS_WARN_STREAM("Kobuki : no param server setting for publish_tf, using default [" << publish_tf << "][" << name << "].");
00052 } else {
00053 if ( publish_tf ) {
00054 ROS_INFO_STREAM("Kobuki : publishing transforms [" << name << "].");
00055 } else {
00056 ROS_INFO_STREAM("Kobuki : not publishing transforms (see robot_pose_ekf) [" << name << "].");
00057 }
00058 }
00059
00060 odom_trans.header.frame_id = odom_frame;
00061 odom_trans.child_frame_id = base_frame;
00062
00063 pose.setIdentity();
00064
00065 odom_publisher = nh.advertise<nav_msgs::Odometry>("odom", 50);
00066 }
00067
00068 bool Odometry::commandTimeout() const {
00069 if ( (!last_cmd_time.isZero()) && ((ros::Time::now() - last_cmd_time) > cmd_vel_timeout) ) {
00070 return true;
00071 } else {
00072 return false;
00073 }
00074 }
00075
00076 void Odometry::update(const ecl::Pose2D<double> &pose_update, ecl::linear_algebra::Vector3d &pose_update_rates) {
00077 pose *= pose_update;
00078
00079
00080 geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(pose.heading());
00081
00082 if ( ros::ok() ) {
00083 publishTransform(odom_quat);
00084 publishOdometry(odom_quat, pose_update_rates);
00085 }
00086 }
00087
00088
00089
00090
00091
00092 void Odometry::publishTransform(const geometry_msgs::Quaternion &odom_quat)
00093 {
00094 if (publish_tf == false)
00095 return;
00096
00097 odom_trans.header.stamp = ros::Time::now();
00098 odom_trans.transform.translation.x = pose.x();
00099 odom_trans.transform.translation.y = pose.y();
00100 odom_trans.transform.translation.z = 0.0;
00101 odom_trans.transform.rotation = odom_quat;
00102 odom_broadcaster.sendTransform(odom_trans);
00103 }
00104
00105 void Odometry::publishOdometry(const geometry_msgs::Quaternion &odom_quat,
00106 const ecl::linear_algebra::Vector3d &pose_update_rates)
00107 {
00108
00109 nav_msgs::OdometryPtr odom(new nav_msgs::Odometry);
00110
00111
00112 odom->header.stamp = ros::Time::now();
00113 odom->header.frame_id = odom_frame;
00114 odom->child_frame_id = base_frame;
00115
00116
00117 odom->pose.pose.position.x = pose.x();
00118 odom->pose.pose.position.y = pose.y();
00119 odom->pose.pose.position.z = 0.0;
00120 odom->pose.pose.orientation = odom_quat;
00121
00122
00123 odom->twist.twist.linear.x = pose_update_rates[0];
00124 odom->twist.twist.linear.y = pose_update_rates[1];
00125 odom->twist.twist.angular.z = pose_update_rates[2];
00126
00127
00128
00129
00130 odom->pose.covariance[0] = 0.1;
00131 odom->pose.covariance[7] = 0.1;
00132 odom->pose.covariance[35] = 0.2;
00133
00134 odom->pose.covariance[14] = DBL_MAX;
00135 odom->pose.covariance[21] = DBL_MAX;
00136 odom->pose.covariance[28] = DBL_MAX;
00137
00138 odom_publisher.publish(odom);
00139 }
00140
00141 }