state_tf.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <tf/transform_broadcaster.h>
00003 #include "math.h"
00004 #include "corobot_msgs/PosMsg.h"
00005 #include "nav_msgs/Odometry.h"
00006 #include <dynamic_reconfigure/server.h>
00007 #include <corobot_state_tf/corobot_state_tfConfig.h>
00008 
00009 long _PreviousLeftEncoderCounts = 0;
00010 long _PreviousRightEncoderCounts = 0;
00011 ros::Time current_time_encoder, last_time_encoder;
00012 double DistancePerCount; //to calculate - distance in meter for one count of the encoders.The Phidget C API gives the number of encoder ticks *4.
00013 double lengthBetweenTwoWheels; //distance in meters between the left and right wheels, taken in the middle. 
00014 /*Measures for Corobot:
00015  *Diameter of wheel = 10.5 cm
00016  *Distance between wheels = 21cm
00017  *ticks per revolution 12*52
00018 
00019   Measures forExplorer:
00020  *Diameter of wheel = 20.32 cm
00021  *Distance between wheels = 48.895cm
00022  *ticks per revolution ??
00023  */
00024 double x;
00025 double y;
00026 double th;
00027 
00028 double vx;
00029 double vy;
00030 double vth;
00031 double dt;
00032 
00033 int firstTime;
00034 bool isExplorer, isCorobot4WD, publish_odom_tf;
00035 bool odometry_activated = true;
00036 
00037 void WheelCallback(const corobot_msgs::PosMsg::ConstPtr& pos)
00038 {
00039   current_time_encoder = pos->header.stamp;
00040   long deltaLeft;
00041   long deltaRight;
00042   //current_time_encoder = ros::Time::now();
00043   dt = (current_time_encoder - last_time_encoder).toSec();
00044   if (dt>0.01){
00045           if(firstTime != 0)
00046           {
00047                 deltaLeft = (pos->px - _PreviousLeftEncoderCounts);
00048 
00049                 deltaRight = (pos->py - _PreviousRightEncoderCounts);
00050             
00051             double vl = 0.0,vr = 0.0;
00052             vl = ((double)deltaLeft * DistancePerCount); //distance made by the left wheel
00053             vr = ((double)deltaRight * DistancePerCount); //distance made by the right wheel
00054             
00055             vx = (vl+vr)/2.0;
00056             vth = (vr-vl)/lengthBetweenTwoWheels; //rotation made by the robot
00057             double delta_x = 0.0, delta_y = 0.0, delta_th = 0.0;
00058             delta_x = (vx * cos(th) - vy * sin(th));
00059             delta_y = (vx * sin(th) + vy * cos(th));
00060             delta_th = vth;
00061             x += delta_x;
00062             y += delta_y;
00063             int mod = (int) ((th+delta_th)/(2*M_PI));
00064             th = (th+ delta_th) -(mod*2*M_PI);
00065           }
00066           else
00067             firstTime = 1;
00068           _PreviousLeftEncoderCounts = pos->px;
00069           _PreviousRightEncoderCounts = pos->py;
00070           last_time_encoder = current_time_encoder;
00071     }
00072 }
00073 
00074 void dynamic_reconfigureCallback(corobot_state_tf::corobot_state_tfConfig &config, uint32_t level) {
00075                 odometry_activated = config.camera_state_tf;
00076 }
00077 
00078 int main(int argc, char** argv){
00079   ros::init(argc, argv, "corobot_state_tf");
00080   ros::NodeHandle n;
00081   ros::NodeHandle nh("~");
00082   nh.param("Explorer", isExplorer, false);
00083   nh.param("Corobot4WD", isCorobot4WD, false);
00084   nh.param("publish_odom_tf", publish_odom_tf, true);
00085 
00086     dynamic_reconfigure::Server<corobot_state_tf::corobot_state_tfConfig> server;
00087     dynamic_reconfigure::Server<corobot_state_tf::corobot_state_tfConfig>::CallbackType f;
00088 
00089     f = boost::bind(&dynamic_reconfigureCallback, _1, _2);
00090     server.setCallback(f);
00091   if (isExplorer)
00092   {
00093         DistancePerCount = (M_PI*0.2032)/(500.0*59.0*4.0);
00094         lengthBetweenTwoWheels = 0.48895;
00095   }
00096   else if (isCorobot4WD)
00097   {
00098         DistancePerCount = (M_PI*0.109)/(12.0*52.0*4.0);
00099         lengthBetweenTwoWheels = 0.31 + 0.03; //length between left front and rear right wheel, plus a little more to compensate for the slipping 
00100   }
00101   else
00102   {
00103         DistancePerCount = (M_PI*0.109)/(12.0*52.0*4.0);
00104         lengthBetweenTwoWheels = 0.282;
00105   }
00106   _PreviousLeftEncoderCounts = 0;
00107   _PreviousRightEncoderCounts = 0;
00108   vx = 0;
00109   vy = 0;
00110   vth = 0;
00111   firstTime = 0;
00112 
00113   ros::Subscriber sub = n.subscribe("/position_data", 1000, WheelCallback);
00114   ros::Publisher odom_pub = n.advertise<nav_msgs::Odometry>("odometry", 50);   
00115   tf::TransformBroadcaster odom_broadcaster;
00116 
00117   ros::Rate r(50);
00118   ros::Rate r_deactivated(2);
00119 
00120   tf::TransformBroadcaster broadcaster;
00121 
00122   while(n.ok()){
00123     ros::spinOnce();
00124     if (odometry_activated)
00125     {
00126             if (isExplorer)
00127                 broadcaster.sendTransform(tf::StampedTransform(tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0.2413, 0, 0)),ros::Time::now(),"base_link", "laser"));
00128             else
00129                 broadcaster.sendTransform(tf::StampedTransform(tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0.15, 0, 0)),ros::Time::now(),"base_link", "laser"));
00130 
00131             //since all odometry is 6DOF we'll need a quaternion created from yaw
00132             geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(th);
00133             geometry_msgs::Quaternion odom_quat2 = tf::createQuaternionMsgFromYaw(0);
00134 
00135             //first, we'll publish the transform over tf
00136             geometry_msgs::TransformStamped odom_trans;
00137             odom_trans.header.stamp = ros::Time::now();
00138             odom_trans.header.frame_id = "odom";
00139             odom_trans.child_frame_id = "base_footprint";
00140 
00141             odom_trans.transform.translation.x = x;
00142             odom_trans.transform.translation.y = y;
00143             odom_trans.transform.translation.z = 0.0;
00144             odom_trans.transform.rotation = odom_quat;
00145 
00146             geometry_msgs::TransformStamped odom_trans2;
00147             odom_trans2.header.stamp = current_time_encoder;
00148             odom_trans2.header.frame_id = "base_footprint";
00149             odom_trans2.child_frame_id = "base_link";
00150 
00151             odom_trans2.transform.translation.x = 0;
00152             odom_trans2.transform.translation.y = 0;
00153             odom_trans2.transform.translation.z = 0.0;
00154             odom_trans2.transform.rotation = odom_quat2;
00155 
00156 
00157             //send the transform
00158             if(publish_odom_tf)
00159                 odom_broadcaster.sendTransform(odom_trans);
00160             odom_broadcaster.sendTransform(odom_trans2);
00161 
00162             //next, we'll publish the odometry message over ROS
00163             nav_msgs::Odometry odom;
00164             odom.header.stamp = current_time_encoder;
00165             odom.header.frame_id = "odom";
00166 
00167             //set the position
00168             odom.pose.pose.position.x = x;
00169             odom.pose.pose.position.y = y;
00170             odom.pose.pose.position.z = 0.0;
00171             odom.pose.pose.orientation = odom_quat;
00172             odom.pose.covariance[0] = 0.01;
00173             odom.pose.covariance[7] = 0.01;
00174             odom.pose.covariance[14] = 10000;
00175             odom.pose.covariance[21] = 10000;
00176             odom.pose.covariance[28] = 10000;
00177             odom.pose.covariance[35] = 0.1;
00178 
00179 
00180             //set the velocity
00181             odom.child_frame_id = "base_link";
00182             if (dt!=0)
00183             {
00184                 odom.twist.twist.linear.x = vx/dt;
00185                 odom.twist.twist.linear.y = vy/dt;
00186                 odom.twist.twist.angular.z = vth/dt;
00187             }
00188             else
00189             {
00190                 odom.twist.twist.linear.x = 0;
00191                 odom.twist.twist.linear.y = 0;
00192                 odom.twist.twist.angular.z = 0;
00193             }
00194             odom.twist.covariance[0] = 0.01;
00195             odom.twist.covariance[7] = 0.01;
00196             odom.twist.covariance[14] = 10000;
00197             odom.twist.covariance[21] = 10000;
00198             odom.twist.covariance[28] = 10000;
00199             odom.twist.covariance[35] = 0.1;
00200 
00201             //publish the message
00202             odom_pub.publish(odom);
00203 
00204             r.sleep();
00205         }
00206         else
00207             r_deactivated.sleep();
00208   }
00209 }


corobot_state_tf
Author(s): Morgan Cormier/mcormier@coroware.com
autogenerated on Tue Jan 7 2014 11:38:58