Statistics
| Branch: | Revision:

root / scout_avr / src / main.cpp @ 2853d46b

History | View | Annotate | Download (4.62 KB)

1
#if 1 ///////////////////////////////////////////////
2

    
3
#include "ros.h"
4
#include "bom.h"
5
#include "range.h"
6
#include "stepper.h"
7
#include <std_msgs/Int16.h> // TODO remove
8
#include <bom/bom.h>
9
#include <sonar/sonar_distance.h>
10
#include <sonar/sonar_toggle.h>
11
#include <sonar/sonar_set_scan.h>
12
#include <util/delay.h>
13

    
14
/* Period of main loop in ms */
15
#define MAINLOOP_PERIOD 100//50
16

    
17
char range_enabled = 0;
18

    
19
void debug(const char *str)
20
{
21
}
22

    
23
void callback(const std_msgs::Int16& msg)
24
{
25
}
26

    
27
/* dammit, Priya, this capitalization just looks ridiculous */
28
void range_toggle_cb(const sonar::sonar_toggleRequest& req,
29
    sonar::sonar_toggleResponse& resp)
30
{
31
  range_enabled = req.set_on;
32
  resp.ack = true;
33
}
34

    
35
void range_set_scan_cb(const sonar::sonar_set_scanRequest& req,
36
    sonar::sonar_set_scanResponse& resp)
37
{
38
  step_sweep_bounds(req.stop_l, req.stop_r);
39
  resp.ack = true;
40
}
41

    
42
int main()
43
{
44
  unsigned long now, next;
45
  unsigned int ranges[2];
46
  char i, id;
47

    
48
  ros::NodeHandle nh;
49
  nh.initNode();
50

    
51
  /* To be removed later; just an example of a subscirber */
52
  ros::Subscriber<std_msgs::Int16> test_in("test_in", callback);
53
  nh.subscribe(test_in);
54

    
55
  /* Stepper */
56
  // TODO ROS messages to set bounds
57
  step_init();
58
  step_dir(1);
59
  step_set_size(STEP_WHOLE);
60
  step_sweep_bounds(-26, 26);
61

    
62
  /* Range */
63
  range_init();
64
  sonar::sonar_distance range_msg;
65
  ros::Publisher range_pub("sonar_distance", &range_msg);
66
  ros::ServiceServer
67
    <sonar::sonar_toggleRequest, sonar::sonar_toggleResponse>
68
    range_toggle("sonar_toggle", range_toggle_cb);
69
  ros::ServiceServer
70
    <sonar::sonar_set_scanRequest, sonar::sonar_set_scanResponse>
71
    range_set_scan("sonar_set_scan", range_set_scan_cb);
72
  nh.advertise(range_pub);
73

    
74
  /* BOM */
75
  bom_init();
76
  bom::bom bom_msg;
77
  ros::Publisher bom_pub("bom", &bom_msg);
78
  nh.advertise(bom_pub);
79

    
80
  id = 0;
81
  next = 0;
82
  while (1)
83
  {
84
    nh.spinOnce();
85

    
86
    /* Skip loop if the loop period hasn't passed yet */
87
    /* TODO if we need more exact timing, we can enter a tight loop when now
88
     * gets close to next, and avoid the uncertainty of nh.spinOnce() */
89
    now = nh.getHardware()->time();
90
    if (now < next) {
91
      continue;
92
    }
93
    next = now + MAINLOOP_PERIOD;
94

    
95
    /* Temporary, for BOM testing */
96
    id++;
97
    if (id == 0x40) {
98
      id = 0;
99
    }
100
    set_robot_id(id);
101
    bom_send(id & 1);
102

    
103
    /* BOM */
104
    for (i = 0; i < 4; i++) {
105
      int msg = bom_get(i);
106
      if (msg != BOM_NO_DATA) {
107
        bom_msg.sender = bom_msg_get_robot_id(msg);
108
        bom_msg.send_dir = bom_msg_get_dir(msg);
109
        bom_msg.recv_dir = i;
110
        bom_pub.publish(&bom_msg);
111
      }
112
    }
113

    
114
    /* Stepper / range sensor */
115
    if (range_enabled) {
116
      step_sweep();
117
      range_measure(ranges);
118
      range_msg.header.stamp = nh.now();
119
      range_msg.header.seq++;
120
      range_msg.pos = 0; // TODO fill this
121
      range_msg.distance0 = ranges[0];
122
      range_msg.distance1 = ranges[1];
123
      range_pub.publish(&range_msg);
124
    }
125

    
126
  }
127

    
128
  return 0;
129
}
130

    
131
#else ///////////////////////////////////////////////
132

    
133
extern "C"
134
{
135
#include <stdlib.h>
136
#include <string.h>
137
#include <avr/io.h>
138
#include <util/delay.h>
139
}
140

    
141
#include "Atmega128rfa1.h"
142
#include "range.h"
143
#include "bom.h"
144
#include "stepper.h"
145

    
146
Atmega128rfa1 avr;
147

    
148
void debug(const char *str)
149
{
150
  avr.puts(str);
151
}
152

    
153
int main()
154
{
155
  char buf[20];
156
  //int i;
157
  //char id = 0;
158
  /*unsigned long now, next = 0;
159
  unsigned int ranges[2];*/
160
  avr.init();
161
  range_init();
162
  bom_init();
163
  func step_sweep_cb = step_init(10);
164
  step_sweep_bounds(-26, 26);
165
  step_dir(1);
166
  step_sweep_speed(50);
167
  PORTF |= _BV(PF4);
168
  _delay_ms(500);
169
  PORTF = (PORTF & ~_BV(PF4)) | _BV(PF5);
170
  _delay_ms(500);
171
  PORTF &= ~_BV(PF5);
172
  while (1)
173
  {
174
    step_sweep_cb();
175
    _delay_ms(10);
176
    /*now = avr.time();
177
    if (now > next) {
178
      next = now + 500;*/
179
      /*ultoa(now, buf, 10);
180
      avr.puts(buf);
181
      avr.puts("\r\n");*/
182
      /*id++;
183
      if (id == 0x40) {
184
        id = 0;
185
      }
186
      set_robot_id(id);*/
187
      /*range_measure(ranges);
188
      utoa(ranges[0], buf, 10);
189
      avr.puts("Range: ");
190
      avr.puts(buf);
191
      avr.puts(", ");
192
      utoa(ranges[1], buf, 10);
193
      avr.puts(buf);
194
      avr.puts("\r\n");*/
195
      /*for (i = 0; i < 4; i++) {
196
        bom_send(i);
197
        int msg = bom_get(i);
198
        if (msg != BOM_NO_DATA) {
199
          avr.puts("BOM ");
200
          itoa(i, buf, 10);
201
          avr.puts(buf);
202
          avr.puts(": ");
203
          itoa(bom_msg_get_robot_id(msg), buf, 10);
204
          avr.puts(buf);
205
          avr.puts(" (");
206
          itoa(bom_msg_get_dir(msg), buf, 10);
207
          avr.puts(buf);
208
          avr.puts(")\r\n");
209
        }
210
      }*/
211
    //}
212
  }
213
  return 0;
214
}
215

    
216
#endif //////////////////////////////////////////////