Go to the documentation of this file.
27 #include <std_srvs/Trigger.h>
45 if (!controller_nh.
getParam(
"publish_rate", publish_rate)){
46 ROS_ERROR(
"Parameter 'publish_rate' not set");
49 if(publish_rate <= 0){
56 const double cov_pose = controller_nh.
param(
"cov_pose", 0.1);
57 const double cov_twist = controller_nh.
param(
"cov_twist", 0.1);
64 bool broadcast_tf =
true;
65 controller_nh.
getParam(
"broadcast_tf", broadcast_tf);
85 virtual bool srv_reset(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
88 res.message =
"not running";
91 boost::mutex::scoped_lock lock(
mutex_);
95 ROS_INFO(
"Resetting odometry to zero.");
109 boost::mutex::scoped_try_lock lock(
mutex_);
140 if(!isRunning())
return;
142 boost::mutex::scoped_lock lock(
mutex_);
161 odom_tf_.transform.translation.x =
odom_.pose.pose.position.x;
162 odom_tf_.transform.translation.y =
odom_.pose.pose.position.y;
static void transformTFToMsg(const Transform &bt, geometry_msgs::Transform &msg)
boost::scoped_ptr< OdometryTracker > odom_tracker_
ros::ServiceServer service_reset_
#define ROS_ERROR_STREAM(args)
boost::scoped_ptr< UndercarriageGeom > geom_
std::string child_frame_id_
bool getParam(const std::string &key, bool &b) const
static void transformMsgToTF(const geometry_msgs::Transform &msg, Transform &bt)
virtual void update(const ros::Time &time, const ros::Duration &period)
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
virtual bool srv_reset(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
virtual bool init(hardware_interface::JointStateInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
geometry_msgs::TransformStamped odom_tf_
ros::Timer publish_timer_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual void stopping(const ros::Time &time)
virtual void starting(const ros::Time &time)
boost::scoped_ptr< tf::TransformBroadcaster > tf_broadcast_odometry_
PlatformState platform_state_
bool init(Interface *hw, ros::NodeHandle &controller_nh)
T param(const std::string ¶m_name, const T &default_val) const
void publish(const ros::TimerEvent &event)
ros::Publisher topic_pub_odometry_
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const