darwin_odom_twist_alg_node.cpp
Go to the documentation of this file.
00001 #include "darwin_odom_twist_alg_node.h"
00002 
00003 DarwinOdomTwistAlgNode::DarwinOdomTwistAlgNode(void) :
00004   algorithm_base::IriBaseAlgorithm<DarwinOdomTwistAlgorithm>()
00005 {
00006   //init class attributes if necessary
00007   this->loop_rate_ = 100;//in [Hz]
00008   this->yaw_angle=0.0;
00009   this->is_first_msg_=true;
00010 
00011   this->public_node_handle_.param<std::string>("tf_prefix",    this->tf_prefix_,     "");
00012   this->public_node_handle_.param<std::string>("odom_id",      this->odom_id_,      "odom" );
00013   this->public_node_handle_.param<std::string>("base_link_id", this->base_link_id_, "base_link" );
00014   this->public_node_handle_.param<bool>       ("publish_tf",   this->publish_tf_,   true  );
00015 
00016   // push down frame ids if necessary
00017   if( !this->tf_prefix_.empty() )
00018   {
00019     this->odom_id_      = this->tf_prefix_ + "/" + this->odom_id_;
00020     this->base_link_id_ = this->tf_prefix_ + "/" + this->base_link_id_;
00021   }
00022 
00023   // [init publishers]
00024   this->odom_publisher_ = this->public_node_handle_.advertise<nav_msgs::Odometry>("odom", 100);
00025 
00026   // [init subscribers]
00027   this->input_twist_subscriber_ = this->public_node_handle_.subscribe("input_twist", 100, &DarwinOdomTwistAlgNode::input_twist_callback, this);
00028   // [init services]
00029 
00030   // [init clients]
00031 
00032   // [init action servers]
00033 
00034   // [init action clients]
00035 }
00036 
00037 DarwinOdomTwistAlgNode::~DarwinOdomTwistAlgNode(void)
00038 {
00039   // [free dynamic memory]
00040 }
00041 
00042 void DarwinOdomTwistAlgNode::mainNodeThread(void)
00043 {
00044   ros::Time current_time=ros::Time::now();
00045   geometry_msgs::TransformStamped odom_trans_msg;
00046   double dt = (current_time - this->last_time_).toSec();
00047   static int delay=10;
00048 
00049   this->input_twist_mutex_.enter();
00050   this->yaw_angle+=this->twist_.twist.angular.z*dt;
00051   //since all odometry is 6DOF we'll need a quaternion created from yaw
00052   geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(this->yaw_angle);
00053 
00054   //update transform message
00055   this->transform_.translation.x += this->twist_.twist.linear.x*dt*cos(this->yaw_angle);
00056   this->transform_.translation.y += this->twist_.twist.linear.x*dt*sin(this->yaw_angle);
00057   this->transform_.translation.z += 0.0;
00058   this->transform_.rotation       = odom_quat;
00059 
00060   //update pose
00061   this->pose_.pose.position.x += this->twist_.twist.linear.x*dt*cos(this->yaw_angle);
00062   this->pose_.pose.position.y += this->twist_.twist.linear.x*dt*sin(this->yaw_angle);
00063   this->pose_.pose.position.z += 0.0;
00064   this->pose_.pose.orientation = odom_quat;
00065   this->input_twist_mutex_.exit();
00066 
00067   //update last time
00068   this->last_time_ = current_time;
00069 
00070   //send the transform
00071   if(this->publish_tf_)
00072   {
00073     //first, we'll publish the transform over tf
00074     odom_trans_msg.header.stamp    = current_time;
00075     odom_trans_msg.header.frame_id = this->odom_id_;
00076     odom_trans_msg.child_frame_id  = this->base_link_id_;
00077     odom_trans_msg.transform       = this->transform_;
00078  
00079     if(delay==0)
00080       this->odom_broadcaster_.sendTransform(odom_trans_msg);
00081   }
00082  
00083   //next, we'll publish the odometry message over ROS
00084   this->Odometry_msg_.header.stamp     = current_time;
00085   this->Odometry_msg_.header.frame_id  = this->odom_id_;
00086   this->Odometry_msg_.child_frame_id   = this->base_link_id_;
00087   this->Odometry_msg_.pose             = this->pose_;
00088   this->Odometry_msg_.twist            = this->twist_;
00089 
00090   //publish the message
00091   if(delay==0)
00092     this->odom_publisher_.publish(this->Odometry_msg_);
00093   delay--;
00094   if(delay<0) 
00095     delay=10;
00096 }
00097 
00098 /*  [subscriber callbacks] */
00099 void DarwinOdomTwistAlgNode::input_twist_callback(const geometry_msgs::Twist::ConstPtr& msg) 
00100 { 
00101   if(this->is_first_msg_)
00102   {
00103     this->is_first_msg_ = false;
00104     this->last_time_=ros::Time::now();
00105   }
00106   // copy the input twist
00107   this->input_twist_mutex_.enter();
00108   this->twist_.twist.linear.x  = msg->linear.x;
00109   this->twist_.twist.linear.y  = msg->linear.y;
00110   this->twist_.twist.linear.z  = msg->linear.z;
00111   this->twist_.twist.angular.x = msg->angular.x;
00112   this->twist_.twist.angular.y = msg->angular.y;
00113   this->twist_.twist.angular.z = msg->angular.z;
00114   this->input_twist_mutex_.exit();
00115 }
00116 
00117 /*  [service callbacks] */
00118 
00119 /*  [action callbacks] */
00120 
00121 /*  [action requests] */
00122 
00123 void DarwinOdomTwistAlgNode::node_config_update(Config &config, uint32_t level)
00124 {
00125   this->alg_.lock();
00126 
00127   this->alg_.unlock();
00128 }
00129 
00130 void DarwinOdomTwistAlgNode::addNodeDiagnostics(void)
00131 {
00132 }
00133 
00134 /* main function */
00135 int main(int argc,char *argv[])
00136 {
00137   return algorithm_base::main<DarwinOdomTwistAlgNode>(argc, argv, "darwin_odom_twist_alg_node");
00138 }


iri_darwin_odom_twist
Author(s): darwin
autogenerated on Fri Dec 6 2013 19:55:41