Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #include <ros/ros.h>
00039 #include <tf/transform_broadcaster.h>
00040 #include <nav_msgs/Odometry.h>
00041 #include <geometry_msgs/Twist.h>
00042 #include <lse_sensor_msgs/Nostril.h>
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
00105
00106
00107 geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(odom_yaw);
00108
00109
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
00120 odom_broadcaster.sendTransform(odom_trans);
00121
00122
00123 nav_msgs::Odometry odom;
00124 odom.header.stamp = current_time;
00125 odom.header.frame_id = "odom";
00126
00127
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
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
00138 odom_pub.publish(odom);
00139
00140
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