Interacting with V-REP using ROS services

As a first example, we will use ROS services to start and stop the simulation scene. To do this, we must call /vrep/simRosStartSimulation and the/vrep/simRosStopSimulation services respectively. We will discuss the source code of the start_stop_scene.cpp file located in the vrep_demo_pkg/src directory:

#include "ros/ros.h" 
#include "vrep_common/simRosStartSimulation.h" 
#include "vrep_common/simRosStopSimulation.h" 
 
int main( int argc, char** argv ) { 
 
ros::init( argc, argv, "start_stop_vrep_node"); 
   ros::NodeHandle n; 
ros::ServiceClient start_vrep_client = n.serviceClient<vrep_common::simRosStartSimulation>("/vrep/simRosStartSimulation"); 
   vrep_common::simRosStartSimulation start_srv; 
 
ros::ServiceClient stop_vrep_client = n.serviceClient<vrep_common::simRosStopSimulation>("/vrep/simRosStopSimulation"); 
   vrep_common::simRosStopSimulation stop_srv; 
 
   ROS_INFO("Starting Vrep simulation..."); 
   if( start_vrep_client.call( start_srv ) ) { 
         if( start_srv.response.result == 1 ) { 
               ROS_INFO("Simulation started, wait 5 seconds before stop it!"); 
               sleep(5); 
               if( stop_vrep_client.call( stop_srv ) ) { 
                     if( stop_srv.response.result == 1 ) { 
                           ROS_INFO("Simulation stopped");      
                     } 
               } 
               else 
                     ROS_ERROR("Failed to call /vrep/simRosStopSimulation service"); 
         } 
   } 
   else 
         ROS_ERROR("Failed to call /vrep/simRosStartSimulation service"); 
} 

Let's see the explanation of the code:

ros::ServiceClient start_vrep_client = n.serviceClient<vrep_common::simRosStartSimulation>("/vrep/simRosStartSimulation"); 
vrep_common::simRosStartSimulation start_srv; 
 
ros::ServiceClient stop_vrep_client = n.serviceClient<vrep_common::simRosStopSimulation>("/vrep/simRosStopSimulation"); 
vrep_common::simRosStopSimulation stop_srv; 

Here, we declare the service client objects, as already seen in Chapter 1. These services communicate with the vrep_common::simRosStartSimulation and vrep_common::simRosStartSimulation message types respectively. These services do not require any input value, while returning the success or failure of the start/stop operation. If the start operation is executed without errors, we can stop the simulation after a certain time, as shown in the following code:

ROS_INFO("Starting Vrep simulation..."); 
if( start_vrep_client.call( start_srv ) ) { 
if( start_srv.response.result != -1 ) { 
ROS_INFO("Simulation started, wait 5 seconds before stop it!"); 
sleep(5); 
         if( stop_vrep_client.call( stop_srv ) ) { 
               if( stop_srv.response.result != -1 ) { 
                     ROS_INFO("Simulation stopped");      
               } 
         } 
         else 
               ROS_ERROR("Failed to call /vrep/simRosStopSimulation service"); 
} 
 
} 
else 
ROS_ERROR("Failed to call /vrep/simRosStartSimulation service"); 

We can now use another service, /vrep/simRosAddStatusbarMessage, to publish messages to the status bar of V-REP. We can improve the previous code with the following lines, as reported in the start_stop_scene_with_msg.cpp file:

int cnt = 0; 
while( cnt++ < 5 ) { 
std::stringstream ss; 
   ss << "Simulation while stop in " << 6-cnt << " seconds"; 
   msg_srv.request.message = ss.str(); 
   if( !msg_client.call( msg_srv ) ) { 
         ROS_WARN("Failed to call /vrep/simRosAddStatusbarMessage service");                           
   } 
   sleep(1);    
} 

Here the simRosAddStatusbarMessage service is used to display how many seconds remain before stopping the simulation. We can test this behavior by compiling and running the start_stop_scene_with_msg.cpp  node:

    $ rosrun vrep_demo_pkg start_stop_scene_with_msg

The output of this node on the V-REP window is shown in the following screenshot:

Figure 7: Messages sent to V-REP status bar via vrep_plugin