Up:[[Tutorial]]

----

The aim of this tutorial is to explain how to integrate SIGVerse with ROS operating system.

First, we will show how to install ROS on your operating system, then we will explain step by step how to run SIGVerse controller in ROS node and how to communicate with another node.

The ROS part tutorial is based on the official [[ROS wiki:http://www.ros.org/wiki/]], you can check it for more details.

#contents

*Overview[#ed1b8322]

In order to integrate SIGVerse and ROS, we first need to create ROS package containing two nodes, SIGVerse controller node and ROS command node.
The first node, SIGVerse controller node, will receive data from the SIGViewer as messages, then publish them on the message topic, in the other part, ROS command node reads these data and subscribe the corresponding velocity on the velocity topic, the velocity command will be retrieved by the SIGVerse controller node to be used for controlling the robot.

&ref(Simple_Ros_.PNG,,80%);


////////////////////////////////////


*Installing ROS [#ed1b8326]

To install ROS on your server please refer to the [[official web site:http://wiki.ros.org/ROS/Installation]].


**Creating ROS workspace [#ed1b8324]
In our project we are using catkin, here are the steps to follow to create a ROS workspace:

Run the following command:
 $ source /opt/ros/groovy/setup.sh

To create a catkin workspace:

 $ mkdir -p ~/catkin_ws/src
 $ cd ~/catkin_ws/src
 $ catkin_init_workspace

You can build even though no project is created yet, you just need MakeLists.txt:

 $ cd ~/catkin_ws/
 $ catkin_make

Run the setup.bash

 $ source devel/setup.bash


////////////////////////////////////


*Creating the package [#ed1b8323]
We need to create a new package in the catkin_ws directory.
// containing two nodes.

- To create a new package, go to catkin_ws:
 $ cd ~/catkin_ws/src
 $ catkin_create_pkg sig_ros

//- Create two new cpp files named sig_controller.cpp and ros_controller.cpp
// $ cd ~/catkin_ws/sig_ros/src/
// $ vim sig_controller.cpp
// $ vim ros_controller.cpp



/////////////////////////////////////////



*Download the project [#ed1b8232]

Please download the project file from here.
Please download the project file from here.~
https://github.com/SIGVerse/samples/tree/master/ROS_integration

// To download the project from GIT repository, use the following link:
// git@socio4.iir.nii.ac.jp:~/SigverseGitServer/unstable/usersContribution/tafifet/ROS_SIG_Integration.git


////////////////////////////////////////


* Compiling the project [#ed1b8353]

-After downloading the project from git, copy the "sig_ros" directory to ~/catkin_make/src.
-In "~/catkin_make/devel/lib" create a new directory named "libsig_ros" and copy the file "RobotInMove.xml"

You need to have Cmake installed on your server.

Let's edit the CMakeLists.txt file to compile the project:


Cmake parameters:

#highlight(cpp){{
 cmake_minimum_required(VERSION 2.8.3)
 project(Sigvers_Ros)
  find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs message_generation )
 ## Generate messages in the 'msg' folder
     add_message_files(
     FILES
     Velocity.msg
     )
  ## Generate added messages and services with any dependencies listed here
     generate_messages(
     DEPENDENCIES
     std_msgs
     )
  ## include libraries
  include_directories(include ${catkin_INCLUDE_DIRS})
  include_directories(/home/<username>/sigverse-2.2.0/include/sigverse/home/<username>/sigverse-2.2.0/include/sigverse/comm/controller)
}}


- These lines allow to generate the ros_controller node:

 add_executable(ros_controller src/ros_controller.cpp)
 target_link_libraries(ros_controller ${catkin_LIBRARIES})
 add_dependencies(ros_controller sig_ros_gencpp)


- These lines allow to generate the sig_controller library:

 ADD_LIBRARY(sig_ros/sig_controller src/sig_controller.cpp)
 target_link_libraries(sig_ros/sig_controller ${catkin_LIBRARIES})
 add_dependencies(sig_ros/sig_controller sig_ros_gencpp)


- To compile the package, run the following commands:
 $ cd ~/catkin_ws
 $ catkin_make

A new library will be generated in ~/catkin_ws/devel/lib/libsig_ros.


Run the following command to add this package to ROS packages:

   $source ~/catkin_ws/devel/setup.sh 



-Now let's check if our package is recognized by ROS:
 & Roscd sig_ros

We must have the following output:

 $ CMakeLists.txt include msg package.xml src


This shows that the sig_ros package exists.


////////////////////////////////////



*Testing the project [#ed1b4432]

**Running the server [#ed1b8132]

To run the server please follow the these steps:

Go to catkin_ws and and follow these steps :
 
-Run the ROS system:

 $ roscore

-Go to ~/catkin_ws/devel/lib/libsig_ros, and run the sigverse controller:

 $ cd ~/catkin_ws/devel/lib/libsig_ros
 $ sigserver.sh -w ./RobotInMove.xml


**Client side [#ed1b8131]


-Run SIGViewer and start the viewer to launch the two nodes.

-To make the robot move, click on the message button, select robot_000 as entity, and send one the following messages:
moveforward, movebackward, turnleft and turnright.


*Source Code understanding [#ed1b3329]

**SIGVerse controller node [#ed1b3669]

sig_controller.cpp


- Let’s check this file step by step 

The following is the callback function which preforms the command on the velocity of the robot’s wheels:


***Message Sender [#ed1b8136]

#highlight(cpp){{
   void SendController::poseCallback(const Sigvers_Ros::VelocityConstPtr& vel)
   {     Wheel_one =  vel->linear;
         Wheel_two =  vel->angular;
      
         printf("Velocity 1!!!  %f\n", Wheel_one);
         printf("Velocity 2!!!  %f\n", Wheel_two);
      
   }
}}

-Read from the Velocity Topic.
-Print the Velocity value applied on the robot.



***Node Initialization [#ed1b8137]

#highlight(cpp){{
  void SendController::onInit(InitEvent &evt)
   { Wheel_one = 0.0;
    Wheel_two = 0.0;
    int argc =0;
    char** argv = NULL;
    my = this->getRobotObj(this->myname());
    my->setWheel(10.0, 10.0);
    ros::init(argc, argv, "sig_controller_node"); //Initialize ROS. This allows ROS to do name remapping through the command line
                                                  // -- not important for now. This is also where we specify the name of our node.
                                                  //Node names must be unique in a running system.
    ros::NodeHandle n;                            // Create a handle to this process' node. The first NodeHandle created will actually do the initialization
                                                  // of the node, and the last one destructed will cleanup any resources the node was using.
    velocity = 1;
    chatter_pub = n.advertise<std_msgs::String>("command_message", 1);
    pose_sub    = n.subscribe<Sigvers_Ros::Velocity>("velocity_command",    1,&SendController::poseCallback,this);
    ros::Rate loop_rate(10); //A ros::Rate object allows you to specify a frequency that you would like to loop at. 
                             //It will keep track of how long it has been since the last call to Rate::sleep(),
                             //and sleep for the correct amount of time.In this case we tell it we want to run at 10hz.
   // Running the ros_command node
   system ("source ~/catkin_ws/devel/setup.sh");
   system ("rosrun sig_ros ros_controller &");
   }
}}

-In this part, we initialize the ROS node.
-Create two topics for publishing/reading data, command_message and velocity_command node.
-Launch the ros_controller node.

***Robot Controller [#ed1b8138]
#highlight(cpp){{
 double SendController::onAction(ActionEvent &evt)
 {
  my->setWheelVelocity(Weel_one,Weel_two);
  ros::spinOnce(); //
  return 1.0;
 }
}}

This function allows to control the robot using the appropriate velocity.


**ROS command node [#ed1b3779]



This is the node that controls the robot’s velocity:

ros_controller.cpp:

#highlight(cpp){{
  CommandSig::CommandSig():
   linear_(0),
   angular_(0),
   l_scale_(2.0),
   a_scale_(2.0)
   {
     nh_.param("scale_angular", a_scale_, a_scale_);
     nh_.param("scale_linear",  l_scale_, l_scale_);
     vel_pub_ = nh_.advertise<Sigvers_Ros::Velocity>("velocity_command", 1);
     mess_sub =    nh_.subscribe("command_message",100,&CommandSig::chatterCallback,this);
   }
}}

- Initialization of the command Node's Parameters 

- The Node will send velocity information using velocity_command Topic

- The Node will receive information using command_message Topic


***Main to execute the Node [#v1bef770]

#highlight(cpp){{
int main(int argc, char** argv)
  {
    ros::init(argc, argv, "ros_command_node");
    CommandSig Command_sig;
    ros::Rate loop_rate(10);
    ros::spin();
    return(0);
  }
}}

- This part starts the Sigvers_Command_node Node.


***Message Sender [#ed1b8140]

- This is the callback function which receives messages from the SIGVerse controller node and publishes the corresponding velocity to be sent to the robot on the velocity_command topic:

#highlight(cpp){{
   void CommandSig::chatterCallback (const std_msgs::String::ConstPtr& msg)
   {
    Sigvers_Ros::Velocity vel;
    if(strcmp("go",msg->data.c_str())==0)
    {
    vel.angular = 3.0;
    vel.linear = 3.0;
    vel_pub_.publish(vel);
    }
    else if(strcmp("back",msg->data.c_str())==0)
   {
    vel.angular = -3.0;
    vel.linear = -3.0;
    vel_pub_.publish(vel);
    }
    else if(strcmp("left" ,msg->data.c_str())==0)
   {
   vel.angular = 0.78;
   vel.linear = -0.78;
   vel_pub_.publish(vel);
   sleep(1.8);
   vel.angular = 0.0;
   vel.linear = 0.0;
   vel_pub_.publish(vel);
   }
   else if(strcmp("right" ,msg->data.c_str())==0)
   {
   vel.angular = -0.78;
   vel.linear = 0.78;
   vel_pub_.publish(vel);
   sleep(1.8);
   vel.angular = 0.0;
   vel.linear =  0.0;
   vel_pub_.publish(vel);
   }
   else if(strcmp("stop",msg->data.c_str())==0)
  {
   vel.angular = 0.0;
   vel.linear = 0.0;
   vel_pub_.publish(vel);
  }
 .....
 }
}}

//////////////////////////////////////////////////////

* World file [#ed1b8152]

RobotInMove.xml:

#highlight(cpp){{
 <?xml version="1.0" encoding="utf-8"?>
 <world name="myworld1">
  <gravity x="0.0" y="-980.7" z="0.0"/>
 <instanciate class="WheelRobot-nii-v1.xml" type="Robot">
    <set-attr-value name="name"           value="robot_000"/>
    <set-attr-value name="language"       value="c++"/>
    <set-attr-value name="implementation" value="./libSig_app.so"/>
    <set-attr-value name="dynamics"       value="false"/>
    <set-attr-value name="x"              value="-100.0"/>
    <set-attr-value name="y"              value="30.0"/>
    <set-attr-value name="z"              value="-130.0"/>
    <set-attr-value name="collision"      value="true"/>
    <!--stereo camera right-->
    <camera id="1"
            link="REYE_LINK"
            direction="0.0 -1.0 1.0"
            position="0.0 0.0 3.0"/>
    <!--stereo camera left-->
    <camera id="2"
            link="LEYE_LINK"
            direction="0.0 -1.0 1.0"
            position="0.0 0.0 3.0"/>
    <!--distance sensor-->
    <camera id="3"
            link="WAIST_LINK0"
            direction="0.0 1.0 0.0"
            position="0.0 -5.0 20.0"/>
    <!--monitoring camera-->
    <camera id="4"
            link="WAIST_LINK2"
            direction="0 0 1"
            quaternion="0.0 0.0 -0.966 0.259"
            position="0.0 40.0 120.0"/>
  </instanciate>
 </world>
}}

////////////////////////////////////////////////////

#counter
#highlight(end)

[[Tutorial]]

Front page   Edit Diff Backup Upload Copy Rename Reload   New List of pages Search Recent changes   Help   RSS of recent changes