$search
00001 /* 00002 * Gazebo - Outdoor Multi-Robot Simulator 00003 * Copyright (C) 2003 00004 * Nate Koenig & Andrew Howard 00005 * 00006 * This program is free software; you can redistribute it and/or modify 00007 * it under the terms of the GNU General Public License as published by 00008 * the Free Software Foundation; either version 2 of the License, or 00009 * (at your option) any later version. 00010 * 00011 * This program is distributed in the hope that it will be useful, 00012 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00013 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00014 * GNU General Public License for more details. 00015 * 00016 * You should have received a copy of the GNU General Public License 00017 * along with this program; if not, write to the Free Software 00018 * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA 00019 * 00020 */ 00021 /* 00022 * Desc: Controller for diffdrive robots in gazebo. 00023 * Author: Tony Pratkanis 00024 * Date: 17 April 2009 00025 * SVN info: $Id$ 00026 */ 00027 00028 #include <gazebo/gazebo.h> 00029 #include <gazebo/GazeboError.hh> 00030 #include <gazebo/Quatern.hh> 00031 00032 #include <ros/ros.h> 00033 #include <tf/transform_broadcaster.h> 00034 #include <geometry_msgs/Twist.h> 00035 #include <nav_msgs/Odometry.h> 00036 00037 #include <boost/bind.hpp> 00038 00039 class DiffDrive { 00040 public: 00041 libgazebo::PositionIface *posIface; 00042 ros::NodeHandle* rnh_; 00043 ros::Subscriber sub_; 00044 ros::Publisher pub_; 00045 00046 void cmdVelCallBack(const geometry_msgs::Twist::ConstPtr& cmd_msg) { 00047 std::cout << " pos " << this->posIface 00048 << " x " << cmd_msg->linear.x 00049 << " y " << cmd_msg->linear.y 00050 << " z " << cmd_msg->angular.z 00051 << std::endl; 00052 00053 if (this->posIface) { 00054 this->posIface->Lock(1); 00055 this->posIface->data->cmdVelocity.pos.x = cmd_msg->linear.x; 00056 this->posIface->data->cmdVelocity.pos.y = cmd_msg->linear.y; 00057 this->posIface->data->cmdVelocity.yaw = cmd_msg->angular.z; 00058 this->posIface->Unlock(); 00059 } 00060 } 00061 00062 DiffDrive() { 00063 libgazebo::Client *client = new libgazebo::Client(); 00064 libgazebo::SimulationIface *simIface = new libgazebo::SimulationIface(); 00065 this->posIface = new libgazebo::PositionIface(); 00066 00067 int serverId = 0; 00068 00070 try { 00071 client->ConnectWait(serverId, GZ_CLIENT_ID_USER_FIRST); 00072 } catch (gazebo::GazeboError e) { 00073 std::cout << "Gazebo error: Unable to connect\n" << e << "\n"; 00074 return; 00075 } 00076 00078 try { 00079 simIface->Open(client, "default"); 00080 } catch (gazebo::GazeboError e) { 00081 std::cout << "Gazebo error: Unable to connect to the sim interface\n" << e << "\n"; 00082 return; 00083 } 00084 00086 try { 00087 this->posIface->Open(client, "robot_description::position_iface_0"); 00088 } catch (std::string e) { 00089 std::cout << "Gazebo error: Unable to connect to the position interface\n" << e << "\n"; 00090 return; 00091 } 00092 00093 // Enable the motor 00094 this->posIface->Lock(1); 00095 this->posIface->data->cmdEnableMotors = 1; 00096 this->posIface->Unlock(); 00097 00098 this->rnh_ = new ros::NodeHandle(); 00099 //this->sub_ = rnh_->subscribe<geometry_msgs::Twist>("/cmd_vel", 100, boost::bind(&DiffDrive::cmdVelCallBack,this,_1)); 00100 this->sub_ = rnh_->subscribe<geometry_msgs::Twist>("/cmd_vel", 100, &DiffDrive::cmdVelCallBack,this); 00101 this->pub_ = rnh_->advertise<nav_msgs::Odometry>("/erratic_odometry/odom", 1); 00102 00103 // spawn 2 threads by default, ///@todo: make this a parameter 00104 ros::MultiThreadedSpinner s(2); 00105 boost::thread spinner_thread( boost::bind( &ros::spin, s ) ); 00106 00107 nav_msgs::Odometry odom; 00108 00109 // setup transform publishers, need to duplicate pr2_odometry controller functionalities 00110 tf::TransformBroadcaster transform_broadcaster_ ; 00111 00112 ros::Duration d; d.fromSec(0.01); 00113 00114 while(rnh_->ok()) { 00115 if (this->posIface) { 00116 this->posIface->Lock(1); 00117 00118 // duplicate pr2_odometry functionalities, broadcast 00119 // transforms from base_footprint to odom 00120 // and from base_link to base_footprint 00121 00122 // get current time 00123 ros::Time current_time_ = ros::Time::now(); 00124 00125 // getting data for base_link to odom transform 00126 btQuaternion qt; 00127 qt.setRPY(this->posIface->data->pose.roll, this->posIface->data->pose.pitch, this->posIface->data->pose.yaw); 00128 btVector3 vt(this->posIface->data->pose.pos.x, this->posIface->data->pose.pos.y, this->posIface->data->pose.pos.z); 00129 tf::Transform base_link_to_odom(qt, vt); 00130 transform_broadcaster_.sendTransform(tf::StampedTransform(base_link_to_odom,ros::Time::now(),"odom","base_link")); 00131 00132 00133 // publish odom topic 00134 odom.pose.pose.position.x = this->posIface->data->pose.pos.x; 00135 odom.pose.pose.position.y = this->posIface->data->pose.pos.y; 00136 00137 gazebo::Quatern rot; 00138 rot.SetFromEuler(gazebo::Vector3(this->posIface->data->pose.roll,this->posIface->data->pose.pitch,this->posIface->data->pose.yaw)); 00139 00140 odom.pose.pose.orientation.x = rot.x; 00141 odom.pose.pose.orientation.y = rot.y; 00142 odom.pose.pose.orientation.z = rot.z; 00143 odom.pose.pose.orientation.w = rot.u; 00144 00145 odom.twist.twist.linear.x = this->posIface->data->velocity.pos.x; 00146 odom.twist.twist.linear.y = this->posIface->data->velocity.pos.y; 00147 odom.twist.twist.angular.z = this->posIface->data->velocity.yaw; 00148 00149 odom.header.frame_id = "odom"; 00150 00151 odom.header.stamp = ros::Time::now(); 00152 00153 this->pub_.publish(odom); 00154 00155 this->posIface->Unlock(); 00156 } 00157 d.sleep(); 00158 } 00159 } 00160 ~DiffDrive() { 00161 delete this->rnh_; 00162 } 00163 }; 00164 00165 00166 00167 00168 int main(int argc, char** argv) { 00169 ros::init(argc,argv,"gazebo_ros_diffdrive",ros::init_options::NoSigintHandler|ros::init_options::AnonymousName); 00170 00171 DiffDrive d; 00172 return 0; 00173 } 00174 00175