Skip to content

Commit

Permalink
Updated proto files for full functionality
Browse files Browse the repository at this point in the history
  • Loading branch information
joaocgreis committed Oct 26, 2014
1 parent ae9c8d1 commit 19f3066
Show file tree
Hide file tree
Showing 5 changed files with 240 additions and 8 deletions.
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@ project (RoAH_RSBB_Comm)
set(EXECUTABLE_OUTPUT_PATH ${PROJECT_BINARY_DIR}/bin)
set(LIBRARY_OUTPUT_PATH ${PROJECT_BINARY_DIR}/lib)

add_definitions("-Wall")
add_definitions("-std=c++0x")

add_subdirectory(gen/roah_rsbb_msgs/)
Expand Down
136 changes: 134 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -13,14 +13,21 @@ needed to communicate over UDP;
- A C++ header to ease the task of communicating specifically with
RoAH RSBB.

:warning: Please remember to always update right before the competitions!
```bash
cd roah_rsbb_comm_ros/
git pull
git submodule update --init --recursive
```


## Dependencies

You need to have installed a C++11 compiler, CMake, Boost, Protobuf
and OpenSSL.

If you are using Ubuntu, install the dependencies with:
```
```bash
sudo apt-get install build-essential cmake libboost-all-dev libprotoc-dev protobuf-compiler libssl-dev
```

Expand All @@ -31,7 +38,7 @@ This was tested with Ubuntu 12.04.5 LTS (Precise Pangolin) and
## Compiling

To compile, use:
```
```bash
cmake .
make
```
Expand All @@ -43,6 +50,17 @@ lib/libprotobuf_comm.a
```


## Using

You can use the proto files in any language, if you implement
communication to be compliant with protobuf_comm. Check the
documentation at http://www.robocup-logistics.org/refbox for a
full description. There is also a Java implementation available
there.

Read below to understand the proto files.


## Using roah_rsbb.h

This C++ header file provides a small decorator on top of
Expand All @@ -61,3 +79,117 @@ a way to use `PublicChannel` and `PrivateChannel` with error output
done by ROS. Include this file only if your project uses ROS.
If your project uses some other framework, you can use this file
as a base to adapt to your framework.


## Understanding the proto files

*The proto files follow the general idea of the ones in Robocup LLSF,
but adapted to the specifics of RoAH. Most notably, the idea of
having two teams is completely dropped, a private channel is open
for every robot that is participating in a benchmark.*

RSBB communication happens in two kinds of channels:
- Public channel: Used to advertise the RSBB and active robots. Only
one such channel can be active and can be used by everyone.
- Private channels: Used to communicate with a team during a
benchmark. Multiple private channels can be active if multiple
benchmarks are happening simultaneously. These channels are
encrypted using the teams private passwords.

In normal operation, the RSBB publishes `RoahRsbbBeacon` in the
public channel every second. Active team robots should publish
`RobotBeacon`, also every second.

The `RoahRsbbBeacon` contains:
- A list of robots that should be ready to start or are already
benchmarking. For each robot a port number is provided, where
it should setup its private channel.
- The state of the home automation devices and tablet application.
Note that while the output is public, the devices and tablet can
only be controlled by teams executing *Catering for Granny Annie’s Comfort*.

The `RobotBeacon` contains:
- The team name, used to identify the team.
- The robot name, used to identify the robot within the team. There
are no multi-robot benchmarks, so this is only used for identification
in the public display.
- The clock time in the moment the message is sent. This is used to
identify clock synchronization problems as soon as possible.

When a robot is expected to run a benchmark soon, a private channel
is created on the port specified by the RSBB. The RSBB will transmit
`BenchmarkState` every second. The robot should transmit
`RobotState` every second, and stop transmitting in the public channel.
When anything changes, these messages can be transmitted faster for a
while, 10 messages with a period of 50 milliseconds. Benchmark
progression is controlled by a state machine.

The `BenchmarkState` contains:
- The specific type of benchmark to run, identified by its initials.
- The state the RSBB is in (benchmark state).
- The time of the last message received from the robot, used as an
acknowledgement.
- The goal for *Object Manipulation Functionality*, only if it is the
benchmark running and the benchmark state is `GOAL_TX`.

The `RobotState` contains:
- The clock time in the moment the message is sent. This is used to
identify clock synchronization problems and acknowledgements.
- The number of messages saved as offline data. This will be displayed
by the RSBB but will not be used for anything else. Teams should set
this to the number of messages saved or any other integer that signals
that messages are being saved as offline data. This will be used to
raise a warning as soon as possible is data saving fails.
- The state the robot is in (robot state).
- Online data to be transmitted.
- Result of the *Object Perception Functionality*, only if that is
the benchmark running and the robot state is `RESULT_TX`.
- Commands for the home automation devices and tablet application,
only if the benchmark is *Catering for Granny Annie’s Comfort*.


## Understanding benchmark and robot states

The progression of the benchmark is controlled by two state machines,
one running on the RSBB controlling the benchmark state and another
running on the robot controlling the robot state. This is necessary
because the connection is unreliable and messages are likely to be
lost, so they must be retransmitted until the state is updated on the
other side.

The robot state machine should be updated when a state from the RSBB
is received, according to the following table. The top row contains
the current robot state. When the benchmark state contained in the
first column is received from the RSBB, the robot state should be
updated for the one in the table.

| | **STOP** | **PREPARING** | **WAITING_GOAL** | **EXECUTING** | **RESULT_TX** |
|-------------------:|:-------------------------:|:-----------------------:|:----------------------------------------:|:-----------------------:|:----------------------------------:|
| **STOP** | Keep <br/> `STOP` | Halt <br/> `STOP` | Halt <br/> `STOP` | Halt <br/> `STOP` | End of benchmark <br/> `STOP` |
| **PREPARE** | Prepare <br/> `PREPARING` | Keep <br/> `PREPARING` | Keep <br/> `WAITING_GOAL` | Error <br/> `STOP` | New goal <br/> `PREPARING` |
| **GOAL_TX** | Error <br/> `STOP` | Error <br/> `STOP` | Read goal and start <br/> `EXECUTING` | Keep <br/> `EXECUTING` | Keep <br/> `RESULT_TX` |
| **WAITING_RESULT** | Error <br/> `STOP` | Error <br/> `STOP` | No goal, start <br/> `EXECUTING` | Keep <br/> `EXECUTING` | Keep <br/> `RESULT_TX` |

Notice that there is no way to move to `WAITING_GOAL` or `RESULT_TX`.
This happens because these states are not reached by a command from
the RSBB but by an internal event.

| Current Robot State | Event | New Robot State |
|:-------------------:|:--------------------:|:-------------------------:|
| **PREPARING** | Preparation complete | `WAITING_GOAL` |
| **EXECUTING** | Goal complete | `RESULT_TX` |

Therefore, when the robot state is `PREPARING`, the robot should move
to the right position and prepare as needed to receive the goal. When
the robot state is `EXECUTING`, the robot should execute the goal.

For reference, the RSBB can be expected to update according to the
following transition table on its end.

| | **STOP** | **PREPARE** | **GOAL_TX** | **WAITING_RESULT** |
|-----------------:|:---------------------------------------:|:-------------------------:|:--------------------------------------:|:-----------------------------------------:|
| **STOP** | Keep or start <br/> `STOP` or `PREPARE` | Keep <br/> `PREPARE` | Retry <br/> `PREPARE` | Retry <br/> `PREPARE` |
| **PREPARING** | Error <br/> `STOP` | Keep <br/> `PREPARE` | Retry <br/> `PREPARE` | Retry <br/> `PREPARE` |
| **WAITING_GOAL** | Error <br/> `STOP` | Send goal <br/> `GOAL_TX` | Keep <br/> `GOAL_TX` | Retry <br/> `PREPARE` |
| **EXECUTING** | Error <br/> `STOP` | Retry <br/> `PREPARE` | Wait for result <br/> `WAITING_RESULT` | Keep <br/> `WAITING_RESULT` |
| **RESULT_TX** | Error <br/> `STOP` | Retry <br/> `PREPARE` | Retry <br/> `PREPARE` | New goal or end <br/> `PREPARE` or `STOP` |
24 changes: 21 additions & 3 deletions proto/BenchmarkState.proto
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@

package roah_rsbb_msgs;

import "Time.proto";

option java_package = "eu.rockin.roah_rsbb_msgs";
option java_outer_classname = "BenchmarkStateProtos";

Expand All @@ -28,9 +30,25 @@ message BenchmarkState {
MSG_TYPE = 20;
}

// The type of benchmark ([tf][123])
// The type of benchmark (HGTKMH, HWV, HCFGAC, HOPF, HOMF, HSUF)
required string benchmark_type = 1;

// The state TODO
required string benchmark_state = 2;
enum State {
STOP = 0;
PREPARE = 1;
GOAL_TX = 2;
WAITING_RESULT = 3;
}

// The state of the benchmark
required State benchmark_state = 2;

// Time in the last message received from the robot
// Items up to that message do not need to be retransmitted
optional Time acknowledgement = 3;

// HOMF: initial state of the switches, in order
repeated bool initial_state = 8;
// HOMF: switches to be toggled, by this order
repeated uint32 switches = 9;
}
36 changes: 35 additions & 1 deletion proto/RoahRsbbBeacon.proto
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@

package roah_rsbb_msgs;

import "Time.proto";

option java_package = "eu.rockin.roah_rsbb_msgs";
option java_outer_classname = "RoahRsbbBeaconProtos";

Expand All @@ -31,9 +33,41 @@ message RoahRsbbBeacon {
// The teams that should be active benchmarking
repeated BenchmarkingTeam benchmarking_teams = 1;


// Last time the bell was rung
required Time devices_bell = 10;

// State of switch 1
required bool devices_switch_1 = 11;

// State of switch 2
required bool devices_switch_2 = 12;

// State of switch 3
required bool devices_switch_3 = 13;

// State of dimmer (0-100)
required uint32 devices_dimmer = 14;

// State of blinds (0-100)
required uint32 devices_blinds = 15;


// True means the tablet should display the map
// False means it should display the call button
required bool display_map = 2;
required bool tablet_display_map = 20;

// UTC time of the last time the user used the call button on the tablet
required Time tablet_call_time = 21;

// UTC time of the last time the user selected a position on the tablet
required Time tablet_position_time = 22;

// Last user selected position on the tablet, X
required double tablet_position_x = 23;

// Last user selected position on the tablet, Y
required double tablet_position_y = 24;
}

message BenchmarkingTeam {
Expand Down
51 changes: 49 additions & 2 deletions proto/RobotState.proto
Original file line number Diff line number Diff line change
Expand Up @@ -30,11 +30,58 @@ message RobotState {
MSG_TYPE = 40;
}

// UTC time, to check clock synchronization
// UTC time, to check clock synchronization and send acknowledgements
required Time time = 1;

// Number of messages saved by the offline data saver
required uint32 messages_saved = 2;

enum State {
STOP = 0;
PREPARING = 1;
WAITING_GOAL = 2;
EXECUTING = 3;
RESULT_TX = 4;
}

// The state of the robot in the benchmark
required State robot_state = 3;

// For all repeated string fields:
// Repeated equal strings are ignored by the RSBB unless a message
// that doesn't contain the string is received in between

// HWV, HOMF: Notifications issued
repeated string notifications = 8;
// HWV: Activation event
repeated string activation_event = 9;
// HWV: Visitor
repeated string visitor = 10;

// HCFGAC: Final command given
repeated string final_command = 16;
// HCFGAC: State of switch 1
optional bool devices_switch_1 = 17;
// HCFGAC: State of switch 2
optional bool devices_switch_2 = 18;
// HCFGAC: State of switch 3
optional bool devices_switch_3 = 19;
// HCFGAC: State of dimmer (0-100)
optional uint32 devices_dimmer = 20;
// HCFGAC: State of blinds (0-100)
optional uint32 devices_blinds = 21;
// HCFGAC: True means the tablet should display the map
// False means it should display the call button
optional bool tablet_display_map = 22;

// TODO robot state
// HOPF: Object class
optional string object_class = 32;
// HOPF: Object name
optional string object_name = 33;
// HOPF: Object position, X
optional double object_pose_x = 34;
// HOPF: Object position, Y
optional double object_pose_y = 35;
// HOPF: Object position, Theta
optional double object_pose_theta = 36;
}

0 comments on commit 19f3066

Please sign in to comment.