single_miniq_node.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 #include <tf/transform_broadcaster.h>
00040 #include <nav_msgs/Odometry.h>                  // odom
00041 #include <geometry_msgs/Twist.h>                // cmd_vel
00042 #include <lse_sensor_msgs/Nostril.h>            // nose
00043 
00044 #include "miniQ.h"
00045 
00046 miniQ robot = miniQ();
00047 
00048 void cmdVelReceived(const geometry_msgs::Twist::ConstPtr& cmd_vel)
00049 {
00050     robot.setVelocities(cmd_vel->linear.x, cmd_vel->angular.z);
00051 }
00052 
00053 
00054 int main(int argc, char** argv)
00055 {
00056         ros::init(argc, argv, "miniq_node");
00057 
00058         ROS_INFO("miniQ for ROS - Single robot version.");
00059 
00060         ros::NodeHandle n;
00061         ros::NodeHandle pn("~");
00062     
00063         std::string port;
00064         pn.param<std::string>("port", port, "/dev/ttyUSB0");
00065         int baudrate;
00066         pn.param("baudrate", baudrate, 57600);
00067         
00068         tf::TransformBroadcaster odom_broadcaster;
00069         
00070         ros::Publisher odom_pub = n.advertise<nav_msgs::Odometry>("/odom", 50);
00071         ros::Subscriber cmd_vel_sub = n.subscribe<geometry_msgs::Twist>("/cmd_vel", 10, cmdVelReceived);
00072 
00073         ros::Publisher nose_pub = n.advertise<lse_sensor_msgs::Nostril>("/nose", 50);
00074     
00075         if(!miniQ::openPort((char*)port.c_str(), baudrate))
00076         {
00077                 ROS_FATAL("miniQ -- Failed to open serial port %s at %d baud!", port.c_str(), baudrate);
00078                 ROS_BREAK();
00079         }
00080         ROS_INFO("miniQ -- Successfully connected to the miniQ!");
00081     
00082         ros::Duration(0.5).sleep();
00083     
00084         if(!robot.checkVersion())
00085         {
00086                 ROS_FATAL("miniQ -- The firmware version of the miniQ robot is not compatible with this ROS node!");
00087                 ROS_BREAK();
00088         }
00089     
00090         ros::Time current_time;
00091         
00092         ros::Rate r(MINIQ_RATE);
00093         while(n.ok())
00094         {
00095         current_time = ros::Time::now();
00096         
00097         if(!robot.update()) ROS_WARN("miniQ -- Failed to update the data!!!");
00098         else
00099         {
00100                 double odom_x = robot.getX();
00101                 double odom_y = robot.getY();
00102                 double odom_yaw = robot.getYaw();
00103 
00104                 //ROS_INFO("Publishing data... %lf %lf %lf", odom_x, odom_y, odom_yaw);
00105                 
00106                 // Since all odometry is 6DOF we'll need a quaternion created from yaw
00107                 geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(odom_yaw);
00108                 
00109                 // First, we'll publish the transform over tf
00110                 geometry_msgs::TransformStamped odom_trans;
00111                 odom_trans.header.stamp = current_time;
00112                 odom_trans.header.frame_id = "odom";
00113                 odom_trans.child_frame_id = "base_link";
00114                 
00115                 odom_trans.transform.translation.x = odom_x;
00116                 odom_trans.transform.translation.y = odom_y;
00117                 odom_trans.transform.rotation = odom_quat;
00118                 
00119                 // Send the transform
00120                 odom_broadcaster.sendTransform(odom_trans);
00121                 
00122                 // Next, we'll publish the odometry message over ROS
00123                 nav_msgs::Odometry odom;
00124                 odom.header.stamp = current_time;
00125                 odom.header.frame_id = "odom";
00126                 
00127                 // Set the position
00128                 odom.pose.pose.position.x = odom_x;
00129                 odom.pose.pose.position.y = odom_y;
00130                 odom.pose.pose.orientation = odom_quat;
00131                 
00132                 // Set the velocity
00133                 odom.child_frame_id = "base_link";
00134                 odom.twist.twist.linear.x = robot.getLinearVelocity();
00135                 odom.twist.twist.angular.z = robot.getAngularVelocity();
00136                 
00137                 // Publish the message
00138                 odom_pub.publish(odom);
00139 
00140                 // Nose data...
00141                 lse_sensor_msgs::Nostril nose_msg; 
00142                 
00143                 nose_msg.header.stamp = current_time;
00144                 nose_msg.header.frame_id = "base_link";
00145 
00146                 nose_msg.sensor_model = "e2v MiCS 5524";
00147                 nose_msg.reading = robot.getGas();
00148                 nose_msg.min_reading = 0.0;
00149                 nose_msg.max_reading = 1.0;
00150                 nose_msg.clean_air = 0.0;
00151                 nose_msg.raw_data = robot.getRawGas();
00152 
00153                 nose_pub.publish(nose_msg);
00154         }
00155 
00156                 ros::spinOnce();
00157                 r.sleep();
00158         }
00159         
00160         return 0;
00161 }
00162 
00163 // EOF


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