Go to the documentation of this file.
28 #include <nav_msgs/Odometry.h>
29 #include <std_srvs/Trigger.h>
48 ROS_ERROR(
"Parameter 'steer_joint' not set");
52 ROS_ERROR(
"Parameter 'drive_joint' not set");
60 std::string description_name;
61 bool has_model = nh.
searchParam(
"robot_description", description_name) && model.
initParam(description_name);
63 urdf::Vector3 steer_pos;
64 urdf::JointConstSharedPtr steer_joint;
81 if (!nh.
getParam(
"publish_rate", publish_rate)){
82 ROS_ERROR(
"Parameter 'publish_rate' not set");
85 if(publish_rate <= 0){
90 const std::string frame_id = nh.
param(
"frame_id", std::string(
"odom"));
91 const std::string child_frame_id = nh.
param(
"child_frame_id", std::string(
"base_footprint"));
92 const double cov_pose = nh.
param(
"cov_pose", 0.1);
93 const double cov_twist = nh.
param(
"cov_twist", 0.1);
100 bool broadcast_tf =
true;
101 nh.
getParam(
"broadcast_tf", broadcast_tf);
104 odom_tf_.header.frame_id = frame_id;
105 odom_tf_.child_frame_id = child_frame_id;
120 virtual bool srv_reset(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
123 res.message =
"not running";
126 boost::mutex::scoped_lock lock(
mutex_);
130 ROS_INFO(
"Resetting odometry to zero.");
142 boost::mutex::scoped_try_lock lock(
mutex_);
174 boost::mutex::scoped_lock lock(
mutex_);
183 odom_tf_.transform.translation.x =
odom_.pose.pose.position.x;
184 odom_tf_.transform.translation.y =
odom_.pose.pose.position.y;
virtual bool init(hardware_interface::JointStateInterface *hw, ros::NodeHandle &nh)
hardware_interface::JointStateHandle drive_joint_
#define ROS_ERROR_STREAM(args)
boost::scoped_ptr< tf::TransformBroadcaster > tf_broadcast_odometry_
JointStateHandle getHandle(const std::string &name)
bool getParam(const std::string &key, bool &b) const
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
virtual void update(const ros::Time &time, const ros::Duration &period)
hardware_interface::JointStateHandle steer_joint_
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
void publish(const ros::TimerEvent &)
ros::ServiceServer service_reset_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
bool parseWheelTransform(const std::string &joint_name, const std::string &parent_link_name, tf2::Transform &transform, urdf::Model *model)
virtual void stopping(const ros::Time &time)
tf2Scalar getAngle() const
bool searchParam(const std::string &key, std::string &result) const
ros::Timer publish_timer_
virtual void starting(const ros::Time &time)
boost::scoped_ptr< OdometryTracker > odom_tracker_
double getVelocity() const
double getPosition() const
URDF_EXPORT bool initParam(const std::string ¶m)
PlatformState platform_state_
T param(const std::string ¶m_name, const T &default_val) const
geometry_msgs::TransformStamped odom_tf_
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Publisher topic_pub_odometry_
virtual bool srv_reset(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)