Project

General

Profile

Statistics
| Branch: | Revision:

root / scout_avr / src / main.cpp @ 8741d18c

History | View | Annotate | Download (5.44 KB)

1 6e7f0a98 Tom Mullins
#if 1 ///////////////////////////////////////////////
2 807483bf Tom Mullins
3 49090532 Tom Mullins
#include "ros.h"
4 6e7f0a98 Tom Mullins
#include "bom.h"
5 47e26dee Tom Mullins
#include "range.h"
6 6c9146d5 Tom Mullins
#include "stepper.h"
7 066b08bb Tom Mullins
#include "orb.h"
8 8741d18c Tom Mullins
#include "cliffSensor.h"
9 6c9146d5 Tom Mullins
#include <bom/bom.h>
10
#include <sonar/sonar_distance.h>
11
#include <sonar/sonar_toggle.h>
12
#include <sonar/sonar_set_scan.h>
13 066b08bb Tom Mullins
#include <headlights/set_headlights.h>
14 8741d18c Tom Mullins
#include <cliffsensor/cliff_status_changed.h>
15 47e26dee Tom Mullins
#include <util/delay.h>
16 88fb3a79 Tom Mullins
17 6c9146d5 Tom Mullins
/* Period of main loop in ms */
18 2853d46b Tom Mullins
#define MAINLOOP_PERIOD 100//50
19 6c9146d5 Tom Mullins
20
char range_enabled = 0;
21 49090532 Tom Mullins
22 812788aa Tom Mullins
void debug(const char *str)
23
{
24 31f4a032 Tom Mullins
}
25
26 066b08bb Tom Mullins
void orb_callback(const headlights::set_headlights& msg)
27 49090532 Tom Mullins
{
28 066b08bb Tom Mullins
  orb_set0(msg.left_red, msg.left_green, msg.left_blue);
29
  orb_set1(msg.right_red, msg.right_green, msg.right_blue);
30 49090532 Tom Mullins
}
31
32 6c9146d5 Tom Mullins
/* dammit, Priya, this capitalization just looks ridiculous */
33
void range_toggle_cb(const sonar::sonar_toggleRequest& req,
34
    sonar::sonar_toggleResponse& resp)
35
{
36
  range_enabled = req.set_on;
37 64aea12e Tom Mullins
  if (range_enabled)
38
    step_enable();
39
  else
40
    step_disable();
41 6c9146d5 Tom Mullins
  resp.ack = true;
42
}
43
44
void range_set_scan_cb(const sonar::sonar_set_scanRequest& req,
45
    sonar::sonar_set_scanResponse& resp)
