0
$\begingroup$

Gazebo Answers logo

i am beginner and i wanna learn how can I use gazebo in ros. i installed gazebo 1.5.0 in synaptic.

in http://gazebosim.org/wiki/1.5/install wroted:

Only install Gazebo from here, and only follow tutorials from this website. Documentation on ros.org for Gazebo is old and not actively maintained.

and i wanna work gazebo with ros interface, but i'm confused! cus there is another tutorial for gazebo here >> http://www.ros.org/wiki/simulator_gazebo/Tutorials

what is your idea?


Originally posted by Mohsen Hk on Gazebo Answers with karma: 31 on 2013-03-20

Post score: 1

$\endgroup$

1 Answer 1

0
$\begingroup$

Gazebo Answers logo

hello. ROS simulator gazebo is outdated, use the gazebosim here wich is the one being updated and developed.

You can follow the tutorials here to learn how to use sensor data and move models and then use a plugin to send data to ROS. You will need some knowledge of ROS publishing/subscribe to topics and types of messages, but once this "bridge" is set up you can use ROS to send vel commands to your gazebo robot.

At the moment i have a robot in gazebo that sends laser scans and Pose to ROS and receives geometry_msgs/Twist (linear and angular vel) to move him around. With this i'm able to use ROS gmapping and rviz to create the maps just like in any other ROS simulation.

EDIT/UPDATE: @amit, and everyone who might find this usefull to use Gazebosim and ROS, this assumes you have done the tutorials, specialy Control model and ROS-enabled plugin. Also i'm using gazebo-1.4 and ROS fuerte.

WARNING: this is what i did, i'm not using join commands (and don't intend to for now), only set the velocity of the model, using a robot model without friction and the hokuyo model for laser, already in the gazebo models library (gazebosim.org/models). I'm almost sure that you can use the tutorial "box" (not tried it myself tho).

->If there are better ways of doing it please feel free to comment.

TYPOS: the forum feature that uses underscores "_" to set italic text is setting some parts of my answer to italic without me wanting to and removing underscores where it should not.

