rbcar_robot_control.cpp
Go to the documentation of this file.
00001 /*
00002  * rbcar_robot_control
00003  * Copyright (c) 2015, Robotnik Automation, SLL
00004  * All rights reserved.
00005  *
00006  * Redistribution and use in source and binary forms, with or without
00007  * modification, are permitted provided that the following conditions are met:
00008  *
00009  *     * Redistributions of source code must retain the above copyright
00010  *       notice, this list of conditions and the following disclaimer.
00011  *     * Redistributions in binary form must reproduce the above copyright
00012  *       notice, this list of conditions and the following disclaimer in the
00013  *       documentation and/or other materials provided with the distribution.
00014  *     * Neither the name of the Robotnik Automation, SLL. nor the names of its
00015  *       contributors may be used to endorse or promote products derived from
00016  *       this software without specific prior written permission.
00017  *
00018  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00021  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00022  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00023  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00024  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00025  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00026  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00027  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00028  * POSSIBILITY OF SUCH DAMAGE.
00029  *
00030  * \author Robotnik
00031  * \brief Controller for the RBCAR robot in ackermann-steering (single)
00032     Control steering (2 direction axes) and traction axes (4W) of the RBCAR single Ackerman drive kinematics
00033     transforms the commands received from the joystick (or other high level controller) in motor position / velocity commands
00034  */
00035 
00036 #include <ros/ros.h>
00037 #include <sensor_msgs/JointState.h>
00038 #include <sensor_msgs/Imu.h>
00039 #include <std_msgs/Float64.h>
00040 #include <tf/transform_broadcaster.h>
00041 #include <nav_msgs/Odometry.h>
00042 #include <robotnik_msgs/set_mode.h>
00043 #include <robotnik_msgs/get_mode.h>
00044 #include <robotnik_msgs/set_odometry.h>
00045 #include <robotnik_msgs/ptz.h>
00046 
00047 #include "ackermann_msgs/AckermannDriveStamped.h"
00048 
00049 //#include "self_test/self_test.h"
00050 #include "diagnostic_msgs/DiagnosticStatus.h"
00051 #include "diagnostic_updater/diagnostic_updater.h"
00052 #include "diagnostic_updater/update_functions.h"
00053 #include "diagnostic_updater/DiagnosticStatusWrapper.h"
00054 #include "diagnostic_updater/publisher.h"
00055 
00056 
00057 #define PI 3.1415926535
00058 #define RBCAR_MIN_COMMAND_REC_FREQ   5.0
00059 #define RBCAR_MAX_COMMAND_REC_FREQ   150.0
00060 
00061 #define RBCAR_D_WHEELS_M            1.65    // distance from front to back axis, car-like kinematics
00062 #define RBCAR_WHEEL_DIAMETER        0.470   // wheel avg diameter - may need calibration according to tyre pressure
00063         
00064 using namespace std;
00065 
00066 class RbcarControllerClass {
00067 
00068 public:
00069 
00070   ros::NodeHandle node_handle_;
00071   ros::NodeHandle private_node_handle_;
00072   double desired_freq_;
00073 
00074   // Diagnostics
00075   diagnostic_updater::Updater diagnostic_;                              // General status diagnostic updater
00076   diagnostic_updater::FrequencyStatus freq_diag_;               // Component frequency diagnostics
00077   diagnostic_updater::HeaderlessTopicDiagnostic *subs_command_freq; // Topic reception frequency diagnostics
00078   ros::Time last_command_time_;                                 // Last moment when the component received a command
00079   diagnostic_updater::FunctionDiagnosticTask command_freq_;
00080 
00081   // Robot model 
00082   std::string robot_model_;
00083   
00084   // Velocity and position references to low level controllers
00085   ros::Publisher ref_vel_flw_;
00086   ros::Publisher ref_vel_frw_;
00087   ros::Publisher ref_vel_blw_;
00088   ros::Publisher ref_vel_brw_;
00089   ros::Publisher ref_pos_flw_;
00090   ros::Publisher ref_pos_frw_;
00091 
00092   // Joint states published by the joint_state_controller of the Controller Manager
00093   ros::Subscriber joint_state_sub_;
00094 
00095   // High level robot command
00096   ros::Subscriber cmd_sub_;
00097         
00098   //ros::Subscriber gyro_sub_;
00099 
00100   // Services
00101   ros::ServiceServer srv_SetOdometry_;
00102   
00103   // Ackermann Topics - control action - traction - velocity
00104   std::string frw_vel_topic_;
00105   std::string flw_vel_topic_;
00106   std::string brw_vel_topic_;
00107   std::string blw_vel_topic_;
00108   
00109   // Ackerman Topics - control action - steering - position
00110   std::string frw_pos_topic_;
00111   std::string flw_pos_topic_;
00112 
00113   // Joint names - traction - velocity 
00114   std::string joint_front_right_wheel;
00115   std::string joint_front_left_wheel;
00116   std::string joint_back_left_wheel;
00117   std::string joint_back_right_wheel;
00118     
00119   // Joint names - steering - position
00120   std::string joint_front_right_steer;
00121   std::string joint_front_left_steer;
00122 
00123   // Indexes to joint_states
00124   int frw_vel_, flw_vel_, blw_vel_, brw_vel_;
00125   int frw_pos_, flw_pos_;
00126 
00127   // Robot Speeds
00128   double linearSpeedXMps_;
00129   double linearSpeedYMps_;
00130   double angularSpeedRads_;
00131 
00132   // Robot Positions
00133   double robot_pose_px_;
00134   double robot_pose_py_;
00135   double robot_pose_pa_;
00136   double robot_pose_vx_;
00137   double robot_pose_vy_;
00138   
00139   // Robot Joint States
00140   sensor_msgs::JointState joint_state_;
00141   
00142   // Command reference
00143   ackermann_msgs::AckermannDriveStamped base_vel_msg_;
00144   
00145   // External speed references
00146   double v_ref_;
00147   double alfa_ref_;
00148   double pos_ref_pan_;
00149   double pos_ref_tilt_;
00150   
00151   // Flag to indicate if joint_state has been read
00152   bool read_state_; 
00153   
00154   // Robot configuration parameters 
00155   double rbcar_wheel_diameter_; 
00156   double rbcar_d_wheels_;
00157 
00158   // IMU values
00159   double ang_vel_x_;
00160   double ang_vel_y_;
00161   double ang_vel_z_;
00162 
00163   double lin_acc_x_;
00164   double lin_acc_y_;
00165   double lin_acc_z_;
00166 
00167   double orientation_x_;
00168   double orientation_y_;
00169   double orientation_z_;
00170   double orientation_w_;
00171 
00172   // Parameter that defines if odom tf is published or not
00173   bool publish_odom_tf_;
00174 
00175   ros::Subscriber imu_sub_; 
00176   
00177   // Publisher for odom topic
00178   ros::Publisher odom_pub_; 
00179 
00180   // Broadcaster for odom tf  
00181   tf::TransformBroadcaster odom_broadcaster;
00182 
00183 
00187 RbcarControllerClass(ros::NodeHandle h) : diagnostic_(),
00188   node_handle_(h), private_node_handle_("~"), 
00189   desired_freq_(100),
00190   freq_diag_(diagnostic_updater::FrequencyStatusParam(&desired_freq_, &desired_freq_, 0.05)   ),
00191   command_freq_("Command frequency check", boost::bind(&RbcarControllerClass::check_command_subscriber, this, _1))
00192   {
00193 
00194   ROS_INFO("rbcar_robot_control_node - Init ");
00195   
00196   ros::NodeHandle rbcar_robot_control_node_handle(node_handle_, "rbcar_robot_control");
00197 
00198   // Get robot model from the parameters
00199   if (!private_node_handle_.getParam("model", robot_model_)) {
00200           ROS_ERROR("Robot model not defined.");
00201           exit(-1);
00202           }
00203   else ROS_INFO("Robot Model : %s", robot_model_.c_str());
00204 
00205   // Ackermann configuration - traction - topics
00206 
00207 
00208   private_node_handle_.param<std::string>("frw_vel_topic", frw_vel_topic_, "/rbcar/right_front_axle_controller/command");
00209   private_node_handle_.param<std::string>("flw_vel_topic", flw_vel_topic_, "/rbcar/left_front_axle_controller/command");
00210   private_node_handle_.param<std::string>("blw_vel_topic", blw_vel_topic_, "/rbcar/left_rear_axle_controller/command");
00211   private_node_handle_.param<std::string>("brw_vel_topic", brw_vel_topic_, "/rbcar/right_rear_axle_controller/command");
00212 
00213   // Ackermann configuration - traction - joint names 
00214   private_node_handle_.param<std::string>("joint_front_right_wheel", joint_front_right_wheel, "right_front_axle");
00215   private_node_handle_.param<std::string>("joint_front_left_wheel", joint_front_left_wheel, "left_front_axle");
00216   private_node_handle_.param<std::string>("joint_back_left_wheel", joint_back_left_wheel, "left_rear_axle");
00217   private_node_handle_.param<std::string>("joint_back_right_wheel", joint_back_right_wheel, "right_rear_axle");
00218 
00219   // Ackermann configuration - direction - topics
00220   private_node_handle_.param<std::string>("frw_pos_topic", frw_pos_topic_, "/rbcar/right_steering_joint_controller/command");
00221   private_node_handle_.param<std::string>("flw_pos_topic", flw_pos_topic_, "/rbcar/left_steering_joint_controller/command");
00222 
00223   private_node_handle_.param<std::string>("joint_front_right_steer", joint_front_right_steer, "right_steering_joint"); 
00224   private_node_handle_.param<std::string>("joint_front_left_steer", joint_front_left_steer, "left_steering_joint");
00225 
00226   // Robot parameters
00227   if (!private_node_handle_.getParam("rbcar_d_wheels", rbcar_d_wheels_))
00228         rbcar_d_wheels_ = RBCAR_D_WHEELS_M;
00229   if (!private_node_handle_.getParam("rbcar_wheel_diameter", rbcar_wheel_diameter_))
00230     rbcar_wheel_diameter_ = RBCAR_WHEEL_DIAMETER;
00231   ROS_INFO("rbcar_d_wheels_ = %5.2f", rbcar_d_wheels_);
00232   ROS_INFO("rbcar_wheel_diameter_ = %5.2f", rbcar_wheel_diameter_);
00233 
00234   private_node_handle_.param("publish_odom_tf", publish_odom_tf_, true);
00235   if (publish_odom_tf_) ROS_INFO("PUBLISHING odom->base_footprint tf");
00236   else ROS_INFO("NOT PUBLISHING odom->base_footprint tf");
00237   
00238   // Robot Speeds
00239   linearSpeedXMps_   = 0.0;
00240   linearSpeedYMps_   = 0.0;
00241   angularSpeedRads_  = 0.0;
00242 
00243   // Robot Positions
00244   robot_pose_px_ = 0.0;
00245   robot_pose_py_ = 0.0;
00246   robot_pose_pa_ = 0.0;
00247   robot_pose_vx_ = 0.0;
00248   robot_pose_vy_ = 0.0;
00249   
00250   // Robot state space control references
00251   v_ref_ = 0.0;
00252   alfa_ref_ = 0.0;
00253   pos_ref_pan_ = 0.0;
00254 
00255   // Imu variables
00256   ang_vel_x_ = 0.0; ang_vel_y_ = 0.0; ang_vel_z_ = 0.0;
00257   lin_acc_x_ = 0.0; lin_acc_y_ = 0.0; lin_acc_z_ = 0.0;
00258   orientation_x_ = 0.0; orientation_y_ = 0.0; orientation_z_ = 0.0; orientation_w_ = 1.0;
00259 
00260   // Advertise controller services
00261   srv_SetOdometry_ = rbcar_robot_control_node_handle.advertiseService("set_odometry",  &RbcarControllerClass::srvCallback_SetOdometry, this);
00262 
00263   // Subscribe to joint states topic
00264   joint_state_sub_ = rbcar_robot_control_node_handle.subscribe<sensor_msgs::JointState>("/rbcar/joint_states", 1, &RbcarControllerClass::jointStateCallback, this);
00265 
00266   // Subscribe to imu data
00267   imu_sub_ = rbcar_robot_control_node_handle.subscribe("/imu_data", 1, &RbcarControllerClass::imuCallback, this);
00268 
00269   // Adevertise reference topics for the controllers 
00270   ref_vel_frw_ = rbcar_robot_control_node_handle.advertise<std_msgs::Float64>( frw_vel_topic_, 50);
00271   ref_vel_flw_ = rbcar_robot_control_node_handle.advertise<std_msgs::Float64>( flw_vel_topic_, 50);
00272   ref_vel_blw_ = rbcar_robot_control_node_handle.advertise<std_msgs::Float64>( blw_vel_topic_, 50);
00273   ref_vel_brw_ = rbcar_robot_control_node_handle.advertise<std_msgs::Float64>( brw_vel_topic_, 50);  
00274   ref_pos_frw_ = rbcar_robot_control_node_handle.advertise<std_msgs::Float64>( frw_pos_topic_, 50);
00275   ref_pos_flw_ = rbcar_robot_control_node_handle.advertise<std_msgs::Float64>( flw_pos_topic_, 50);
00276           
00277   // Subscribe to command topic
00278   cmd_sub_ = rbcar_robot_control_node_handle.subscribe<ackermann_msgs::AckermannDriveStamped>("command", 1, &RbcarControllerClass::commandCallback, this);
00279     
00280   // Publish odometry 
00281   odom_pub_ = rbcar_robot_control_node_handle.advertise<nav_msgs::Odometry>("/rbcar_robot_control/odom", 1000);
00282 
00283   // Component frequency diagnostics
00284   diagnostic_.setHardwareID("rbcar_robot_control - simulation");
00285   diagnostic_.add( freq_diag_ );
00286   diagnostic_.add( command_freq_ );
00287     
00288   // Topics freq control 
00289   // For /rbcar_robot_control/command
00290   double min_freq = RBCAR_MIN_COMMAND_REC_FREQ; // If you update these values, the
00291   double max_freq = RBCAR_MAX_COMMAND_REC_FREQ; // HeaderlessTopicDiagnostic will use the new values.
00292   
00293   subs_command_freq = new diagnostic_updater::HeaderlessTopicDiagnostic("/rbcar_robot_control/command", diagnostic_,
00294                             diagnostic_updater::FrequencyStatusParam(&min_freq, &max_freq, 0.1, 10));
00295   subs_command_freq->addTask(&command_freq_); // Adding an additional task to the control
00296   
00297   // Flag to indicate joint_state has been read
00298   read_state_ = false;
00299 }
00300 
00302 int starting()
00303 {
00304   ROS_INFO("RbcarControllerClass::starting");
00305 
00306   // Initialize joint indexes according to joint names 
00307   if (read_state_) {
00308     vector<string> joint_names = joint_state_.name;
00309     frw_vel_ = find (joint_names.begin(),joint_names.end(), string(joint_front_right_wheel)) - joint_names.begin();
00310     flw_vel_ = find (joint_names.begin(),joint_names.end(), string(joint_front_left_wheel)) - joint_names.begin();
00311     blw_vel_ = find (joint_names.begin(),joint_names.end(), string(joint_back_left_wheel)) - joint_names.begin();
00312     brw_vel_ = find (joint_names.begin(),joint_names.end(), string(joint_back_right_wheel)) - joint_names.begin();
00313     frw_pos_ = find (joint_names.begin(),joint_names.end(), string(joint_front_right_steer)) - joint_names.begin();
00314     flw_pos_ = find (joint_names.begin(),joint_names.end(), string(joint_front_left_steer)) - joint_names.begin();
00315     return 0;
00316         }
00317   else return -1;
00318 }
00319 
00321 void UpdateControl()
00322 {
00323   // Compute state control actions
00324   // State feedback error 4 position loops / 4 velocity loops 
00325   // Single steering 
00326   double d1 =0.0;
00327   double d = RBCAR_D_WHEELS_M; // divide by 2 for dual Ackermann steering
00328   double alfa_ref_left = 0.0;
00329   double alfa_ref_right = 0.0;
00330   if (alfa_ref_!=0.0) {  // div/0
00331      d1 =  d / tan (alfa_ref_);
00332      alfa_ref_left = atan2( d, d1 - 0.105);
00333      alfa_ref_right = atan2( d, d1 + 0.105);
00334      if (alfa_ref_<0.0) {
00335                 alfa_ref_left = alfa_ref_left - PI;
00336                 alfa_ref_right = alfa_ref_right - PI;
00337                 }     
00338      }
00339   else {
00340      alfa_ref_left = 0.0;
00341      alfa_ref_right = 0.0;
00342      }
00343      
00344    // Angular position ref publish
00345    std_msgs::Float64 frw_ref_pos_msg;
00346    std_msgs::Float64 flw_ref_pos_msg;
00347    std_msgs::Float64 brw_ref_pos_msg;
00348    std_msgs::Float64 blw_ref_pos_msg;
00349 
00350    flw_ref_pos_msg.data = alfa_ref_left;
00351    frw_ref_pos_msg.data = alfa_ref_right;
00352      
00353    // Linear speed ref publish (could be improved by setting correct speed to each wheel according to turning state
00354    // w = v_mps / (PI * D);   w_rad = w * 2.0 * PI
00355    double ref_speed_joint = 2.0 * v_ref_ / RBCAR_WHEEL_DIAMETER;
00356    
00357    std_msgs::Float64 frw_ref_vel_msg;
00358    std_msgs::Float64 flw_ref_vel_msg;
00359    std_msgs::Float64 brw_ref_vel_msg;
00360    std_msgs::Float64 blw_ref_vel_msg;
00361    frw_ref_vel_msg.data = -ref_speed_joint;
00362    flw_ref_vel_msg.data = -ref_speed_joint;
00363    brw_ref_vel_msg.data = -ref_speed_joint;
00364    blw_ref_vel_msg.data = -ref_speed_joint;
00365    
00366    // Publish msgs traction and direction
00367    ref_vel_frw_.publish( frw_ref_vel_msg );
00368    ref_vel_flw_.publish( flw_ref_vel_msg );
00369    ref_vel_blw_.publish( blw_ref_vel_msg );
00370    ref_vel_brw_.publish( brw_ref_vel_msg );
00371    ref_pos_frw_.publish( frw_ref_pos_msg );
00372    ref_pos_flw_.publish( flw_ref_pos_msg );
00373 }
00374 
00375 // Update robot odometry depending on kinematic configuration
00376 void UpdateOdometry()
00377 {
00378         // Get angles
00379     double a1, a2;
00380     //ROS_INFO("UpdateOdometry 1: frw_pos_:%d flw_pos_:%d blw_pos_:%d brw_pos_:%d", frw_pos_, flw_pos_, blw_pos_, brw_pos_);
00381     //ROS_INFO("UpdateOdometry 1: frw_pos_:%5.2f flw_pos_:%5.2f", 
00382         //              joint_state_.position[frw_pos_], joint_state_.position[flw_pos_])
00383     a1 = radnorm2( joint_state_.position[frw_pos_] );
00384     a2 = radnorm2( joint_state_.position[flw_pos_] );
00385 
00386     // Linear speed of each wheel [mps]
00387         double v3, v4; 
00388         v3 = joint_state_.velocity[blw_vel_] * (rbcar_wheel_diameter_ / 2.0);
00389         v4 = joint_state_.velocity[brw_vel_] * (rbcar_wheel_diameter_ / 2.0);
00390         
00391     // Turning angle front 
00392     double fBetaRads = (a1 + a2) / 2.0;
00393         
00394         // Linear speed
00395     double fSamplePeriod = 1.0 / desired_freq_;  // Default sample period    
00396     double v_mps = -(v3 + v4) / 2.0;
00397 
00398     // Compute orientation just integrating imu gyro (not so reliable with the simulated imu)
00399     // robot_pose_pa_ += ang_vel_z_ * fSamplePeriod;
00400 
00401         // Compute orientation converting imu orientation estimation
00402         tf::Quaternion q(orientation_x_, orientation_y_, orientation_z_, orientation_w_);
00403         // ROS_INFO("ox=%5.2f oy=%5.2f oz=%5.2f ow=%5.2f", orientation_x_, orientation_y_, orientation_z_, orientation_w_);
00404         tf::Matrix3x3 m(q);
00405         double roll, pitch, yaw;
00406         m.getRPY(roll, pitch, yaw);
00407         robot_pose_pa_ = yaw;
00408 
00409     // Normalize
00410     while (robot_pose_pa_ >= PI)
00411          robot_pose_pa_ -= 2.0 * PI;
00412     while (robot_pose_pa_ <= (-PI))
00413          robot_pose_pa_ += 2.0 * PI;
00414     
00415     double vx = v_mps * cos(fBetaRads) * cos(robot_pose_pa_);
00416     double vy = v_mps * cos(fBetaRads) * sin(robot_pose_pa_);
00417 
00418     // Positions
00419     robot_pose_px_ += vx * fSamplePeriod;
00420     robot_pose_py_ += vy * fSamplePeriod;
00421           
00422     // Compute Velocity (linearSpeedXMps_ computed in control
00423         robot_pose_vx_ = vx;
00424     robot_pose_vy_ = vy;
00425           
00426     // ROS_INFO("Odom estimated x=%5.2f  y=%5.2f a=%5.2f", robot_pose_px_, robot_pose_py_, robot_pose_pa_);
00427 }
00428 
00429 // Publish robot odometry tf and topic depending 
00430 void PublishOdometry()
00431 {
00432         ros::Time current_time = ros::Time::now();
00433         
00434     //first, we'll publish the transform over tf
00435     // TODO change to tf_prefix 
00436     geometry_msgs::TransformStamped odom_trans;
00437     odom_trans.header.stamp = current_time;
00438     odom_trans.header.frame_id = "odom";
00439     odom_trans.child_frame_id = "base_footprint";
00440 
00441     odom_trans.transform.translation.x = robot_pose_px_;
00442     odom_trans.transform.translation.y = robot_pose_py_;
00443     odom_trans.transform.translation.z = 0.0;
00444     odom_trans.transform.rotation.x = orientation_x_;
00445         odom_trans.transform.rotation.y = orientation_y_;
00446         odom_trans.transform.rotation.z = orientation_z_;
00447         odom_trans.transform.rotation.w = orientation_w_;
00448         
00449     // send the transform over /tf
00450         // activate / deactivate with param
00451         // this tf in needed when not using robot_pose_ekf
00452     if (publish_odom_tf_) odom_broadcaster.sendTransform(odom_trans);  
00453         
00454     //next, we'll publish the odometry message over ROS
00455     nav_msgs::Odometry odom;
00456     odom.header.stamp = current_time;
00457     odom.header.frame_id = "odom";
00458 
00459     //set the position
00460         // Position
00461     odom.pose.pose.position.x = robot_pose_px_;
00462     odom.pose.pose.position.y = robot_pose_py_;
00463     odom.pose.pose.position.z = 0.0;
00464         // Orientation
00465     odom.pose.pose.orientation.x = orientation_x_;
00466         odom.pose.pose.orientation.y = orientation_y_;
00467         odom.pose.pose.orientation.z = orientation_z_;
00468         odom.pose.pose.orientation.w = orientation_w_;
00469         // Pose covariance
00470     for(int i = 0; i < 6; i++)
00471                 odom.pose.covariance[i*6+i] = 0.1;  // test 0.001
00472 
00473     //set the velocity
00474     odom.child_frame_id = "base_footprint";
00475         // Linear velocities
00476     odom.twist.twist.linear.x = robot_pose_vx_;
00477     odom.twist.twist.linear.y = robot_pose_vy_;
00478         odom.twist.twist.linear.z = 0.0;
00479         // Angular velocities
00480         odom.twist.twist.angular.x = ang_vel_x_;
00481         odom.twist.twist.angular.y = ang_vel_y_;
00482     odom.twist.twist.angular.z = ang_vel_z_;
00483         // Twist covariance
00484         for(int i = 0; i < 6; i++)
00485                 odom.twist.covariance[6*i+i] = 0.1;  // test 0.001
00486 
00487     //publish the message
00488     odom_pub_.publish(odom);
00489 }
00490 
00492 void stopping()
00493 {}
00494 
00495 
00496 /*
00497  *      \brief Checks that the robot is receiving at a correct frequency the command messages. Diagnostics
00498  *
00499  */
00500 void check_command_subscriber(diagnostic_updater::DiagnosticStatusWrapper &stat)
00501 {
00502         ros::Time current_time = ros::Time::now();
00503 
00504         double diff = (current_time - last_command_time_).toSec();
00505 
00506         if(diff > 1.0){
00507                 stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Topic is not receiving commands");
00508                 //ROS_INFO("check_command_subscriber: %lf seconds without commands", diff);
00509                 // If no command is received, set Speed References to 0
00510                 // Turning angle can stay in the previous position.
00511                 v_ref_ = 0.0;
00512         }else{
00513                 stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Topic receiving commands");
00514         }
00515 }
00516 
00517 
00518 // Set the base velocity command
00519 // void setCommand(const geometry_msgs::Twist &cmd_vel)
00520 void setCommand(const ackermann_msgs::AckermannDriveStamped &msg)
00521 {   
00522     // Mapping - linear = v_ref_, angular = alfa_ref_ 
00523         double speed_limit = 10.0;  // m/s
00524         double angle_limit = PI/4.0;   // there should be also urdf limits
00525     v_ref_ = saturation(msg.drive.speed, -speed_limit, speed_limit);  
00526     alfa_ref_ = saturation(msg.drive.steering_angle, -angle_limit, angle_limit);
00527 }
00528 
00529 // Service SetOdometry 
00530 bool srvCallback_SetOdometry(robotnik_msgs::set_odometry::Request &request, robotnik_msgs::set_odometry::Response &response )
00531 {
00532         // ROS_INFO("rbcar_odometry::set_odometry: request -> x = %f, y = %f, a = %f", req.x, req.y, req.orientation);
00533         robot_pose_px_ = request.x;
00534         robot_pose_py_ = request.y;
00535         robot_pose_pa_ = request.orientation;
00536 
00537         response.ret = true;
00538         return true;
00539 }
00540 
00541 // Topic command
00542 void jointStateCallback(const sensor_msgs::JointStateConstPtr& msg)
00543 {       
00544   joint_state_ = *msg;
00545   read_state_ = true;
00546 }
00547 
00548 // Topic command
00549 // void commandCallback(const geometry_msgs::TwistConstPtr& msg)
00550 // void commandCallback(const ackermann_msgs::AckermannDriveStamped& msg)
00551 void commandCallback(const ackermann_msgs::AckermannDriveStamped::ConstPtr& msg)
00552 {
00553   // Safety check
00554   last_command_time_ = ros::Time::now();
00555   subs_command_freq->tick();                    // For diagnostics
00556 
00557   base_vel_msg_ = *msg;
00558   this->setCommand(base_vel_msg_);
00559 }
00560 
00561 // Imu callback
00562 void imuCallback( const sensor_msgs::Imu& imu_msg){
00563 
00564         orientation_x_ = imu_msg.orientation.x;
00565         orientation_y_ = imu_msg.orientation.y;
00566         orientation_z_ = imu_msg.orientation.z;
00567         orientation_w_ = imu_msg.orientation.w;
00568 
00569         ang_vel_x_ = imu_msg.angular_velocity.x;
00570         ang_vel_y_ = imu_msg.angular_velocity.y;
00571         ang_vel_z_ = imu_msg.angular_velocity.z;
00572 
00573         lin_acc_x_ = imu_msg.linear_acceleration.x;
00574         lin_acc_y_ = imu_msg.linear_acceleration.y;
00575         lin_acc_z_ = imu_msg.linear_acceleration.z;
00576 }
00577 
00578 double saturation(double u, double min, double max)
00579 {
00580  if (u>max) u=max;
00581  if (u<min) u=min;
00582  return u; 
00583 }
00584 
00585 double radnorm( double value ) 
00586 {
00587   while (value > PI) value -= PI;
00588   while (value < -PI) value += PI;
00589   return value;
00590 }
00591 
00592 double radnorm2( double value ) 
00593 {
00594   while (value > 2.0*PI) value -= 2.0*PI;
00595   while (value < -2.0*PI) value += 2.0*PI;
00596   return value;
00597 }
00598 
00599 bool spin()
00600 {
00601     ROS_INFO("rbcar_robot_control::spin()");
00602     ros::Rate r(desired_freq_);  // 50.0 
00603 
00604     while (!ros::isShuttingDown()) // Using ros::isShuttingDown to avoid restarting the node during a shutdown.
00605     {
00606       if (starting() == 0)
00607       {
00608             while(ros::ok() && node_handle_.ok()) {
00609           UpdateControl();
00610           UpdateOdometry();
00611           PublishOdometry();
00612           diagnostic_.update();
00613           ros::spinOnce();
00614               r.sleep();
00615           }
00616               ROS_INFO("END OF ros::ok() !!!");
00617       } else {
00618        // No need for diagnostic here since a broadcast occurs in start
00619        // when there is an error.
00620        usleep(1000000);
00621        ros::spinOnce();
00622       }
00623    }
00624 
00625    return true;
00626 }
00627 
00628 }; // Class RbcarControllerClass
00629 
00630 int main(int argc, char** argv)
00631 {
00632         ros::init(argc, argv, "rbcar_robot_control");
00633 
00634         ros::NodeHandle n;              
00635         RbcarControllerClass scc(n);
00636 
00637         // ros::ServiceServer service = n.advertiseService("set_odometry", &rbcar_node::set_odometry, &scc);
00638     scc.spin();
00639 
00640         return (0);
00641 }
00642 


rbcar_robot_control
Author(s): Roberto Guzman
autogenerated on Thu Jun 6 2019 19:55:50