Kilobotics Lab Manual
Kilobotics Lab Manual
Kilobotics
Anurag (183230006)
Ponala Venkata Eswara Srisai (183230008)
Sudhakar Kumar (183236001)
Kishan Chouhan (183230015)
1 Overview of Kilobots 4
1.1 Specifications of Kilobot . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 4
1.2 Hardware/ Software Requirement . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 5
1.3 Over-head Controller . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 6
3 Orbiting of Kilobots 12
3.1 Introduction . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 12
3.2 Results and Demonstration . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 13
1
8 Conclusion 31
8.1 Acknowledgement . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 31
2
List of Figures
Overview of Kilobots
Kilobots (Figure 1.1a) are low cost robots designed at Harvard University’s Self-Organizing
Systems Research Lab http://www.eecs.harvard.edu/ssr. The robots are designed to make
testing collective algorithms on hundreds or thousands of robots accessible to robotics researchers.
Though the Kilobots are low-cost, they maintain abilities similar to other collective robots.
These abilities include differential drive locomotion, on-board computation power, neighbor-to-
neighbor communication, neighbor-to neighbor distance sensing, and ambient light sensing. Ad-
ditionally they are designed to operate such that no robot requires any individual attention by a
human operator. This makes controlling a group of Kilobots easy, whether there are 10 or 1000 in
the group.
4
– When receiving a message, distance to the transmitting Kilobot can be determined using
received signal strength. The distance depends on the surface used as the light intensity
is used to compute the value.
– The brightness of the ambient light shining on a Kilobot can be detected.
– A Kilobot can sense its own battery voltage.
• Movement: Each Kilobot has 2 vibration motors, which are independently controllable,
allowing for differential drive of the robot. Each motor can be set to 255 different power
levels. The movement happens via stick and slip mechanism
• Light: Each Kilobot has a red/green/blue (RGB) LED pointed upward, and each color has
3 levels of brightness control.
• Software: The Kilobot Controller software (kiloGUI) is available for controlling the controller
board, sending program files to the robots and controlling them.
• Programming: C language with WinAVR compiler combined with Eclipse or the online
Kilobotics editor (https://www.kilobotics.com/editor)
• Dimensions: diameter: 33 mm, height 34 mm (including the legs, without recharge antenna).
Required hardware:
• Computer with an USB port
• Kilobot robot
• Over-head controller (OHC)
• Kilobot charger
5
Required software: To start programming the Kilobot with the new version from kilobotics, we
have two solutions.
• Online editor https://www.kilobotics.com/editor.
• Install WinAVR and Eclipse to compile the whole library on your computer https://github.
com/mgauci/kilobot_notes/blob/master/eclipse_winavr_setup/eclipse_winavr_setup.
md.
We have used online editor for our labs.
Kilobots are unique in that they stay in “sleep mode” until summoned by the overhead controller.
A person can turn an entire swarm of Kilobots “ON” by sending out one signal – as opposed to
manually switching “ON” every robot.
6
Chapter 2
Establishing communication
between two Kilobots
Here, we will use the ability of two Kilobots to communicate with each other. We will allocate one
Kilobot to be the speaker and the other Kilobot to be the listener.
2.1 Speaker
The objective of this part is to broadcast a fixed message, and blink magenta when we transmit.
Here we introduce message t data structure, and the kilo message tx lback.
• A Kilobot uses IR to broadcast a message within an approximately circular radius of three
body lengths.
• Multiple robots packed closely together will interfere the IR signals. So the Kilobots use a
variant of the CSMA/CD media access control method to resolve the problems with interfer-
ence.
Carrier-sense multiple access with collision detection (CSMA/CD) is a media access control
method which uses carrier-sensing to delay transmissions until no other stations are transmit-
ting.
Step 1: Declare a variable called transmit msg of the structure type message t and add the func-
tion message tx() that returns the address of the message we declared (return & transmit msg).
Step 2: We will register this ”callback” function in the Kilobot main loop, and every time the
Kilobot is ready to send a message it will ”interrupt” the main code and call the message tx() to
get the message that needs to be sent.
A callback is any executable code that is passed as an argument to other code, which is expected
to call back the argument at a given time.
message_t transmit_msg;
message_t *message_tx() {
7
return &transmit_msg;
}
Step 3: Use the setup() function to set the initial contents of the message and compute the message
CRC value (used for error detection) through the function message crc(). The code below shows
how to initialize a simple message.
A cyclic redundancy check (CRC) is an error-detecting code which is used to detect accidental
changes to raw data.
void setup() {
transmit_msg.type = NORMAL;
transmit_msg.data[0]=0;
transmit_msg.crc = message_crc(&transmit_msg);
}
Step 4: Now we will add some more code so that we can have the LED blink whenever the robot
sends a message out. To do this we will declare a variable (often called a ”boolean flag”) called
message sent. We will set this flag inside a function called message tx success() which is another
callback function that only gets called when a message is finally successfully sent on a channel.
Then we will clear this flag in the main loop where we will blink an LED to indicate that a message
was sent.
//At the top of the file, declare a "flag" for when a message is sent
int message_sent = 0;
void message_tx_success() {
message_sent = 1;
}
Step 5: Then, in our program loop, write code to do this
Step 6: Finally, we must register our message transmission functions with the Kilobot library as
follows:
int main() {
kilo_init();
kilo_message_tx = message_tx;
8
kilo_message_tx_success = message_tx_success;
kilo_start(setup, loop);
return 0;
}
2.2 Listener
The objective of this part is to blink yellow when a new message is received and introduce the
kilo message rx callback and store incoming messages.
Step 1: First declare a variable rcvd message of type message t to store any new incoming messages
and a boolean variable called new message to indicate that a new message has been received.
int new_message = 0;
message_t rcvd_message;
9
void message_rx(message_t *msg, distance_measurement_t *dist) {
rcvd_message = *msg; //store the incoming message
new_message = 1; // set the flag to 1 to indicate that a new message arrived
}
Step 2: Check the flag in the program loop to see if a new message has arrived. If a new message
has arrived, we will blink the LED yellow, and clear the flag.
void loop() {
// Blink led yellow when you get a message
if (new_message == 1) {
new_message = 0;
set_color(RGB(1,1,0));
delay(100);
set_color(RGB(0,0,0));
}
}
Step 3: Modify our main section to register the message reception function with the Kilobot library
as follows:
int main() {
kilo_init();
kilo_message_rx = message_rx;
kilo_start(setup, loop);
return 0;
}
10
Figure 2.2: Communication between two Kilobots
According to the Kilobotics website, by default, every kilobot attempts to send message twice
per second. It can also be verified by looking at the frequency of LED blinking. The right Kilobot
acts as speaker and the left Kilobot acts as a receiver.
11
Chapter 3
Orbiting of Kilobots
3.1 Introduction
Our objective is to make one Kilobot orbit around another stationary Kilobot using distance esti-
mation. We will refer to orbiting Kilobot as planet and stationary Kilobot as star. The alogrithm
goes as follows:
12
3.2 Results and Demonstration
Star transmits the message to planet continuously while planet receives message from star and it
estimates the distance between them using the strength of received signal and then accordingly it
follows the algorithm. Following parameters have been used in this algorithm:
• DESIRED DISTANCE = 60. According to the Kilobotics website, this distance of 60mm is a
good compromise between the maximum communication range (110mm) and the minimum
distance (33mm) when two robots are touching.
• TOO CLOSE = 40. If the current distance estimate to the robot is 4cm or smaller, then the
robot is really “too close” to the star. In that case, the robot should just move forward
until the distance is no longer too close. This allows the planet robot to get to a reasonable
distance away from the star quickly and then start the orbiting. However, if the orientation
is not proper, there are chances that the planet might hit the star.
Video of working demo of problem statement can be accessed using link in figure 3.2.
We utilize the estimated distances of robot from the strength of received message to determine
which direction to move. Furthermore, this algorithm for orbiting of Kilobots can be extended to
edge-following if there is a group of stars, then the planets can orbit that group of stars. One such
scenario has been presented in the upcoming chapters, which also prevents the planet from hitting
the star.
13
Chapter 4
4.1 Introduction
In this part, our objective is to design an algorithm so that Kilobot approaches a source of light
(generated by torch light of smartphone) which may be dynamically moving with very slow speed.
The problem statement is similar to that of a line follower with just one onboard sensor [?]. The
algorithm for single sensor line follower goes as follows:
1. Check sensor position.
2. If sensor is on line, go to step 3 else step 4.
3. Move right. Go to step 5.
4. Move left.
5. Go to step 1
14
On similar lines, following a light source algorithm is implemented using flowhcart illustrated in
Figure 4.1. Above mentioned algorithm will help us understand why the robot approaches the
source of light in a zig zag fashion. We cannot do significant improvement in algorithm given the
limitation of onboard ambient light sensor to one.
Video of working demo of problem statement can be accessed using link in Figure 4.2.
Different THRESH LOW and THRESH HIGH parameters were chosen to implement hysteresis be-
haviour, thereby, precluding jittery motion. A high value of THRESH HIGH might ensure that the
Kilobot converges closer and closer to the light source. The function get ambientlight() returns
a 10-bit measurement (0 to 1023). Accordingly, the value of THRESH HIGH might be set for better
convergence towards light source.
15
Chapter 5
5.1 Introduction
Objective: Create a logical synchronous clock between different robots to allow two or more Kilo-
bots to blink an LED in unison roughly every 4 seconds
A large group of decentralized closely cooperating entities, commonly called a collective or swarm,
can work together to complete a task that is beyond the capabilities of any of its individuals [?].
Following are the three basic swarm behaviors [?] that Kilobots have mastered:
1. Foraging – It involves commanding several robots to disperse and explore the area around
them. With Kilobots, the idea is to chip away the time it takes to forage in a particular
location.
16
Figure 5.1: Algorithm for synchronizing phase of blinking LEDs
For our objective, we will use a method that relies on averaging. The algorithm for Synchronizing
robots is given in the flowchart (Figure 5.1). Each Kilobot acts as an oscillator, flashing its LED
in a fixed period P. At the same time, it continually transmits a message with its current position
in the clock period (i.e. a value between 0 and P). In the absence of any neighbors, the Kilobot
will simply blink in a fixed period, like a firefly. If the Kilobot hears neighboring Kilobots, then
it receives information about their current positions in their own periods. In order to synchronize,
17
it collects that information and uses the average to make an adjustment to its own next flashing
time. The steps can be summarized as given below:
// In Program Loop
message_t *message_tx() {
message.data[0] = kilo_ticks - last_reset; // current position in PERIOD
message.crc = message_crc(&message);
return &message;
}
Step 3: Let the Kilobot collect the messages it hears from other neighbors. By comparing the its
own current clock position to that of its neighbors (i.e. the first byte of the received message), a
Kilobot can tell how much it is out of sync with its neighbors. Each time a new message arrives,
the Kilobot will store the value of the adjustment to be made. Then, when the Kilobot completes
its own time period and flashes, it will also make one big adjustment for next time’s flash.
18
5.2 Results and Demonstration
Following parameters were used for this algorithm for synchronizing phase:
• Period = 50. We use the robot’s own clock to check time, by reading the variable kilo ticks.
One tick is equivalent to roughly 30 ms, or equivalently there are approximatly 32 clock ticks
every second.
• RESET TIME ADJUSTMENT DIVIDER = 120. It affects the size of the reset time adjustment for
every discrepancy with a neighbor. A larger value means smaller adjustments. Hence, this
value should increase with the average number of neighbors each robot has.
Video of working demo of problem statement can be accessed using link in Figure 5.2.
19
Chapter 6
20
6.2 Flowchart
Flowchart for orbit after escape algorithm has been divided into two parts comprising of Figure
6.1 and 6.2. First part discusses extension of orbit algorithm for multiple star setting whereas the
latter illustrates the algorithm for escaping obstacle.
In star planet orbiting algorithm, while measuring distance between stars and planet, the param-
eter NUMBER COMMUNICATION defines how many messages should a planet aggregate before making
a decision. Accordingly, planet identifies the nearest star based on the strength of signal received
in previous step. Considering the nearest star, the planet either moves left or right to maintain
DESIRED DISTANCE. The parameter message rx status is used to keep count of successful commu-
nications.
21
22 after escape algorithm (Part II)
Figure 6.2: Flowchart for orbiting
The parameter NUMBER COMMUNICATION affects speed of the planet. For instance, if the number
of stars in communication range is more, the planet moves faster than having only one star in
communication range. This is due to the fact that it needs to receive NUMBER COMMUNICATION times
of measurements from only one star and then, decides the motion. Here are two observations, which
show how the revolution time is getting varied with the number of communications:
• Motor delay = 200, Number of communications = 4, Revolution time = 23 minutes
• Motor delay = 500, Number of communications = 2, Revolution time = 5 minutes
While escaping from TOO CLOSE region, we compare the successive distance measurements to
check for the orientation of planet from star. In our early version of algorithm, we tried to de-
tect transition of distance from increasing to decreasing state as the instant when planet is
oriented away from star but becase of uncertainity in measurements, this led to unwanted be-
haviour. Hence, we decided to keep track of minimum distance from star and check for the con-
dition distance - min distance > THRESHOLD ROTATE to hold. By appropriately choosing the
parameter THRESHOLD ROTATE, we managed to get the final orientation of planet away from di-
rection of star. Moreover, the modified algorithm sans over-dependence on accuracy of a single
measurement, leading to filter like behaviour and an eventual robustness of solution.
It is worth mentioning that the robustness comes at an additional cost, which is, in worst case
scenario, planet would require one complete revolution before being able to escape from TOO CLOSE
region of star. For more detailed understanding of algorithm, readers are referred to code in Ap-
pendix A.
23
We have hard delays in our current implementation which increases the revolution time. In
future, one can replace them with soft delays to alleviate the time of revolution.
The caption of figure 6.4 provides link to the demonstration of algorithm for planet to go away
from too close region, which involves using a robust algorithm followed by orbiting.
Figure 6.4: Escaping too close region of star by planet followed by orbiting
It is evident from the demonstration that there is a damped oscillation before planet starts
orbiting. This can be attributed to difference in centre of rotation of kilobots for clockwise and
anti-clockwise turn. If it were to rotate about its centre, the oscillations would not have been as
heightened as in current scenario.
The caption of figure 6.5 provides link to the demonstration of algorithm for planet to orbit
around two stars. In this case, only one communication was used to identify minimum distance,
leading to instability which can be attributed to CSMA/CD [?] communication protocol followed
by Kilobots.
24
Figure 6.5: Orbiting of planet around two stars using single communication to estimate minimum
distance leads to instability
The caption of figure 6.6 provides link to the demonstration of algorithm for planet to orbit
around two stars where planet uses two communications to make a descision (estimating the mini-
mum distance).
Figure 6.6: Orbiting of planet around two stars using two communications to estimate minimum
distance
The caption of figure 6.7 provides link to the demonstration of algorithm for planet to orbit
around three stars forming a triangle. In this case, planet uses four communications to make a
decision. Though these four communications stabilize the movement of planet, it also increases the
total revolution time.
25
Figure 6.7: Orbiting of planet around three stars using four communications to estimate minimum
distance
6.4 Conclusion
We implemented a robust algorithm for star-planet orbiting by using the concepts of FSM. This
algorithm was able to prevent planet from hitting the star, even if the planet starts in the very close
region of the star. Also, we observed that the movement of a planet can be stabilized by increasing
the number of communications from the star. However, it will also increase the total revolution
time. Also, the orientation of planets and star played a significant role. If the orientation of the
planet is away from that of a star, it might take an additional turn before it begins orbiting.
26
Chapter 7
In this chapter, we will discuss an algorithm motivated by the work [?] of SSL lab, Harvard Uni-
versity, for shape formation. Rather than implementing the entire algorithm, we will only consider
a portion of it, assuming that the next robot to be placed is available near origin.
7.1 Framework
• Three robots (guides) are used as reference for axis orientation.
• A robot (builder) participating in shape formation starts near the left of origin.
• In its effort to reach the desired location, builder orbits around the partial shape using the
algorithm presented in last chapter.
• The builder stops orbiting when it reaches the desired location.
• Builder becomes a guide, thereby, helping the next builder.
To participate in shape formation, builders need to decide upon what global shape to form. This
is achieved by sharing a shape matrix encapsulating the desired shape as an array of 5-tuple. The
5-tuple contains the following information necessary for establishing builders at desired location:
Index N eighbour1 Desired distance1 N eighbour2 Desired distance2 (7.1)
For forming a linear shape of width 2, the shape matrix would look like
3 1 1 2 √1
4 2 1 3 2
5
(7.2)
3 1 4 1
··· ··· ··· ··· ···
It is important to note that we require the shape to ensure two guides for each builder node or else
builder would fail to localize correctly.
27
7.2 Flowchart
Figure 7.1 explains the algorithm for shape formation. Our algorithm differs from [?] in its imple-
mentation of shape matrix, and localization to be discussed later in next section.
7.3 Discussion
Figure 7.2 and 7.3 helps in visualizing the shape formation process for shape matrix (7.2), which
corresponds to a line of width 2. Black circles indicate guide robots which continuously transmit
their Index, whereas grey circles indicate the oncoming builder robot. Shaded circle corresponds to
28
a builder transforming into a guide. A builder is always in listener mode, whereas a guide is always
in speaker mode of communication. Dotted lines trace the path of builder.
When first builder initialized with Index=3 starts its journey, as shown in Figure 7.2, it never
faces a situation which requires Index update and hence, it ultimately reaches the desired location
corresponding to Index=3 and transforms into a guide robot.
When second builder arrives with Index=3, as n in Figure 7.3, it continues on its journey to
occupy the desired location coresponding to Index=3, but when it comes in the communication
range of new guide with Index=3, it realizes that it needs to update its Index to 4. Following
which, it travels to the desired location corresponding to Index=4 and transforms into a guide.
7.4 Demonstration
EPSILON MARGIN and MOTOR ON DURATION plays an essential role in determining the stability and
accuracy of shape formation. For large MOTOR ON DURATION, it is likely for builder to go beyond
its desired location and continue orbiting whereas for larger EPSILON MARGIN, we get distortion in
29
shape. Moreover, we can not choose very small EPSILON MARGIN due to error in measurements. One
way to improve accuracy of shape is by adaptively decreasing the MOTOR ON DURATION of builder
when it comes in the comunication range of desired neighbours. The two parameters discussed
are borrowed from previous chapter. For detailed understanding of these parameters, readers are
motivated to go through code in Appendix B
Figure 7.4 provides the link to video of shape formation in action. Shape matrix (7.2) was fed
to each builder robots to form a rectangle breadth=2 and length=3. Values for EPSILON MARGIN
and MOTOR ON DURATION were assigned to 5 and 500 respectively. For abovementioned values of
parameters, the desired shape formation took place in roughly 10 minutes with observable dis-
tortions in shape. As the shape becomes larger and larger, accumulations of these errors could
prevent a builder from localization, given our naive implementation of the algorithm. We also ex-
perimented with smaller values of EPSILON MARGIN, namely 2, but because of measurement noise,
builders failed to establish themselves at desired location with large probability and continued or-
biting around guides. Same observations were made for large values of MOTOR ON DURATION, namely
1000, as we had implemented hard delays. Although, larger values decreased the time to reach near
the desired region, builders failed to localize within desired error margin. This could be attributed
to large displacement being made before every localization step.
Figure 7.4: Shape formation by kilobots (Shape: Rectangle of breadth=2 and length=3)
Based on our discussion, inclusion of following measures would boost the performance:
• Adaptively decreasing the MOTOR ON DURATION as the builder reaches closer to its target lo-
cation. Doing this would significantly improve the runtime of shape formation and accuracy
of localization if calibrated with proper choice of EPSILON MARGIN.
• Conversion of hard delays to soft delays, thereby, decreasing the overall run time.
• Use of optimization based approach for localization to incorporate uncertainity in measure-
ments.
30
Chapter 8
Conclusion
During our lab work on Kilobotics, we developed essential building blocks for implementation of
shape formation algorithm. In the process, we tested algorithms for efficient orbiting, algorithm
for escaping an obstacle, algorithm for orbiting multiple stars, and lastly, we also implemented a
rudimentary shape formation algorithm for Kilobots. There’s a lot which needs to be achieved in
terms of robustness in performance and integration of individual building blocks. Further, one may
also pursue development of macros to generate shape matrix from a bitmap image.
8.1 Acknowledgement
We would like to thank Tejdeep Reddy for his teaching assistance and lab staffs for maintaining
a healthy number of working robots. Moreover, we would like to thank Prof. Leena Vachhani for
her coursework on Automation and Feedback which motivated us to approach the problem using
finite state machine. Lastly, thanks to Prof. Leena Vachhani, Prof. Arpita Sinha and Adwaith
Vijayakumar for their generous coperation in preponing our presentation dates.
31
Appendix A
32
29 # define FINISH 12
30
31 // ----- VARIABLE DECLARATION -----
32 int state , last_state , distance , last_distance , message_rx_status ,
min_distance , temp ;
33 message_t message ;
34
35 void measure_distance ()
36 {
37 mess age_rx _stat us =0;
38 }
39
40 message_t * message_tx ()
41 {
42 return & message ;
43 }
44
45 // ----- ROUTINE FOR RECEPTION -----
46 void message_rx ( message_t *m , d i s t a n c e _ m e a s u r e m e n t _ t * d )
47 {
48 if ( me ssage_ rx_sta tus == 0)
49 {
50 distance = 1000;
51 }
52 if ( me ssage_ rx_sta tus != N U M B E R _ C O M M U N I C A T I O N )
53 {
54 temp = es timate _dista nce ( d ) ;
55 if ( temp < distance )
56 {
57 distance = temp ;
58 }
59 mess age_rx _statu s ++;
60 }
61 }
62
63 // ----- ROUTINE FOR MOTION -----
64 void move ( int direction )
65 {
66 switch ( direction )
67 {
68 case FORWARD :
69 spinup_motors () ;
70 set_motors ( kilo_straight_left , k i l o_ s t ra i g ht _ r ig h t ) ;
71 delay ( MOTOR _ON_DU RATION ) ;
72 set_motors (0 , 0) ;
73 break ;
33
74 case LEFT :
75 spinup_motors () ;
76 set_motors ( kilo_straight_left , 0) ;
77 delay ( MOTOR _ON_DU RATION ) ;
78 set_motors (0 , 0) ;
79 break ;
80 case RIGHT :
81 spinup_motors () ;
82 set_motors (0 , k i l o_ s t ra i g ht _ r ig h t ) ;
83 delay ( MOTOR _ON_DU RATION ) ;
84 set_motors (0 , 0) ;
85 break ;
86 }
87 }
88
89 void setup ()
90 {
91 // ----- RESET FINITE STATE MACHINE -----
92 state = MEASURE_DISTANCE ;
93 set_color ( RGB (0 ,0 ,1) ) ;
94 }
95
96 void loop ()
97 {
98 switch ( state )
99 {
100 case MEASURE_DISTANCE :
101 // ----- INITIATE RECEPTION -----
102 mes sage_r x_stat us = 0;
103 state = WAIT ;
104 break ;
105 case WAIT :
106 if ( mes sage_r x_sta tus == N U M B E R _ C O M M U N I C A T I O N )
107 {
108 state = D I S T A N C E _ C H E C K _ O R B I T ;
109 }
110 break ;
111 case D I S T A N C E _ C H E C K _ O R B I T :
112 // ----- CHECK THE REGION OF PLANET -----
113 if ( distance < T OO _C LO SE _D IS TA NC E )
114 {
115 state = TOO_CLOSE ;
116 min_distance = distance ;
117 }
118 else
119 {
34
120 if ( distance > DESIRED_DISTANCE )
121 {
122 state = G R E A T E R _ T H A N _ D E S I R E D ;
123 }
124 else
125 {
126 state = S M A L L E R _ T H A N _ D E S I R E D ;
127 }
128 }
129 break ;
130 case TOO_CLOSE :
131 set_color ( RGB (1 ,0 ,0) ) ;
132 move ( LEFT ) ;
133 state = MEASURE_AGAIN ;
134 break ;
135 case MEASURE_AGAIN :
136 mes sage_r x_stat us = 0;
137 state = WAIT_AGAIN ;
138 break ;
139 case WAIT_AGAIN :
140 if ( mes sage_r x_sta tus == N U M B E R _ C O M M U N I C A T I O N )
141 {
142 state = U P D A T E _ M I N I M U M _ D I S T A N C E ;
143 }
144 break ;
145 case U P D A T E _ M I N I M U M _ D I S T A N C E :
146 // ----- UPDATE MINIMUM DISTANCE WHILE TRYING TO ESCAPE
THE OBSTACLE -----
147 if ( distance < min_distance )
148 {
149 min_distance = distance ;
150 }
151 // ----- CHECK IF PLANET IS ORIENTED AWAY FROM OBSTACLE
-----
152 if ( distance - min_distance > THRESHOLD_ROTATE )
153 {
154 state = TOO_CLOSE_ESCAPE ;
155 }
156 else
157 {
158 state = TOO_CLOSE ;
159 }
160 break ;
161 case TOO_CLOSE_ESCAPE :
162 // ----- CHECK IF PLANET IS NEAR THE ORBITING DISTANCE
-----
35
163 if ( distance > DESIRED_DISTANCE - EPSILON_MARGIN )
164 {
165 state = MEASURE_DISTANCE ;
166 }
167 else
168 {
169 move ( FORWARD ) ;
170 state = MEASURE_ESCAPE ;
171 }
172 break ;
173 case MEASURE_ESCAPE :
174 mes sage_r x_stat us = 0;
175 state = WAIT_ESCAPE ;
176 break ;
177 case WAIT_ESCAPE :
178 if ( mes sage_r x_sta tus == N U M B E R _ C O M M U N I C A T I O N )
179 {
180 state = TOO_CLOSE_ESCAPE ;
181 }
182 break ;
183 case G R E A T E R _ T H A N _ D E S I R E D :
184 // ----- ROUTINE FOR CLOCKWISE ORBITING -----
185 move ( RIGHT ) ;
186 set_color ( RGB (0 ,1 ,0) ) ;
187 state = MEASURE_DISTANCE ;
188 break ;
189 case S M A L L E R _ T H A N _ D E S I R E D :
190 // ----- ROUTINE FOR CLOCKWISE ORBITING -----
191 move ( LEFT ) ;
192 set_color ( RGB (1 ,0 ,0) ) ;
193 state = MEASURE_DISTANCE ;
194 break ;
195 default :
196 break ;
197 }
198 last_state = state ;
199 }
200
201
202
203 int main ()
204 {
205 kilo_init () ;
206 // ----- INITIALIZE RECEPTION -----
207 kilo_message_rx = message_rx ;
208 kilo_start ( setup , loop ) ;
36
209
210 return 0;
211 }
37
Appendix B
38
28 float re ce pt io n_ di st an ce [3] = {0 ,0 ,0};
29
30 // ----- SHAPE MATRIX -----
31 int neighbours [8][2] =
{{0 ,0} ,{0 ,0} ,{0 ,0} ,{1 ,2} ,{2 ,3} ,{3 ,4} ,{4 ,5} ,{5 ,6}};
32 float d i st a n ce _ m u lt i p li e r [8][2] = {{0 ,0} , {0 ,0} , {0 ,0} , {1 ,1} ,
{1 ,1.4} , {1 ,1} , {1 ,1.4} ,{1 ,1}};
33
34 message_t * message_tx ()
35 {
36 return & message ;
37 }
38
39 // ----- ROUTINE FOR TRANSMISSION -----
40 void m es sa ge _t x_ su cc es s ()
41 {
42 message_sent = 1;
43 set_color ( RGB (1 , 0 , 1) ) ;
44 delay (100) ;
45 set_color ( RGB (0 , 0 , 0) ) ;
46 }
47
48 // ----- ROUTINE FOR RECEPTION -----
49 void message_rx ( message_t *m , d i s t a n c e _ m e a s u r e m e n t _ t * d )
50 {
51 if ( me ssage_ rx_sta tus == 0)
52 {
53 distance = 1000;
54 }
55 if ( me ssage_ rx_sta tus != N U M B E R _ C O M M U N I C A T I O N )
56 {
57 temp = es timate _dista nce ( d ) ;
58 // ----- CALCULATE MINIMUM DISTANCE -----
59 if ( temp < distance )
60 {
61 distance = temp ;
62 }
63 // ----- STORE RECEPTION ID -----
64 reception_id [ me ssage_ rx_sta tus ] = (* m ) . data [0];
65 // ----- MAXIMUM INDEX IN CURRENT COMMUNICATION -----
66 if ( reception_id [ me ssage_ rx_sta tus ] > max_index )
67 {
68 max_index = reception_id [ messa ge_rx_ status ];
69 }
70 // ----- STORE RECEPTION DISTANCE -----
71 re ce pt io n_ di st an ce [ messa ge_rx_ status ] = temp ;
39
72 mess age_rx _statu s ++;
73 }
74 }
75
76 void measure_distance ()
77 {
78 mess age_rx _stat us =0;
79 }
80
81 // ----- ROUTINE FOR MOTION -----
82 void move ( int direction )
83 {
84 switch ( direction )
85 {
86 case FORWARD :
87 spinup_motors () ;
88 set_motors ( kilo_straight_left , k i l o_ s t ra i g ht _ r ig h t ) ;
89 delay ( MOTOR _ON_DU RATION ) ;
90 set_motors (0 , 0) ;
91 break ;
92 case LEFT :
93 spinup_motors () ;
94 set_motors ( kilo_straight_left , 0) ;
95 delay ( MOTOR _ON_DU RATION ) ;
96 set_motors (0 , 0) ;
97 break ;
98 case RIGHT :
99 spinup_motors () ;
100 set_motors (0 , k i l o_ s t ra i g ht _ r ig h t ) ;
101 delay ( MOTOR _ON_DU RATION ) ;
102 set_motors (0 , 0) ;
103 break ;
104 default :
105 break ;
106 }
107 }
108
109 void setup ()
110 {
111 // ----- RESET FINITE STATE MACHINE -----
112 state = N E IG H B OU R S _I N _ R AN G E ;
113 set_color ( RGB (0 ,0 ,1) ) ;
114 }
115
116 void loop ()
117 {
40
118 switch ( state )
119 {
120 case N EI G H BO U R S_ I N _R A N GE :
121 state = C O M P A R E _ D E S I R E D _ D I S T A N C E ;
122 // ----- INITIATE RECEPTION -----
123 mes sage_r x_stat us = 0;
124 break ;
125 case C O M P A R E _ D E S I R E D _ D I S T A N C E :
126 if ( mes sage_r x_sta tus == N U M B E R _ C O M M U N I C A T I O N )
127 {
128 for ( int i =0; i < N U M B E R _ C O M M U N I C A T I O N ; i ++)
129 {
130 for ( int j = i +1; j < N U M B E R _ C O M M U N I C A T I O N ; j ++)
131 {
132 // ----- CHECK IF DESIRED NEIGHBOURS IN
RANGE -----
133 if ( reception_id [ i ] == neighbours [ index ][0]
&& reception_id [ j ] ==
neighbours [ index ][1])
134 {
135 x = i;
136 y = j;
137 check = 1;
138 break ;
139 }
140 }
141 if ( check == 1)
142 {
143 break ;
144 }
145 }
146
147 // ----- CHECK IF DESIRED NEIGHBOURS AT DESIRED
DISTANCE -----
148 if (( check == 1) && ( r ec ep ti on _d is ta nc e [ x ] >
d i st a n ce _ m ul t i pl i e r [ index ][0] * DESIRED_DISTANCE
- EPSILON_MARGIN && r ec ep ti on _d is ta nc e [ x ] <
d i st a n ce _ m ul t i pl i e r [ index ][0] *
DESIRED_DISTANCE + EPSILON_MARGIN ) &&
( re ce ptio n_ di st an ce [ y ] >
d i st a n ce _ m ul t i pl i e r [ index ][1] *
DESIRED_DISTANCE - EPSILON_MARGIN &&
r ece pt io n_ di st an ce [ y ] <
d i st a n ce _ m ul t i pl i e r [ index ][1] * DESIRED_DISTANCE
+ EPSILON_MARGIN ) )
149 {
41
150 state = FINISH ;
151 }
152 else
153 {
154 state = O R B I T _ A N D _ U P D A T E _ I N D E X ;
155 }
156 }
157 break ;
158 case O R B I T _ A N D _ U P D A T E _ I N D E X :
159 // ----- ALGORITHM FOR ORBITING CLOCKWISE -----
160 if ( distance > DESIRED_DISTANCE )
161 {
162 set_color ( RGB (1 ,0 ,0) ) ;
163 move ( RIGHT ) ;
164 state = N E I GH B O UR S _ IN _ R AN G E ;
165 }
166 else
167 {
168 set_color ( RGB (0 ,0 ,1) ) ;
169 move ( LEFT ) ;
170 state = N E I GH B O UR S _ IN _ R AN G E ;
171 }
172 // ----- UPDATE INDEX IF REQUIRED -----
173 if ( max_index +1 > index )
174 {
175 index = max_index +1;
176 }
177 break ;
178 case FINISH :
179 set_color ( RGB (0 ,1 ,0) ) ;
180 // ----- START TRANSMISSION AFTER DESIRED LOCATION IS
ACHIEVED -----
181 message . type = NORMAL ;
182 message . data [0] = index ;
183 message . crc = message_crc (& message ) ;
184 kilo_message_tx = message_tx ;
185 k i l o _ m e s s a g e _ t x _ s u c c e s s = me ss ag e_ tx _s uc ce ss ;
186 state = INFINITY ;
187 break ;
188 case INFINITY :
189 break ;
190 default :
191 break ;
192 }
193 }
194
42
195 int main ()
196 {
197 kilo_init () ;
198 // ----- INITIALIZE RECEPTION -----
199 kilo_message_rx = message_rx ;
200 kilo_start ( setup , loop ) ;
201 return 0;
202 }
43