rescue junior simplus

Select Sidearea

Robocup Junior Rescue Simulation Platform

C & CPP API

C & CPP API

C & CPP API

Sample codes

Usage

The C/C++ API consists of the following files that each will be explained here. These files are located in the Client/cpp directory.

client
|
|- player.cc (The Main player file that you should fill if you are using Ubuntu or Mac)     ** Change This **
|- player_win.cc (The Main player file that you should fill if you are using Windows)     ** Change This **
|- simplus.proto (Protobuf Message)                          ** Don't Change **
|- requirements.txt (list of requirements )                  ** Don't Change **
|- sample.py (The Sample player file that filled for you)    ** Don't Change **
|- client.py (The main python application that should run)   ** Don't Change **
|- simplus_pb2.py (Auto-generated file from the protobuf)    ** Don't Change **
|_ simplus_pb2_grpc.py (Auto-generated file from the grpc)   ** Don't Change **

Player/ Player_win:

“Player_win.cc” is the sample code for the Windows operating system and “Player.cc” is the sample code for macOS and Ubuntu. This file consists of three functions:

Start (Called at the beginning of the Game)

You Received world info that will be set in the global variables in the file and could be used later. This function should return the team name at the end of the function. World info is as follows:

  • The number of teams in the world
  • The number of Robots each team is using
  • The number of the color sensor each robot has
  • The number of proximity sensor each robot has
 char *  start(int _team_size,int _robot_per_team,int _color_sensor_size,int _proximity_sensor_size){
	team_size=_team_size;
	robot_per_team=_robot_per_team;
	color_sensor_size=_color_sensor_size;
	proximity_sensor_size=_proximity_sensor_size;
	return "my_team_name";
}

Play (Called every loop of the simulator)

You Received robot observation:

  • Information about each color sensor(the sample player is written for 3 color sensor, each color sensor return 3 values(r,g,b) in terms of an array)
  • Information about whether each proximity sensors has detected an obstacle or not in terms of 1/0. The Current robot model contains 8 proximity sensors which mean the proximity_detected array size is 8.
  • Information about the distance of each obstacle to Robot when each proximity sensor senses the obstacle in terms of the float array which each of its elements shows the correspondent value to each proximity sensor and its size is 8.
  • The Robot’s Position in (x,y,z) coordinates.

You should fill the Command values using pointers and return the Action Command :

  • Move: The Linear and Angular speed of the robot should be set in “wheel_linear” and “wheel_angular”.
  • Action: The position of the action should be set whenever an action is detected using “action_x”,”action_y” and “action_z”. In the current player sample, the “find_checkpoint” action is defined and the play function should return the Action’s name whenever an action is detected and the positions are set. Please take a look at World and Rules for more information about the Actions.
 char* play(int colors_1[],int colors_2[],int colors_3[],int proximity_detected[],float proximity_distances[],float pos[],int image_r[],int image_g[],int image_b[],int thermal[],int *led_color_id,float *wheel_linear, float *wheel_angular,float * action_x,float * action_y,float * action_z){

/*       led_color_id:  1---> red  2---> green 3---> blue 4---> off
       colors_1[]:  color sensor 1 value, colors are defined by (r,g,b), colors_1[0]-->r value  colors_1[1]-->g value colors_1[2]-->b value
       colors_2[]: color sensor 2 value, colors are defined by (r,g,b), colors_2[0]-->r value  colors_2[1]-->g value colors_3[2]-->b value
       colors_3[]: color sensor 3 value, colors are defined by (r,g,b), colors_3[0]-->r value  colors_2[1]-->g value colors_3[2]-->b value
       wheel_linear: linear velocity 
       wheel_angular: angular velocity
       proximity_distances[]: values of proximity sensor receptively, you can find the order numbers by clicking on each proximity sensor of robot model in model tree,vrep
       proximity_detected[]: the array length is equal to number of proximity sensor receptively and it's value is 0 or 1 for each proximity. 1 shows that the obstacle is detected
       pos[]: pos[0] --> x  pos[1] --> y   pos[2]--> z
       action_x: the x position of the detected action
       action_y: the y position of the detected action
       action_z: the z position of the detected action
       return char*: action name if action is detected or empty string
  image_r -> red value's of image pixels, it's a 128*128 ravel array
  image_g -> green value's of image pixels, it's a 128*128 ravel array
  image_b -> blue value's of image pixels, it's a 128*128 ravel array
thermal -> red value of the thermal camera
   */
    // Your code will be here
}

End (Called at the end of the Game)

You Can send any message you want to the server at the end of the game by just return it as a string.

char * end(){
	return  "The Ending Message";
}

Sample code

Proximity sensor

// Check if proximity sensor1 detect an obstacle that is in less than 0.3 distance from the robot. 

int check=0;
if (proximity_detected[1]==1 && proximity_distances[1]<0.3)
    check=1;

Move

// forward
 *wheel_linear = 0.05;
 *wheel_angular = 0.0;

// turn right
 *wheel_linear = 0.0;
 *wheel_angular = -0.5;

// turn left
 *wheel_linear = 0.0;
 *wheel_angular = 0.5;

Color sensor

// get red, green and blue value in range of (0,255) from color sensor
// colors_1-> center    colors_2-> left  colors_3-> right

// values of center color sensor
int red = colors_1[0];
int green = colors_1[1];
int blue = colors_1[2];

Robot position

float x =  pos[0];
float y =  pos[1];
float x =  pos[2];

Action

// 'exit' Action 

 *action_x = pos[0];
 *action_y = pos[1];
 *action_z = pos[2];
 return "exit";

Change LED state

// change the LED color to red
// 1 -> red, 2 -> green, 3 -> blue, 0 -> off

*led_color_id = 1;

Share this story:

Write a comment