odometry.cpp
Go to the documentation of this file.
1 
10 /*****************************************************************************
11 ** Includes
12 *****************************************************************************/
13 
14 #include "../../include/kobuki_node/odometry.hpp"
15 
16 /*****************************************************************************
17 ** Namespaces
18 *****************************************************************************/
19 
20 namespace kobuki {
21 
22 /*****************************************************************************
23 ** Implementation
24 *****************************************************************************/
25 
27  odom_frame("odom"),
28  base_frame("base_footprint"),
29  use_imu_heading(true),
30  publish_tf(true)
31 {};
32 
33 void Odometry::init(ros::NodeHandle& nh, const std::string& name) {
34  double timeout;
35  nh.param("cmd_vel_timeout", timeout, 0.6);
36  cmd_vel_timeout.fromSec(timeout);
37  ROS_INFO_STREAM("Kobuki : Velocity commands timeout: " << cmd_vel_timeout << " seconds [" << name << "].");
38 
39  if (!nh.getParam("odom_frame", odom_frame)) {
40  ROS_WARN_STREAM("Kobuki : no param server setting for odom_frame, using default [" << odom_frame << "][" << name << "].");
41  } else {
42  ROS_INFO_STREAM("Kobuki : using odom_frame [" << odom_frame << "][" << name << "].");
43  }
44 
45  if (!nh.getParam("base_frame", base_frame)) {
46  ROS_WARN_STREAM("Kobuki : no param server setting for base_frame, using default [" << base_frame << "][" << name << "].");
47  } else {
48  ROS_INFO_STREAM("Kobuki : using base_frame [" << base_frame << "][" << name << "].");
49  }
50 
51  if (!nh.getParam("publish_tf", publish_tf)) {
52  ROS_WARN_STREAM("Kobuki : no param server setting for publish_tf, using default [" << publish_tf << "][" << name << "].");
53  } else {
54  if ( publish_tf ) {
55  ROS_INFO_STREAM("Kobuki : publishing transforms [" << name << "].");
56  } else {
57  ROS_INFO_STREAM("Kobuki : not publishing transforms (see robot_pose_ekf) [" << name << "].");
58  }
59  }
60 
61  if (!nh.getParam("use_imu_heading", use_imu_heading)) {
62  ROS_WARN_STREAM("Kobuki : no param server setting for use_imu_heading, using default [" << use_imu_heading << "][" << name << "].");
63  } else {
64  if ( use_imu_heading ) {
65  ROS_INFO_STREAM("Kobuki : using imu data for heading [" << name << "].");
66  } else {
67  ROS_INFO_STREAM("Kobuki : using encoders for heading (see robot_pose_ekf) [" << name << "].");
68  }
69  }
70 
71  odom_trans.header.frame_id = odom_frame;
72  odom_trans.child_frame_id = base_frame;
73 
74  pose.setIdentity();
75 
76  odom_publisher = nh.advertise<nav_msgs::Odometry>("odom", 50); // topic name and queue size
77 }
78 
81  return true;
82  } else {
83  return false;
84  }
85 }
86 
87 void Odometry::update(const ecl::LegacyPose2D<double> &pose_update, ecl::linear_algebra::Vector3d &pose_update_rates,
88  double imu_heading, double imu_angular_velocity) {
89  pose *= pose_update;
90 
91  if (use_imu_heading == true) {
92  // Overwite with gyro heading data
93  pose.heading(imu_heading);
94  pose_update_rates[2] = imu_angular_velocity;
95  }
96 
97  //since all ros tf odometry is 6DOF we'll need a quaternion created from yaw
98  geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(pose.heading());
99 
100  if ( ros::ok() ) {
101  publishTransform(odom_quat);
102  publishOdometry(odom_quat, pose_update_rates);
103  }
104 }
105 
106 /*****************************************************************************
107 ** Private Implementation
108 *****************************************************************************/
109 
110 void Odometry::publishTransform(const geometry_msgs::Quaternion &odom_quat)
111 {
112  if (publish_tf == false)
113  return;
114 
115  odom_trans.header.stamp = ros::Time::now();
116  odom_trans.transform.translation.x = pose.x();
117  odom_trans.transform.translation.y = pose.y();
118  odom_trans.transform.translation.z = 0.0;
119  odom_trans.transform.rotation = odom_quat;
121 }
122 
123 void Odometry::publishOdometry(const geometry_msgs::Quaternion &odom_quat,
124  const ecl::linear_algebra::Vector3d &pose_update_rates)
125 {
126  // Publish as shared pointer to leverage the nodelets' zero-copy pub/sub feature
127  nav_msgs::OdometryPtr odom(new nav_msgs::Odometry);
128 
129  // Header
130  odom->header.stamp = ros::Time::now();
131  odom->header.frame_id = odom_frame;
132  odom->child_frame_id = base_frame;
133 
134  // Position
135  odom->pose.pose.position.x = pose.x();
136  odom->pose.pose.position.y = pose.y();
137  odom->pose.pose.position.z = 0.0;
138  odom->pose.pose.orientation = odom_quat;
139 
140  // Velocity
141  odom->twist.twist.linear.x = pose_update_rates[0];
142  odom->twist.twist.linear.y = pose_update_rates[1];
143  odom->twist.twist.angular.z = pose_update_rates[2];
144 
145  // Pose covariance (required by robot_pose_ekf) TODO: publish realistic values
146  // Odometry yaw covariance must be much bigger than the covariance provided
147  // by the imu, as the later takes much better measures
148  odom->pose.covariance[0] = 0.1;
149  odom->pose.covariance[7] = 0.1;
150  odom->pose.covariance[35] = use_imu_heading ? 0.05 : 0.2;
151 
152  odom->pose.covariance[14] = 1e10; // set a non-zero covariance on unused
153  odom->pose.covariance[21] = 1e10; // dimensions (z, pitch and roll); this
154  odom->pose.covariance[28] = 1e10; // is a requirement of robot_pose_ekf
155 
156  odom_publisher.publish(odom);
157 }
158 
159 } // namespace kobuki
void publish(const boost::shared_ptr< M > &message) const
std::string base_frame
Definition: odometry.hpp:54
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
Duration & fromSec(double t)
std::string odom_frame
Definition: odometry.hpp:53
bool param(const std::string &param_name, T &param_val, const T &default_val) const
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
ROSCPP_DECL bool ok()
void sendTransform(const StampedTransform &transform)
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
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool commandTimeout() const
Definition: odometry.cpp:79
#define ROS_WARN_STREAM(args)
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 geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
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