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){
54 const std::string frame_id = controller_nh.
param(
"frame_id", std::string(
"odom"));
55 const std::string child_frame_id = controller_nh.
param(
"child_frame_id", std::string(
"base_footprint"));
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);
69 odom_tf_.child_frame_id = child_frame_id;
83 virtual bool srv_reset(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
86 res.message =
"not running";
89 boost::mutex::scoped_lock lock(
mutex_);
93 ROS_INFO(
"Resetting odometry to zero.");
107 boost::mutex::scoped_try_lock lock(
mutex_);
136 if(!isRunning())
return;
138 boost::mutex::scoped_lock lock(mutex_);
140 topic_pub_odometry_.
publish(odom_);
142 if(tf_broadcast_odometry_){
144 if (odom_tf_.header.stamp == odom_.header.stamp){
155 odom_tf_.header.stamp = odom_.header.stamp;
157 odom_tf_.transform.translation.x = odom_.pose.pose.position.x;
158 odom_tf_.transform.translation.y = odom_.pose.pose.position.y;
159 odom_tf_.transform.rotation = odom_.pose.pose.orientation;
162 tf_broadcast_odometry_->sendTransform(odom_tf_);
void publish(const ros::TimerEvent &event)
boost::scoped_ptr< UndercarriageGeom > geom_
virtual void starting(const ros::Time &time)
void publish(const boost::shared_ptr< M > &message) const
virtual void update(const ros::Time &time, const ros::Duration &period)
geometry_msgs::TransformStamped odom_tf_
ros::Publisher topic_pub_odometry_
virtual bool init(hardware_interface::JointStateInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
virtual void stopping(const ros::Time &time)
boost::scoped_ptr< tf::TransformBroadcaster > tf_broadcast_odometry_
PlatformState platform_state_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
ros::Timer publish_timer_
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
virtual bool srv_reset(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
bool init(Interface *hw, ros::NodeHandle &controller_nh)
boost::scoped_ptr< OdometryTracker > odom_tracker_
bool getParam(const std::string &key, std::string &s) const
#define ROS_ERROR_STREAM(args)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
ros::ServiceServer service_reset_