46
{
47
  step_sweep_bounds(req.stop_l, req.stop_r);
48
  resp.ack = true;
49
}
50
51 49090532 Tom Mullins
int main()
52 88fb3a79 Tom Mullins
{
53 6c9146d5 Tom Mullins
  unsigned long now, next;
54
  unsigned int ranges[2];
55 6e7f0a98 Tom Mullins
  char i, id;
56 6c9146d5 Tom Mullins
57 88fb3a79 Tom Mullins
  ros::NodeHandle nh;
58 6c9146d5 Tom Mullins
  nh.initNode();
59 49090532 Tom Mullins
60 2853d46b Tom Mullins
  /* Stepper */
61
  // TODO ROS messages to set bounds
62
  step_init();
63
  step_dir(1);
64
  step_set_size(STEP_WHOLE);
65
  step_sweep_bounds(-26, 26);
66
67 6c9146d5 Tom Mullins
  /* Range */
68 47e26dee Tom Mullins
  range_init();
69 6c9146d5 Tom Mullins
  sonar::sonar_distance range_msg;
70 86b48573 Tom Mullins
  ros::Publisher range_pub("sonar_distance", &range_msg);
71 6c9146d5 Tom Mullins
  ros::ServiceServer
72
    <sonar::sonar_toggleRequest, sonar::sonar_toggleResponse>
73
    range_toggle("sonar_toggle", range_toggle_cb);
74
  ros::ServiceServer
75
    <sonar::sonar_set_scanRequest, sonar::sonar_set_scanResponse>
76
    range_set_scan("sonar_set_scan", range_set_scan_cb);
77 86b48573 Tom Mullins
  nh.advertise(range_pub);
78 958699af Tom Mullins
  nh.advertiseService(range_toggle);
79
  nh.advertiseService(range_set_scan);
80 6c9146d5 Tom Mullins
81
  /* BOM */
82 47e26dee Tom Mullins
  bom_init();
83 6c9146d5 Tom Mullins
  bom::bom bom_msg;
84
  ros::Publisher bom_pub("bom", &bom_msg);
85 6e7f0a98 Tom Mullins
  nh.advertise(bom_pub);
86 88fb3a79 Tom Mullins
87 066b08bb Tom Mullins
  /* Headlights (aka Orbs) */
88 daf6a575 Tom Mullins
  //orb_init();
89 066b08bb Tom Mullins
  ros::Subscriber<headlights::set_headlights> orb_sub("set_headlights",
90
      orb_callback);
91
  nh.subscribe(orb_sub);
92
93 8741d18c Tom Mullins
  /* Cliff sensors */
94
  cliffSensor_init();
95
  cliffsensor::cliff_status_changed cliff_msg;
96
  ros::Publisher cliff_pub("cliff", &cliff_msg);
97
  nh.advertise(cliff_pub);
98
99 6e7f0a98 Tom Mullins
  id = 0;
100 6c9146d5 Tom Mullins
  next = 0;
101 88fb3a79 Tom Mullins
  while (1)
102
  {
103 6c9146d5 Tom Mullins
    nh.spinOnce();
104
105
    /* Skip loop if the loop period hasn't passed yet */
106
    /* TODO if we need more exact timing, we can enter a tight loop when now
107
     * gets close to next, and avoid the uncertainty of nh.spinOnce() */
108
    now = nh.getHardware()->time();
109
    if (now < next) {
110
      continue;
111
    }
112
    next = now + MAINLOOP_PERIOD;
113
114
    /* Temporary, for BOM testing */
115 6e7f0a98 Tom Mullins
    id++;
116
    if (id == 0x40) {
117
      id = 0;
118
    }
119
    set_robot_id(id);
120 066b08bb Tom Mullins
    bom_send(0);
121 6c9146d5 Tom Mullins
122
    /* BOM */
123 6e7f0a98 Tom Mullins
    for (i = 0; i < 4; i++) {
124
      int msg = bom_get(i);
125
      if (msg != BOM_NO_DATA) {
126
        bom_msg.sender = bom_msg_get_robot_id(msg);
127
        bom_msg.send_dir = bom_msg_get_dir(msg);
128
        bom_msg.recv_dir = i;
129
        bom_pub.publish(&bom_msg);
130
      }
131
    }
132 47e26dee Tom Mullins
133 6c9146d5 Tom Mullins
    /* Stepper / range sensor */
134 2853d46b Tom Mullins
    if (range_enabled) {
135
      step_sweep();
136
      range_measure(ranges);
137 8741d18c Tom Mullins
      range_msg.stamp = nh.now();
138 daf6a575 Tom Mullins
      range_msg.pos = step_get_pos();
139 2853d46b Tom Mullins
      range_msg.distance0 = ranges[0];
140
      range_msg.distance1 = ranges[1];
141 c06735bb Hui Jun Tay
      range_msg.stamp = nh.now();
142 2853d46b Tom Mullins
      range_pub.publish(&range_msg);
143
    }
144 6c9146d5 Tom Mullins
145 8741d18c Tom Mullins
    /* TODO remove raw values and have single bitmask */
146
    cliff_msg.front_raw = read_cliffSensor_front();
147
    cliff_msg.left_raw = read_cliffSensor_left();
148
    cliff_msg.right_raw = read_cliffSensor_right();
149
    cliff_msg.cliff_status = cliff_msg.front_raw | cliff_msg.left_raw
150
      | cliff_msg.right_raw;
151
152 88fb3a79 Tom Mullins
  }
153
154
  return 0;
155 49090532 Tom Mullins
}
156 88fb3a79 Tom Mullins
157 807483bf Tom Mullins
#else ///////////////////////////////////////////////
158
159
extern "C"
160 88fb3a79 Tom Mullins
{
161
#include <stdlib.h>
162
#include <string.h>
163 fd73d758 Tom Mullins
#include <avr/io.h>
164
#include <util/delay.h>
165 88fb3a79 Tom Mullins
}
166
167 49090532 Tom Mullins
#include "Atmega128rfa1.h"
168 1c3c96ce Tom Mullins
#include "range.h"
169 f115416e Tom Mullins
#include "bom.h"
170 6c9146d5 Tom Mullins
#include "stepper.h"
171 49090532 Tom Mullins
172 31f4a032 Tom Mullins
Atmega128rfa1 avr;
173
174 812788aa Tom Mullins
void debug(const char *str)
175
{
176 31f4a032 Tom Mullins
  avr.puts(str);
177
}
178
179 88fb3a79 Tom Mullins
int main()
180
{
181 1c3c96ce Tom Mullins
  char buf[20];
182 86b48573 Tom Mullins
  //int i;
183
  //char id = 0;
184 2853d46b Tom Mullins
  /*unsigned long now, next = 0;
185
  unsigned int ranges[2];*/
186 88fb3a79 Tom Mullins
  avr.init();
187 1c3c96ce Tom Mullins
  range_init();
188 f115416e Tom Mullins
  bom_init();
189 2853d46b Tom Mullins
  func step_sweep_cb = step_init(10);
190 6c9146d5 Tom Mullins
  step_sweep_bounds(-26, 26);
191
  step_dir(1);
192 2853d46b Tom Mullins
  step_sweep_speed(50);
193
  PORTF |= _BV(PF4);
194
  _delay_ms(500);
195
  PORTF = (PORTF & ~_BV(PF4)) | _BV(PF5);
196
  _delay_ms(500);
197
  PORTF &= ~_BV(PF5);
198 88fb3a79 Tom Mullins
  while (1)
199
  {
200 2853d46b Tom Mullins
    step_sweep_cb();
201
    _delay_ms(10);
202
    /*now = avr.time();
203 49090532 Tom Mullins
    if (now > next) {
204 2853d46b Tom Mullins
      next = now + 500;*/
205 fd73d758 Tom Mullins
      /*ultoa(now, buf, 10);
206 812788aa Tom Mullins
      avr.puts(buf);
207 fd73d758 Tom Mullins
      avr.puts("\r\n");*/
208 6c9146d5 Tom Mullins
      /*id++;
209 31f4a032 Tom Mullins
      if (id == 0x40) {
210
        id = 0;
211
      }
212 6c9146d5 Tom Mullins
      set_robot_id(id);*/
213 2853d46b Tom Mullins
      /*range_measure(ranges);
214 86b48573 Tom Mullins
      utoa(ranges[0], buf, 10);
215 f115416e Tom Mullins
      avr.puts("Range: ");
216
      avr.puts(buf);
217
      avr.puts(", ");
218 86b48573 Tom Mullins
      utoa(ranges[1], buf, 10);
219
      avr.puts(buf);
220 2853d46b Tom Mullins
      avr.puts("\r\n");*/
221 6c9146d5 Tom Mullins
      /*for (i = 0; i < 4; i++) {
222 f115416e Tom Mullins
        bom_send(i);
223
        int msg = bom_get(i);
224
        if (msg != BOM_NO_DATA) {
225
          avr.puts("BOM ");
226
          itoa(i, buf, 10);
227
          avr.puts(buf);
228
          avr.puts(": ");
229 31f4a032 Tom Mullins
          itoa(bom_msg_get_robot_id(msg), buf, 10);
230
          avr.puts(buf);
231
          avr.puts(" (");
232
          itoa(bom_msg_get_dir(msg), buf, 10);
233 f115416e Tom Mullins
          avr.puts(buf);
234 31f4a032 Tom Mullins
          avr.puts(")\r\n");
235 f115416e Tom Mullins
        }
236 6c9146d5 Tom Mullins
      }*/
237 2853d46b Tom Mullins
    //}
238 88fb3a79 Tom Mullins
  }
239
  return 0;
240 cf115e3d Tom Mullins
}
241 807483bf Tom Mullins
242
#endif //////////////////////////////////////////////