traxbot_node.cpp
Go to the documentation of this file.
00001 
00002 #include <stdlib.h>
00003 #include <stdio.h>
00004 #include <string>
00005 #include <vector>
00006 
00007 #include <ros/ros.h>
00008 #include <tf/transform_broadcaster.h>
00009 #include <nav_msgs/Odometry.h>                  // odom
00010 #include <geometry_msgs/Twist.h>                // cmd_vel
00011 
00012 #include <cereal_port/CerealPort.h>
00013 
00014 
00015 #define MAX_ENCODER_COUNT 32768
00016 
00017 #define AXLE_LENGTH     0.180
00018 #define PULSES_TO_M     0.000087512033
00019                         
00020 #ifndef NORMALIZE
00021     #define NORMALIZE(z) atan2(sin(z), cos(z))  // Normalize angle to domain -pi, pi 
00022 #endif
00023 
00024 
00025 ros::Publisher * odom_pub_ptr;
00026 tf::TransformBroadcaster * odom_broadcaster_ptr;
00027 
00028 cereal::CerealPort serial_port;
00029 ros::Time current_time, last_time;
00030 double last_time_pub = 0.0;
00031 
00032 bool signof (int n) { return n >= 0; }
00033 bool confirm_communication = true;
00034 int ID_Robot = 0;
00035 
00036 double odometry_x_ = 0.0;
00037 double odometry_y_ = 0.0;
00038 double odometry_yaw_ = 0.0;
00039 int right_encoder_prev = 0;
00040 int left_encoder_prev = 0;
00041 
00042 
00043 //Receive encoder ticks and send 'odom' and 'tf'
00044 void robotDataCallback(std::string * data){ 
00045    
00046     if (confirm_communication){
00047       //ROS_INFO("Robot -- Communication OK! Received: \"%s\"", data->c_str());
00048       ROS_INFO("Traxbot is Streaming Data.");
00049       confirm_communication = false;
00050     }
00051     
00052     int first_at = data->find_first_of("@", 0);
00053     int second_at = data->find_first_of("@", first_at+1);    
00054     int first_comma = data->find_first_of(",", 0);
00055     int second_comma = data->find_first_of(",", first_comma+1);    
00056 
00057     //protection against broken msgs from the buffer (e.g., '@6,425@6,4250,6430e')
00058     if ( second_at > -1 || second_comma == -1){
00059       ROS_WARN("%s ::: ENCODER MSG IGNORED", data->c_str());
00060       return; 
00061     }    
00062     
00063     int left_encoder_count, right_encoder_count;        
00064     sscanf(data->c_str(), "@6,%d,%de", &right_encoder_count, &left_encoder_count);   //encoder msg parsing
00065 
00066     //protection against broken msgs from the buffer (e.g., '@6,425@6,4250,6430e')
00067     if ( abs(right_encoder_count) > MAX_ENCODER_COUNT || abs(left_encoder_count) > MAX_ENCODER_COUNT){
00068       ROS_WARN("Encoders > MAX_ENCODER_COUNT");
00069       return; 
00070     }
00071         
00072     double last_x = odometry_x_;
00073     double last_y = odometry_y_;
00074     double last_yaw = odometry_yaw_;           
00075     
00076     // It is not necessary to reset the encoders:    
00077     int right_enc_dif = 0, left_enc_dif = 0;    
00078     
00079     if ( right_encoder_prev >= (0.75*MAX_ENCODER_COUNT) && signof (right_encoder_count) == 0 && signof(right_encoder_prev) == 1 ){
00080       right_enc_dif = (MAX_ENCODER_COUNT-right_encoder_prev) + (MAX_ENCODER_COUNT+right_encoder_count);
00081           
00082     }else if (right_encoder_prev <= (-0.75*MAX_ENCODER_COUNT) && signof (right_encoder_count) == 1 && signof(right_encoder_prev) == 0){
00083       right_enc_dif = -(MAX_ENCODER_COUNT+right_encoder_prev) + (right_encoder_count-MAX_ENCODER_COUNT);
00084       
00085     }else{
00086       right_enc_dif = right_encoder_count - right_encoder_prev;
00087     }
00088     
00089     
00090     if ( left_encoder_prev >= (0.75*MAX_ENCODER_COUNT) && signof (left_encoder_count) == 0 && signof(left_encoder_prev) == 1){
00091       left_enc_dif = (MAX_ENCODER_COUNT-left_encoder_prev) + (MAX_ENCODER_COUNT+left_encoder_count);
00092       
00093     }else if (left_encoder_prev <= (-0.75*MAX_ENCODER_COUNT) && signof (left_encoder_count) == 1 && signof(left_encoder_prev) == 0){
00094       left_enc_dif = -(MAX_ENCODER_COUNT+left_encoder_prev) + (left_encoder_count-MAX_ENCODER_COUNT);
00095       
00096     }else{
00097       left_enc_dif = left_encoder_count - left_encoder_prev;
00098     }      
00099   
00100     //calulate Odometry: 
00101     double dist = (right_enc_dif*PULSES_TO_M + left_enc_dif*PULSES_TO_M) / 2.0; 
00102     double ang = (right_enc_dif*PULSES_TO_M - left_enc_dif*PULSES_TO_M) / AXLE_LENGTH;
00103     bool publish_info = true;
00104 
00105     if (right_encoder_prev == right_encoder_count && left_encoder_prev == left_encoder_count){
00106         publish_info = false;
00107     }
00108     
00109     // update previous encoder counts:
00110     left_encoder_prev = left_encoder_count;
00111     right_encoder_prev = right_encoder_count;
00112 
00113     // Update odometry
00114     odometry_yaw_ = NORMALIZE(odometry_yaw_ + ang);             // rad
00115     odometry_x_ = odometry_x_ + dist*cos(odometry_yaw_);        // m
00116     odometry_y_ = odometry_y_ + dist*sin(odometry_yaw_);        // m   
00117     
00118     last_time = current_time;
00119     current_time = ros::Time::now();      
00120 
00121     // Calculate the robot speed 
00122     double dt = (current_time - last_time).toSec();
00123     double vel_x = (odometry_x_ - last_x)/dt;
00124     double vel_y = (odometry_y_ - last_y)/dt;
00125     double vel_yaw = (odometry_yaw_ - last_yaw)/dt;    
00126 
00127     //Publish at least at most at 75Hz
00128     /*if (current_time.toSec() - 0.013 >= last_time_pub){
00129         publish_info = true;
00130     }*/
00131     
00132     //if(publish_info){
00133 
00134         last_time_pub = current_time.toSec();
00135     
00136         // Since all odometry is 6DOF we'll need a quaternion created from yaw    
00137         geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(odometry_yaw_);
00138 
00139         // First, we'll publish the transform over tf
00140         geometry_msgs::TransformStamped odom_trans;
00141         odom_trans.header.stamp = current_time;
00142         odom_trans.header.frame_id = "odom";
00143         odom_trans.child_frame_id = "base_link";
00144             
00145         odom_trans.transform.translation.x = odometry_x_;
00146         odom_trans.transform.translation.y = odometry_y_;
00147         odom_trans.transform.translation.z = 0.0;
00148         odom_trans.transform.rotation = odom_quat;
00149             
00150         // Send the transform
00151         odom_broadcaster_ptr->sendTransform(odom_trans);                // odom->base_link transform
00152                 
00153             
00154         // Next, we'll publish the odometry message over ROS
00155         nav_msgs::Odometry odom;
00156         odom.header.stamp = current_time;
00157         odom.header.frame_id = "odom";
00158             
00159         // Set the position
00160         odom.pose.pose.position.x = odometry_x_;
00161         odom.pose.pose.position.y = odometry_y_;
00162         odom.pose.pose.position.z = 0.0;
00163         odom.pose.pose.orientation = odom_quat;
00164             
00165         // Set the velocity
00166         odom.child_frame_id = "base_link";
00167         odom.twist.twist.linear.x = vel_x;
00168         odom.twist.twist.linear.y = vel_y;
00169         odom.twist.twist.angular.z = vel_yaw;
00170             
00171         // Publish the message
00172         odom_pub_ptr->publish(odom);            // odometry publisher 
00173     //} 
00174 }
00175 
00176 std::string drive(double linear_speed, double angular_speed, int ID_Robot) {
00177   
00178   //truncate to 3 decimals:
00179   int linear_speed_3decimals = floorf(linear_speed * 1000 + 0.5);
00180   int angular_speed_3decimals = floorf(angular_speed * 1000 + 0.5);
00181   
00182   std::string vel_lin_str, vel_ang_str;
00183   std::stringstream out_lin, out_ang;
00184   
00185   //int to string:
00186   out_lin << linear_speed_3decimals;
00187   vel_lin_str = out_lin.str();
00188   
00189   out_ang << angular_speed_3decimals;
00190   vel_ang_str = out_ang.str();
00191   
00192   std::string result = "@11," + vel_lin_str + "," + vel_ang_str + "e";
00193      
00194   return result;
00195 }
00196 
00197 //receive cmds_vel from nav_stack
00198 void cmdVelReceived(const geometry_msgs::Twist::ConstPtr& cmd_vel){
00199   
00200         std::string result = drive(cmd_vel->linear.x, cmd_vel->angular.z, ID_Robot);
00201         ROS_INFO("[cmd_vel]: Vlinear = %f, Vangular = %f",cmd_vel->linear.x, cmd_vel->angular.z);
00202         ROS_INFO("Sending: %s\n", result.c_str());
00203         serial_port.write( result.c_str() ); 
00204 }
00205 
00206 int main(int argc, char** argv){ //typical usage: "./traxbot_node /dev/ttyACMx"
00207   
00208         ros::init(argc, argv, "traxbot_node");
00209         ros::NodeHandle n;
00210         ros::NodeHandle pn("~");
00211         std::string port;
00212         
00213         if (argc<2){
00214          port="/dev/ttyACM0";
00215          ROS_WARN("No Serial Port defined, defaulting to \"%s\"",port.c_str());
00216          ROS_WARN("Usage: \"rosrun [pkg] robot_node /serial_port\"");
00217         }else{
00218           port=(std::string)argv[1];
00219           ROS_INFO("Serial port: %s",port.c_str());
00220         }       
00221         
00222         // ROS publishers and subscribers
00223         ros::Publisher odom_pub = n.advertise<nav_msgs::Odometry>("/odom", 100);
00224         tf::TransformBroadcaster odom_broadcaster;
00225         ros::Subscriber cmd_vel_sub  = n.subscribe<geometry_msgs::Twist>("/cmd_vel", 10, cmdVelReceived);
00226     
00227         odom_pub_ptr = &odom_pub;
00228         odom_broadcaster_ptr = &odom_broadcaster;       
00229         
00230         // baud_rate and serial port:   
00231         int baudrate;
00232         pn.param<std::string>("port", port, port.c_str()); 
00233         pn.param("baudrate", baudrate, 115200); 
00234 
00235         // Open the serial port to the robot
00236         try{ serial_port.open((char*)port.c_str(), baudrate); }
00237         catch(cereal::Exception& e){
00238                 ROS_FATAL("Robot -- Failed to open serial port!");
00239                 ROS_BREAK();
00240         }
00241     
00242         //wait (2.5 seconds) until serial port gets ready
00243         ros::Duration(2.5).sleep();     
00244                 
00245         // Ask Robot ID from the Arduino board (stored in the EEPROM)
00246         ROS_INFO("Starting Traxbot...");
00247         serial_port.write("@5e");
00248         std::string reply;
00249 
00250         try{ serial_port.readBetween(&reply,'@','e'); } 
00251         catch(cereal::TimeoutException& e){
00252           ROS_ERROR("Initial Read Timeout!");
00253         }
00254         
00255         int VDriver, Temperature, OMNI_Firmware, Battery;
00256         sscanf(reply.c_str(), "@5,%d,%d,%d,%d,%de", &Temperature, &OMNI_Firmware, &Battery, &VDriver, &ID_Robot);   //encoder msg parsing
00257 
00258         ROS_INFO("Traxbot ID = %d", ID_Robot);
00259         if (ID_Robot < 1 || ID_Robot > 3){
00260                 ROS_WARN("Attention! Unexpected Traxbot ID!");
00261         }
00262         ROS_INFO("OMNI Board Temperature = %.2f C", Temperature*0.01);
00263         ROS_INFO("OMNI Firmware = %.2f", OMNI_Firmware*0.01);
00264         ROS_INFO("Arduino Firmware Version = %d.00", VDriver);
00265 
00266         if (VDriver > 1500){
00267                 ROS_ERROR("Reset Robot Connection and try again.");
00268                 return(0);
00269         }
00270 
00271         ROS_INFO("Battery = %.2f V", Battery*0.01 );
00272         if (Battery < 100){
00273                 ROS_ERROR("Robot is off. Check power source!");
00274                 return(0);
00275         }
00276         if (Battery < 850 && Battery > 100){
00277                 ROS_WARN("Warning! Low Battery!");
00278         }
00279         
00280         // Start receiving streaming data
00281         if( !serial_port.startReadBetweenStream(boost::bind(&robotDataCallback, _1), '@', 'e') ){
00282                   ROS_FATAL("Robot -- Failed to start streaming data!");
00283                   ROS_BREAK();
00284         }
00285         serial_port.write("@18e");
00286     
00287         ros::spin(); //trigger callbacks and prevents exiting
00288         return(0);
00289 }


mrl_robots_drivers
Author(s): André Araújo and David Portugal
autogenerated on Mon Jan 6 2014 11:28:51