miniq_pid_server.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2012, ISR University of Coimbra.
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of the ISR University of Coimbra nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *
00035 * Author: Gonçalo Cabrita on 20/08/2012
00036 *********************************************************************/
00037 
00038 #include <ros/ros.h>
00039 
00040 #include <dynamic_reconfigure/server.h>
00041 #include <lse_miniq_driver/miniQConfig.h>
00042 
00043 #include <lse_miniq_msgs/WheelVelocity.h>
00044 #include "miniQ.h"
00045 
00046 miniQ robot = miniQ();
00047 
00048 // Parameters
00049 bool l_s_updated;
00050 int l_s_kp, l_s_ki, l_s_kd;
00051 bool l_r_updated;
00052 int l_r_kp, l_r_ki, l_r_kd;
00053 bool r_s_updated;
00054 int r_s_kp, r_s_ki, r_s_kd;
00055 bool r_r_updated;
00056 int r_r_kp, r_r_ki, r_r_kd;
00057 
00058 bool turn_robot_off;
00059 bool run_robot;
00060 
00061 bool wheel_velocity_reference_updated;
00062 double wheel_velocity_reference;
00063 
00064 void callback(lse_miniq_driver::miniQConfig &config, uint32_t level)
00065 {
00066         if(run_robot != config.run_robot && !config.run_robot) turn_robot_off = true;
00067         else turn_robot_off = false;
00068         run_robot = config.run_robot;
00069         
00070         if(wheel_velocity_reference == config.wheel_velocities) wheel_velocity_reference_updated = false;
00071         else
00072         {
00073                 wheel_velocity_reference_updated = true;
00074                 wheel_velocity_reference = config.wheel_velocities;
00075         }
00076         if(l_s_kp == config.left_starting_kp && l_s_ki == config.left_starting_ki && l_s_kd == config.left_starting_kd) l_s_updated = false;
00077         else
00078         {
00079                 l_s_updated = true;
00080                 l_s_kp = config.left_starting_kp;
00081                 l_s_ki = config.left_starting_ki;
00082                 l_s_kd = config.left_starting_kd;
00083         }  
00084         if(l_r_kp == config.left_running_kp && l_r_ki == config.left_running_ki && l_r_kd == config.left_running_kd) l_r_updated = false;
00085         else
00086         {
00087                 l_r_updated = true;
00088                 l_r_kp = config.left_running_kp;
00089                 l_r_ki = config.left_running_ki;
00090                 l_r_kd = config.left_running_kd;
00091         }
00092         if(r_s_kp == config.right_starting_kp && r_s_ki == config.right_starting_ki && r_s_kd == config.right_starting_kd) r_s_updated = false;
00093         else
00094         {
00095                 r_s_updated = true;
00096                 r_s_kp = config.right_starting_kp;
00097                 r_s_ki = config.right_starting_ki;
00098                 r_s_kd = config.right_starting_kd;
00099         }  
00100         if(r_r_kp == config.right_running_kp && r_r_ki == config.right_running_ki && r_r_kd == config.right_running_kd) r_r_updated = false;
00101         else
00102         {
00103                 r_r_updated = true;
00104                 r_r_kp = config.right_running_kp;
00105                 r_r_ki = config.right_running_ki;
00106                 r_r_kd = config.right_running_kd;
00107         }
00108 }
00109 
00110 int main(int argc, char **argv)
00111 {
00112   ros::init(argc, argv, "miniq_pid_server");
00113 
00114   ros::NodeHandle n;
00115   ros::NodeHandle pn("~");
00116     
00117   std::string port;
00118   pn.param<std::string>("port", port, "/dev/ttyUSB0");
00119   int baudrate;
00120   pn.param("baudrate", baudrate, 57600);
00121         
00122   ros::Publisher left_pub = n.advertise<lse_miniq_msgs::WheelVelocity>("/left_wheel_velocity", 20);
00123   ros::Publisher right_pub = n.advertise<lse_miniq_msgs::WheelVelocity>("/right_wheel_velocity", 20);
00124     
00125   if(!miniQ::openPort((char*)port.c_str(), baudrate))
00126   {
00127         ROS_FATAL("miniQ -- Failed to open serial port %s at %d baud!", port.c_str(), baudrate);
00128         ROS_BREAK();
00129   }
00130   ROS_INFO("miniQ PID Server -- Successfully connected to the miniQ!"); 
00131   
00132   ros::Duration(3.0).sleep();
00133     
00134   if(!robot.checkVersion())
00135   {
00136         ROS_FATAL("miniQ PID Server -- The firmware version of the miniQ robot is not compatible with this ROS node!");
00137         ROS_BREAK();
00138   }
00139 
00140   dynamic_reconfigure::Server<lse_miniq_driver::miniQConfig> server;
00141   dynamic_reconfigure::Server<lse_miniq_driver::miniQConfig>::CallbackType f;
00142 
00143   f = boost::bind(&callback, _1, _2);
00144   server.setCallback(f);
00145 
00146   turn_robot_off = false;
00147 
00148   ros::Rate r(2.5);
00149   while(n.ok())
00150   {
00151         if(!robot.updateWheelVelocities()) ROS_ERROR("miniQ PID Server -- Failed to update the miniQ wheel velocities!!!");
00152         else
00153         {
00154                 lse_miniq_msgs::WheelVelocity right_msg;
00155                 right_msg.reference = wheel_velocity_reference;
00156                 right_msg.measured = robot.getRightWheelVelocity();
00157                 right_pub.publish(right_msg);
00158 
00159                 lse_miniq_msgs::WheelVelocity left_msg;
00160                 left_msg.reference = wheel_velocity_reference;
00161                 left_msg.measured = robot.getLeftWheelVelocity();
00162                 left_pub.publish(left_msg);
00163         }
00164 
00165         if(l_s_updated)
00166         {
00167                 l_s_updated = false;
00168                 if(!robot.setPIDGains(l_s_kp, l_s_ki, l_s_kd, miniQ::LeftStartingPID)) ROS_ERROR("miniQ PID Server -- ERROR updating left starting PID!");
00169                 ros::Duration(0.1).sleep();
00170         }
00171 
00172         if(l_r_updated)
00173         {
00174                 l_r_updated = false;
00175                 if(!robot.setPIDGains(l_r_kp, l_r_ki, l_r_kd, miniQ::LeftRunningPID)) ROS_ERROR("miniQ PID Server -- ERROR updating left running PID!");
00176                 ros::Duration(0.1).sleep();
00177         }
00178 
00179         if(r_s_updated)
00180         {
00181                 r_s_updated = false;
00182                 if(!robot.setPIDGains(r_s_kp, r_s_ki, r_s_kd, miniQ::RightStartingPID)) ROS_ERROR("miniQ PID Server -- ERROR updating right starting PID!");
00183                 ros::Duration(0.1).sleep();
00184         }
00185 
00186         if(r_r_updated)
00187         {       
00188                 r_r_updated = false;
00189                 if(!robot.setPIDGains(r_r_kp, r_r_ki, r_r_kd, miniQ::RightRunningPID)) ROS_ERROR("miniQ PID Server -- ERROR updating right running PID!");
00190                 ros::Duration(0.1).sleep();
00191         }
00192 
00193         if(turn_robot_off)
00194         {
00195                 turn_robot_off = false;
00196                 robot.setVelocities(0.0, 0.0);
00197         }
00198         else if(run_robot && wheel_velocity_reference_updated)
00199         {
00200                 wheel_velocity_reference_updated = false;
00201                 robot.setVelocities(wheel_velocity_reference, 0.0);
00202         robot.updateVelocities();
00203         }
00204         
00205         ros::spinOnce();
00206         r.sleep();
00207   }
00208   return 0;
00209 }


lse_miniq_driver
Author(s): Gonçalo Cabrita
autogenerated on Mon Jan 6 2014 11:25:52