Be sure to get familiar with ROS messages, in this case geometry_msgs/Twist , geometry_msgs/PoseStamped (http://www.ros.org/wiki/geometry_msgs) and sensor_msgs/LaserScan (http://ros.org/wiki/sensor_msgs) and have some understanding of publishing/subscribing topics in ROS. I tried to clean, comment and remove unecessary code the best i could. Hope you get the basic ideas of how things work and then experiment on your own.

#include <boost/bind.hpp>
#include <gazebo.hh>
#include <physics/physics.hh>
#include <common/common.hh>
#include <stdio.h>

#include "ros/ros.h"
#include "geometry_msgs/Twist.h"
#include "geometry_msgs/PoseStamped.h"
#include "sensor_msgs/LaserScan.h"

#include "gazebo/gazebo.hh"
#include "gazebo/physics/physics.hh"
#include "gazebo/common/common.hh"
#include "gazebo/sensors/RaySensor.hh"
#include "gazebo/sensors/SensorManager.hh"
#include "math/Vector3.hh"
#include <math/gzmath.hh>

static float Vlin=0.0, Vang=0.0; // set as global 

namespace gazebo
{   
  class ROSModelPlugin : public ModelPlugin
  {   
    public: ROSModelPlugin()
    {
      // Start up ROS
      std::string name1 = "gz"; // this is what appears in the rostopics
      int argc = 0;
      ros::init(argc, NULL, name1);      
    }
    public: ~ROSModelPlugin()
    {
      delete this->nh;
    }

    public: void Load(physics::ModelPtr _parent, sdf::ElementPtr /*_sdf*/)
    {
      // Store the pointer to the model
      this->model = _parent;
            
      // ROS Nodehandle
      this->nh = new ros::NodeHandle("~");
      // ROS Subscriber
      this->subvel = this->nh->subscribe<geometry_msgs::Twist>("cmd_vel", 1000, &ROSModelPlugin::ROSCallback_Vel, this );

      this->nh = new ros::NodeHandle("~");
      this->pubscan = this->nh->advertise<sensor_msgs::LaserScan>("scan",1000);

      this->nh = new ros::NodeHandle("~");
      this->pubpose = this->nh->advertise<geometry_msgs::PoseStamped>("pose",1000);

//***********************************************
      sensors::SensorPtr sensor = sensors::SensorManager::Instance()->GetSensor("laser");
      if(!sensor)
        printf("sensor is NULL\n");
      this->raysensor = boost::shared_dynamic_cast<sensors::RaySensor>(sensor);
      if(!this->raysensor)
        printf("raysensor is NULL\n");
//***********************************************

      // Listen to the update event. This event is broadcast every
      // simulation iteration.
      // for gazebo 1.4 or lower it should be ConnectWorldUpdateStart
      this->updateConnection = event::Events::ConnectWorldUpdateBegin(
          boost::bind(&ROSModelPlugin::OnUpdate, this));
    }

    // Called by the world update start event
    public: void OnUpdate()
    {
      std::vector<double> rangesgz;
            static double qw,qx,qy,qz, Rrad, Prad, Yrad;

// ************* QUATERNION / POSE DATA ******************
      math::Vector3 p = model->GetWorldPose().pos;
      math::Quaternion r = model->GetWorldPose().rot;
      //from quaternion to Roll Pitch Yaw, in radianos
      qw=r.w;   qx=r.x;     qy=r.y;     qz=r.z;
      Rrad=atan2(  2*(qw*qx+qy*qz),  1-2*(qx*qx+qy*qy)  );  //Roll
      Prad=asin(2*(qw*qy-qz*qx));               //Pitch
      Yrad=atan2(  2*(qw*qz+qx*qy),  1-2*(qy*qy+qz*qz)  );  //Yaw

// ***************************************************
            ros::Time current_time, last_time;
            current_time = ros::Time::now();
            last_time = ros::Time::now();

// *********** SCAN DATA *****************************
            //Pub Scan msg
            sensor_msgs::LaserScan scan2ros;
            scan2ros.header.stamp=current_time; //ros::Time::now();
            scan2ros.header.frame_id="base_scan";
            scan2ros.angle_min=this->raysensor->GetAngleMin().Radian();
            scan2ros.angle_max=this->raysensor->GetAngleMax().Radian();
            scan2ros.angle_increment=this->raysensor->GetAngleResolution();
            scan2ros.time_increment=0.0;
            scan2ros.scan_time=0.0;
            scan2ros.range_min=this->raysensor->GetRangeMin();
            float rmn=scan2ros.range_min;
            scan2ros.range_max=this->raysensor->GetRangeMax();
            float rmx=scan2ros.range_max;
            // *********************************************
            this->raysensor->GetRanges(rangesgz);
            int raynumber=this->raysensor->GetRangeCount();
            scan2ros.ranges.resize(raynumber);
            for (int iray=0;iray<raynumber;iray++)
            {
                // i found that for some unknown reason the laser scan subtracts,
                // to each laser measure, the min range defined on the laser model
                // to "correct" this when building the scan message for ROS i add
                // that valor if the sum is not greater than max range
                float rg = this->raysensor->GetRange(iray);
                if(rg+rmn<=rmx)
                    {scan2ros.ranges[iray]=rg+rmn;}
                else {scan2ros.ranges[iray]=rmx;}
            }
            // *********************************************
            this->pubscan.publish(scan2ros);

// ******************************************
            //Pub Pose msg
            geometry_msgs::Point p2ros;
            p2ros.x=p.x; p2ros.y=p.y; p2ros.z=p.z;

            geometry_msgs::Quaternion r2ros;
            r2ros.x=r.x; r2ros.y=r.y; r2ros.z=r.z; r2ros.w=r.w;

            geometry_msgs::PoseStamped Pose2ros;
            Pose2ros.header.stamp=scan2ros.header.stamp;//ros::Time::now();
            Pose2ros.header.frame_id="base_link";
            Pose2ros.pose.position=p2ros;
            Pose2ros.pose.orientation=r2ros;

            this->pubpose.publish(Pose2ros);
            
// *********************************************** 
            //set velocities
            float velx,vely;
            velx=Vlin*cos(Yrad);
            vely=Vlin*sin(Yrad);    
            this->model->SetLinearVel(math::Vector3(velx, vely, 0));
            this->model->SetAngularVel(math::Vector3(0, 0, Vang));

// ***********************************************
            ros::spinOnce();
    }

    // callback functions run every time data is published to the topic
    void ROSCallback_Vel(const geometry_msgs::Twist::ConstPtr& msg)
    {
            Vlin=msg->linear.x;
            Vang=msg->angular.z;
    }
    
    // Pointer to the model
    private: physics::ModelPtr model;

    private: sensors::RaySensorPtr raysensor;

    // Pointer to the update event connection
    private: event::ConnectionPtr updateConnection;

    // ROS Nodehandle
    private: ros::NodeHandle* nh;
    // ROS Subscriber
    ros::Subscriber subvel;

        // ROS Publisher
        ros::Publisher pubscan;
        ros::Publisher pubpose;
        //*************

  };

  // Register this plugin with the simulator
  GZ_REGISTER_MODEL_PLUGIN(ROSModelPlugin)
}

After running a world with a robot with the plugin, in the terminal window type "rostopic list" and you should get something like:

/gz/cmd_vel

/gz/pose

/gz/scan

/rosout

/rosout_agg

now you can download ros teleop with keyboard (http://www.ros.org/wiki/teleop_twist_keyboard), first go to you ros workspace folder "$roscd" then in the terminal type:

svn co https://brown-ros-pkg.googlecode.com/svn/trunk/distribution/brown_remotelab

next edit brown_remotelab/teleop_twist_keyboard/bin/teleop_twist_keyboard.py , in line 61 replace pub = rospy.Publisher('cmd_vel', Twist) with pub = rospy.Publisher('gz/cmd_vel', Twist)

if everything is working if you run the teleop you should be able to control the model manualy.

"HOMEWORK"

furthermore, you can learn how to publish odom and tf topics (http://www.ros.org/wiki/navigation/Tutorials/RobotSetup/Odom) then use ROS gmapping (http://www.ros.org/wiki/gmapping) but with

rosrun gmapping slam_gmapping scan:=gz/scan

and use rviz to see the map.


Originally posted by GAugusto with karma: 161 on 2013-03-21

This answer was ACCEPTED on the original site

Post score: 5


Original comments

Comment by Mohsen Hk on 2013-03-21:
Hi :) tnx! i read Ros beginner level tutorials from here >> http://www.ros.org/wiki/ROS/Tutorials but now i wanna learn gazzebo first, then use ROS interface for. i find some link for next step : (http://gazebosim.org/wiki/Tutorials#Gazebo_Version_1.5) , (http://gazebosim.org/user_guide/) , (http://gazebosim.org/wiki/Main_Page) , (http://www.ros.org/wiki/gazebo) , (http://www.ros.org/wiki/simulator_gazebo) , (http://www.ros.org/wiki/simulator_gazeb). what is your idea if i wanna learn in order?

Comment by nkoenig on 2013-03-22:
The best way to learn Gazebo is to follow the tutorials (http://gazebosim.org/wiki/tutorials). Once you're ready, you can advance onto ROS plugins(http://gazebosim.org/wiki/Tutorials/1.5/ros_enabled_model_plugin)

Comment by GAugusto on 2013-03-22:
hello. i advise you start with the tutorials from gazebosim 1.5 version, then you will have a basic idea of how things work. http://gazebosim.org/wiki/Tutorials#Gazebo_Version_1.5 in between "Building a Robot" and "Plugins" go to version 1.3 (3.3 on the tutorial page) and do "Controlling a Robot" (this section is not on 1.4 and 1.5) wich will give some understanding on how to move objects/robots. then ros model plugin http://gazebosim.org/wiki/Tutorials/1.5/ros_enabled_model_plugin

Comment by Mohsen Hk on 2013-03-23:
thank you friends :)

Comment by amit on 2013-04-02:
@GAugusto Hi, You have mentioned that you have a robot in Gazebo that sends laser scans and Pose to ROS and receives geometry_msgs/Twist (linear and angular vel) to move him around. I need to do the same thing. Could you please explain a little further how did you do it ?

Comment by GAugusto on 2013-04-03:
@amit hi, i edited my answer, hope that helps. also some parts where the text is italic are missing "_" underscores and that might give the typos. saddly can't find a way around it.

Comment by logicalguy on 2013-04-03:
Hi, if there's anyone who's done ROS plugins in gazebosim in Python, please provide code/tips, etc., for people who prefer python over C++. Thanks!

Comment by amit on 2013-04-03:
Thanks GAugusto..

Comment by gazer on 2013-05-20:
Hello. I have two questions.

  1. ROS is communicated through plugin, so to control a robot , publishing force/volocity to the robot, and receive the position/sensor data, we need plugin, and we also need to write our own ROS-Node, is this true?
  2. do you recommand any resource for writing the plugin and the ROS to achieve the purposes mention in question 1?

thank you very much for your time. very appreciated!

Comment by nkoenig on 2013-05-20:
A gazebo plugin can act as a rosnode. Here is an example: https://bitbucket.org/osrf/drcsim/src/c062c14af79a529d481c07be4ec1044f2baaf7d1/ros/atlas_msgs/AtlasPlugin.cpp?at=default

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.