Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 #include <hardware_interface/joint_state_interface.h>
00019
00020 #include <pluginlib/class_list_macros.h>
00021
00022 #include <tf/transform_broadcaster.h>
00023
00024 #include <cob_omni_drive_controller/UndercarriageCtrlGeom.h>
00025 #include <cob_omni_drive_controller/OdometryTracker.h>
00026
00027 #include <std_srvs/Trigger.h>
00028
00029 #include "GeomController.h"
00030
00031 namespace cob_omni_drive_controller
00032 {
00033
00034
00035 class OdometryController: public GeomController<hardware_interface::JointStateInterface, UndercarriageGeom>
00036 {
00037 public:
00038 OdometryController() {}
00039
00040 virtual bool init(hardware_interface::JointStateInterface* hw, ros::NodeHandle &root_nh, ros::NodeHandle& controller_nh){
00041
00042 if(!GeomController::init(hw, controller_nh)) return false;
00043
00044 double publish_rate;
00045 if (!controller_nh.getParam("publish_rate", publish_rate)){
00046 ROS_ERROR("Parameter 'publish_rate' not set");
00047 return false;
00048 }
00049 if(publish_rate <= 0){
00050 ROS_ERROR_STREAM("publish_rate must be positive.");
00051 return false;
00052 }
00053
00054 const std::string frame_id = controller_nh.param("frame_id", std::string("odom"));
00055 const std::string child_frame_id = controller_nh.param("child_frame_id", std::string("base_footprint"));
00056 const double cov_pose = controller_nh.param("cov_pose", 0.1);
00057 const double cov_twist = controller_nh.param("cov_twist", 0.1);
00058
00059 odom_tracker_.reset(new OdometryTracker(frame_id, child_frame_id, cov_pose, cov_twist));
00060 odom_ = odom_tracker_->getOdometry();
00061
00062 topic_pub_odometry_ = controller_nh.advertise<nav_msgs::Odometry>("odometry", 1);
00063
00064 bool broadcast_tf = true;
00065 controller_nh.getParam("broadcast_tf", broadcast_tf);
00066
00067 if(broadcast_tf){
00068 odom_tf_.header.frame_id = frame_id;
00069 odom_tf_.child_frame_id = child_frame_id;
00070 tf_broadcast_odometry_.reset(new tf::TransformBroadcaster);
00071 }
00072
00073 publish_timer_ = controller_nh.createTimer(ros::Duration(1/publish_rate), &OdometryController::publish, this);
00074 service_reset_ = controller_nh.advertiseService("reset_odometry", &OdometryController::srv_reset, this);
00075
00076 return true;
00077 }
00078 virtual void starting(const ros::Time& time){
00079 if(time != stop_time_) odom_tracker_->init(time);
00080 reset_ = false;
00081 }
00082
00083 virtual bool srv_reset(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
00084 {
00085 if(!isRunning()){
00086 res.message = "not running";
00087 res.success = false;
00088 }else{
00089 boost::mutex::scoped_lock lock(mutex_);
00090 reset_ = true;
00091 lock.unlock();
00092 res.success = true;
00093 ROS_INFO("Resetting odometry to zero.");
00094 }
00095
00096 return true;
00097 }
00098
00099 virtual void update(const ros::Time& time, const ros::Duration& period){
00100
00101 updateState();
00102
00103 geom_->calcDirect(platform_state_);
00104
00105 odom_tracker_->track(time, period.toSec(), platform_state_.getVelX(), platform_state_.getVelY(), platform_state_.dRotRobRadS);
00106
00107 boost::mutex::scoped_try_lock lock(mutex_);
00108 if(lock){
00109 if(reset_){
00110 odom_tracker_->init(time);
00111 reset_ = false;
00112 }
00113 odom_ = odom_tracker_->getOdometry();
00114 }
00115
00116 }
00117 virtual void stopping(const ros::Time& time) { stop_time_ = time; }
00118
00119 private:
00120 PlatformState platform_state_;
00121
00122 ros::Publisher topic_pub_odometry_;
00123 ros::ServiceServer service_reset_;
00124
00125 boost::scoped_ptr<tf::TransformBroadcaster> tf_broadcast_odometry_;
00126 boost::scoped_ptr<OdometryTracker> odom_tracker_;
00127 ros::Timer publish_timer_;
00128 nav_msgs::Odometry odom_;
00129 bool reset_;
00130 boost::mutex mutex_;
00131 geometry_msgs::TransformStamped odom_tf_;
00132 ros::Time stop_time_;
00133
00134
00135 void publish(const ros::TimerEvent&){
00136 if(!isRunning()) return;
00137
00138 boost::mutex::scoped_lock lock(mutex_);
00139
00140 topic_pub_odometry_.publish(odom_);
00141
00142 if(tf_broadcast_odometry_){
00143
00144
00145 odom_tf_.header.stamp = odom_.header.stamp;
00146
00147 odom_tf_.transform.translation.x = odom_.pose.pose.position.x;
00148 odom_tf_.transform.translation.y = odom_.pose.pose.position.y;
00149 odom_tf_.transform.rotation = odom_.pose.pose.orientation;
00150
00151
00152 tf_broadcast_odometry_->sendTransform(odom_tf_);
00153 }
00154 }
00155 };
00156
00157 }
00158
00159 PLUGINLIB_EXPORT_CLASS( cob_omni_drive_controller::OdometryController, controller_interface::ControllerBase)