Go to the documentation of this file.00001
00002 #ifndef ODOMETER_BASE_H_
00003 #define ODOMETER_BASE_H_
00004
00005 #include <ros/ros.h>
00006 #include <nav_msgs/Odometry.h>
00007 #include <std_srvs/Empty.h>
00008
00009 #include <tf/transform_listener.h>
00010 #include <tf/transform_broadcaster.h>
00011
00012 namespace viso2_ros
00013 {
00014
00020 class OdometerBase
00021 {
00022
00023 private:
00024
00025
00026 ros::Publisher odom_pub_;
00027 ros::Publisher pose_pub_;
00028
00029 ros::ServiceServer reset_service_;
00030
00031
00032 std::string sensor_frame_id_;
00033 std::string odom_frame_id_;
00034 std::string base_link_frame_id_;
00035 tf::TransformListener tf_listener_;
00036 tf::TransformBroadcaster tf_broadcaster_;
00037 bool publish_tf_;
00038 bool invert_tf_;
00039
00040
00041 tf::Transform integrated_pose_;
00042
00043 ros::Time last_update_time_;
00044
00045
00046 boost::array<double, 36> pose_covariance_;
00047 boost::array<double, 36> twist_covariance_;
00048
00049 public:
00050
00051 OdometerBase()
00052 {
00053
00054 ros::NodeHandle local_nh("~");
00055
00056 local_nh.param("odom_frame_id", odom_frame_id_, std::string("/odom"));
00057 local_nh.param("base_link_frame_id", base_link_frame_id_, std::string("/base_link"));
00058 local_nh.param("sensor_frame_id", sensor_frame_id_, std::string("/camera"));
00059 local_nh.param("publish_tf", publish_tf_, true);
00060 local_nh.param("invert_tf", invert_tf_, false);
00061
00062 ROS_INFO_STREAM("Basic Odometer Settings:" << std::endl <<
00063 " odom_frame_id = " << odom_frame_id_ << std::endl <<
00064 " base_link_frame_id = " << base_link_frame_id_ << std::endl <<
00065 " publish_tf = " << (publish_tf_?"true":"false") << std::endl <<
00066 " invert_tf = " << (invert_tf_?"true":"false"));
00067
00068
00069 odom_pub_ = local_nh.advertise<nav_msgs::Odometry>("odometry", 1);
00070 pose_pub_ = local_nh.advertise<geometry_msgs::PoseStamped>("pose", 1);
00071
00072 reset_service_ = local_nh.advertiseService("reset_pose", &OdometerBase::resetPose, this);
00073
00074 integrated_pose_.setIdentity();
00075
00076 pose_covariance_.assign(0.0);
00077 twist_covariance_.assign(0.0);
00078 }
00079
00080 protected:
00081
00082 void setSensorFrameId(const std::string& frame_id)
00083 {
00084 sensor_frame_id_ = frame_id;
00085 }
00086
00087 std::string getSensorFrameId() const
00088 {
00089 return sensor_frame_id_;
00090 }
00091
00092 void setPoseCovariance(const boost::array<double, 36>& pose_covariance)
00093 {
00094 pose_covariance_ = pose_covariance;
00095 }
00096
00097 void setTwistCovariance(const boost::array<double, 36>& twist_covariance)
00098 {
00099 twist_covariance_ = twist_covariance;
00100 }
00101
00102 void integrateAndPublish(const tf::Transform& delta_transform, const ros::Time& timestamp)
00103 {
00104 if (sensor_frame_id_.empty())
00105 {
00106 ROS_ERROR("[odometer] update called with unknown sensor frame id!");
00107 return;
00108 }
00109 if (timestamp < last_update_time_)
00110 {
00111 ROS_WARN("[odometer] saw negative time change in incoming sensor data, resetting pose.");
00112 integrated_pose_.setIdentity();
00113 tf_listener_.clear();
00114 }
00115 integrated_pose_ *= delta_transform;
00116
00117
00118 tf::StampedTransform base_to_sensor;
00119 std::string error_msg;
00120 if (tf_listener_.canTransform(base_link_frame_id_, sensor_frame_id_, timestamp, &error_msg))
00121 {
00122 tf_listener_.lookupTransform(
00123 base_link_frame_id_,
00124 sensor_frame_id_,
00125 timestamp, base_to_sensor);
00126 }
00127 else
00128 {
00129 ROS_WARN_THROTTLE(10.0, "The tf from '%s' to '%s' does not seem to be available, "
00130 "will assume it as identity!",
00131 base_link_frame_id_.c_str(),
00132 sensor_frame_id_.c_str());
00133 ROS_DEBUG("Transform error: %s", error_msg.c_str());
00134 base_to_sensor.setIdentity();
00135 }
00136
00137 tf::Transform base_transform = base_to_sensor * integrated_pose_ * base_to_sensor.inverse();
00138
00139 nav_msgs::Odometry odometry_msg;
00140 odometry_msg.header.stamp = timestamp;
00141 odometry_msg.header.frame_id = odom_frame_id_;
00142 odometry_msg.child_frame_id = base_link_frame_id_;
00143 tf::poseTFToMsg(base_transform, odometry_msg.pose.pose);
00144
00145
00146 tf::Transform delta_base_transform = base_to_sensor * delta_transform * base_to_sensor.inverse();
00147 if (!last_update_time_.isZero())
00148 {
00149 double delta_t = (timestamp - last_update_time_).toSec();
00150 if (delta_t)
00151 {
00152 odometry_msg.twist.twist.linear.x = delta_base_transform.getOrigin().getX() / delta_t;
00153 odometry_msg.twist.twist.linear.y = delta_base_transform.getOrigin().getY() / delta_t;
00154 odometry_msg.twist.twist.linear.z = delta_base_transform.getOrigin().getZ() / delta_t;
00155 tf::Quaternion delta_rot = delta_base_transform.getRotation();
00156 tfScalar angle = delta_rot.getAngle();
00157 tf::Vector3 axis = delta_rot.getAxis();
00158 tf::Vector3 angular_twist = axis * angle / delta_t;
00159 odometry_msg.twist.twist.angular.x = angular_twist.x();
00160 odometry_msg.twist.twist.angular.y = angular_twist.y();
00161 odometry_msg.twist.twist.angular.z = angular_twist.z();
00162 }
00163 }
00164
00165 odometry_msg.pose.covariance = pose_covariance_;
00166 odometry_msg.twist.covariance = twist_covariance_;
00167 odom_pub_.publish(odometry_msg);
00168
00169 geometry_msgs::PoseStamped pose_msg;
00170 pose_msg.header.stamp = odometry_msg.header.stamp;
00171 pose_msg.header.frame_id = odometry_msg.header.frame_id;
00172 pose_msg.pose = odometry_msg.pose.pose;
00173
00174 pose_pub_.publish(pose_msg);
00175
00176 if (publish_tf_)
00177 {
00178 if (invert_tf_)
00179 {
00180 tf_broadcaster_.sendTransform(
00181 tf::StampedTransform(base_transform.inverse(), timestamp,
00182 base_link_frame_id_, odom_frame_id_));
00183 }
00184 else
00185 {
00186 tf_broadcaster_.sendTransform(
00187 tf::StampedTransform(base_transform, timestamp,
00188 odom_frame_id_, base_link_frame_id_));
00189 }
00190 }
00191
00192 last_update_time_ = timestamp;
00193 }
00194
00195
00196 bool resetPose(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
00197 {
00198 integrated_pose_.setIdentity();
00199 return true;
00200 }
00201
00202 };
00203
00204 }
00205
00206 #endif
00207