14 #include "../../include/kobuki_node/odometry.hpp" 28 base_frame(
"base_footprint"),
29 use_imu_heading(true),
35 nh.
param(
"cmd_vel_timeout", timeout, 0.6);
40 ROS_WARN_STREAM(
"Kobuki : no param server setting for odom_frame, using default [" <<
odom_frame <<
"][" << name <<
"].");
46 ROS_WARN_STREAM(
"Kobuki : no param server setting for base_frame, using default [" <<
base_frame <<
"][" << name <<
"].");
52 ROS_WARN_STREAM(
"Kobuki : no param server setting for publish_tf, using default [" <<
publish_tf <<
"][" << name <<
"].");
57 ROS_INFO_STREAM(
"Kobuki : not publishing transforms (see robot_pose_ekf) [" << name <<
"].");
65 ROS_INFO_STREAM(
"Kobuki : using imu data for heading [" << name <<
"].");
67 ROS_INFO_STREAM(
"Kobuki : using encoders for heading (see robot_pose_ekf) [" << name <<
"].");
88 double imu_heading,
double imu_angular_velocity) {
93 pose.heading(imu_heading);
94 pose_update_rates[2] = imu_angular_velocity;
124 const ecl::linear_algebra::Vector3d &pose_update_rates)
127 nav_msgs::OdometryPtr odom(
new nav_msgs::Odometry);
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;
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];
148 odom->pose.covariance[0] = 0.1;
149 odom->pose.covariance[7] = 0.1;
152 odom->pose.covariance[14] = 1e10;
153 odom->pose.covariance[21] = 1e10;
154 odom->pose.covariance[28] = 1e10;
void publish(const boost::shared_ptr< M > &message) const
void publishTransform(const geometry_msgs::Quaternion &odom_quat)
void init(ros::NodeHandle &nh, const std::string &name)
const ros::Duration & timeout() const
Duration & fromSec(double t)
bool param(const std::string ¶m_name, T ¶m_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)
tf::TransformBroadcaster odom_broadcaster
ros::Duration cmd_vel_timeout
geometry_msgs::TransformStamped odom_trans
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool commandTimeout() const
#define ROS_WARN_STREAM(args)
ros::Publisher odom_publisher
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
void publishOdometry(const geometry_msgs::Quaternion &odom_quat, const ecl::linear_algebra::Vector3d &pose_update_rates)
ecl::LegacyPose2D< double > pose