Skip to content

Session 2: creating a ROS agent

Miguel Riem de Oliveira edited this page Mar 3, 2016 · 6 revisions

ROS Tutorials

First of all, make sure you completed the tutorials in the prerequisites . You may skip the python tutorials.

Select your team

Add you repository to the list of players, and pick a team. You should be able to edit the wiki so go ahead and add your player.

Getting the pose of a player

Adapting the example from here we must extend the class player with a method to read the pose of the player, i.e. the transform from the /map to the /moliveira reference frames.

#include <iostream>
#include <vector>
#include <boost/shared_ptr.hpp>
#include <ros/ros.h>
#include <tf/transform_listener.h>
#include <tf/transform_broadcaster.h> 
                                                                                                                       
using namespace std;

namespace rws2016_moliveira
{
    class Player
    {
        public:

            //Constructor with the same name as the class
            Player(string name) {this->name = name;}

            int setTeamName(int team_index = 0 /*default value*/)
            {
                switch (team_index)
                {
                    case 0: 
                        return setTeamName("red"); break;
                    case 1: 
                        return setTeamName("green"); break;
                    case 2: 
                        return setTeamName("blue");  break;
                    default: 
                        cout << "wrong team index given. Cannot set team" << endl; break;
                }
            }

            //Set team name, if given a correct team name (accessor)
            int setTeamName(string team)
            {
                if (team=="red" || team=="green" || team=="blue")
                {
                    this->team = team;
                    return 1;
                }
                else
                {
                    cout << "cannot set team name to " << team << endl;
                    return 0;
                }
            }

            //Gets team name (accessor)
            string getTeamName(void) {return team;}

           /**
             * @brief Gets the pose (calls updatePose first)
             *
             * @return the transform
             */
            tf::Transform getPose(void)
            {
                ros::Duration(0.1).sleep(); //To allow the listener to hear messages
                tf::StampedTransform st; //The pose of the player
                try{
                    listener.lookupTransform("/map", name, ros::Time(0), st);
                }
                catch (tf::TransformException ex){
                    ROS_ERROR("%s",ex.what());
                    ros::Duration(1.0).sleep();
                }

                tf::Transform t;
                t.setOrigin(st.getOrigin());
                t.setRotation(st.getRotation());
                return t;
            }

            string name; //A public atribute

        private:
            string team;
            tf::TransformListener listener; //gets transforms from the system
    };

    //Class MyPlayer extends class Player
    class MyPlayer: public Player ///Hidden for better visualization
    class Team  ///Hidden for better visualization

} //end of namespace rws2016_moliveira

int main(int argc, char** argv)
{
    //initialize ROS stuff
    ros::init(argc, argv, "player_moliveira_node");
    ros::NodeHandle node;

    //Creating an instance of class MyPlayer
    rws2016_moliveira::MyPlayer my_player("moliveira", "red");

    //Infinite loop
    ros::Rate loop_rate(10);
    while (ros::ok())
    {
        //Test the get pose method                                                                                     
        tf::Transform t = my_player.getPose();
        cout << "x = " << t.getOrigin().x() << " y = " << t.getOrigin().y() << endl;

        ros::spinOnce();
        loop_rate.sleep();
    }

    return 0;
}

Note: to compile you must add / uncomment the following lines to your CMakeLists.txt file

find_package(catkin REQUIRED COMPONENTS
  roscpp
  rospy
  std_msgs
  tf
)

## System dependencies are found with CMake's conventions
find_package(Boost REQUIRED COMPONENTS system)

and you must link your node against the catking libraries

target_link_libraries(player_moliveira_node
  ${catkin_LIBRARIES}
)

Moving my_player around

From now on, no more code to copy paste ...

Adapting the example from here extend the class MyPlayer with a method called move, which broadcasts a transform with the new position of the player.

/**
 * @brief Moves MyPlayer
 *
 * @param displacement the liner movement of the player, bounded by [-0.1, 1]
 * @param turn_angle the turn angle of the player, bounded by  [-M_PI/60, M_PI/60]
 */
 void move(double displacement, double turn_angle)
 {
 // your code here ...
 }

Note: use your name to define a local reference frame (e.g. /moliveira), and the global reference frame call it /map

Hunters and Preys

Add a my_team, hunter_team, and prey_team to the Class my_player

Create a method that computes the distance and angle to each player in the hunters/preys teams.