Project

General

Profile

Revision 53349043

ID53349043c921e6f3479bf12000c67830839e8463
Parent bc943bf6
Child 32c4f513

Added by Thomas Mullins almost 11 years ago

Disabled stepper movement and cleaned up code a bit

View differences:

scout_avr/src/Atmega128rfa1.h
7 7

  
8 8
#define RX_BUFFER_SIZE 256
9 9

  
10
#define MAX_SUBSCRIBERS 8
11
#define MAX_PUBLISHERS 6
10
#define MAX_SUBSCRIBERS 3
11
#define MAX_PUBLISHERS 5
12 12
#define INPUT_SIZE 256
13 13
#define OUTPUT_SIZE 1024
14 14

  
scout_avr/src/debug.h
1
#ifndef _DEBUG_H
2
#define _DEBUG_H
3

  
4
void debug(const char *str);
5

  
6
#endif
scout_avr/src/main.cpp
1
#if 1 ///////////////////////////////////////////////
2

  
3 1
#include "ros.h"
4 2
#include "bom.h"
5 3
#include "range.h"
......
19 17

  
20 18
char range_enabled = 0;
21 19

  
22
void debug(const char *str)
23
{
24
}
25

  
26 20
void orb_callback(const messages::set_headlights& msg)
27 21
{
28 22
  orb_set0(msg.left_red, msg.left_green, msg.left_blue);
......
61 55
  // TODO ROS messages to set bounds
62 56
  step_init();
63 57
  step_dir(1);
64
  step_set_size(STEP_WHOLE);
58
  step_set_size(STEP_HALF);
65 59
  step_sweep_bounds(-26, 26);
66 60

  
67 61
  /* Range */
......
85 79
  nh.advertise(bom_pub);
86 80

  
87 81
  /* Headlights (aka Orbs) */
88
  //orb_init();
82
  //orb_init(); TODO debug orbs
89 83
  ros::Subscriber<messages::set_headlights> orb_sub("set_headlights",
90 84
      orb_callback);
91 85
  nh.subscribe(orb_sub);
......
158 152

  
159 153
  return 0;
160 154
}
161

  
162
#else ///////////////////////////////////////////////
163

  
164
extern "C"
165
{
166
#include <stdlib.h>
167
#include <string.h>
168
#include <avr/io.h>
169
#include <util/delay.h>
170
}
171

  
172
#include "Atmega128rfa1.h"
173
#include "range.h"
174
#include "bom.h"
175
#include "stepper.h"
176

  
177
Atmega128rfa1 avr;
178

  
179
void debug(const char *str)
180
{
181
  avr.puts(str);
182
}
183

  
184
int main()
185
{
186
  char buf[20];
187
  //int i;
188
  //char id = 0;
189
  /*unsigned long now, next = 0;
190
  unsigned int ranges[2];*/
191
  avr.init();
192
  range_init();
193
  bom_init();
194
  func step_sweep_cb = step_init(10);
195
  step_sweep_bounds(-26, 26);
196
  step_dir(1);
197
  step_sweep_speed(50);
198
  PORTF |= _BV(PF4);
199
  _delay_ms(500);
200
  PORTF = (PORTF & ~_BV(PF4)) | _BV(PF5);
201
  _delay_ms(500);
202
  PORTF &= ~_BV(PF5);
203
  while (1)
204
  {
205
    step_sweep_cb();
206
    _delay_ms(10);
207
    /*now = avr.time();
208
    if (now > next) {
209
      next = now + 500;*/
210
      /*ultoa(now, buf, 10);
211
      avr.puts(buf);
212
      avr.puts("\r\n");*/
213
      /*id++;
214
      if (id == 0x40) {
215
        id = 0;
216
      }
217
      set_robot_id(id);*/
218
      /*range_measure(ranges);
219
      utoa(ranges[0], buf, 10);
220
      avr.puts("Range: ");
221
      avr.puts(buf);
222
      avr.puts(", ");
223
      utoa(ranges[1], buf, 10);
224
      avr.puts(buf);
225
      avr.puts("\r\n");*/
226
      /*for (i = 0; i < 4; i++) {
227
        bom_send(i);
228
        int msg = bom_get(i);
229
        if (msg != BOM_NO_DATA) {
230
          avr.puts("BOM ");
231
          itoa(i, buf, 10);
232
          avr.puts(buf);
233
          avr.puts(": ");
234
          itoa(bom_msg_get_robot_id(msg), buf, 10);
235
          avr.puts(buf);
236
          avr.puts(" (");
237
          itoa(bom_msg_get_dir(msg), buf, 10);
238
          avr.puts(buf);
239
          avr.puts(")\r\n");
240
        }
241
      }*/
242
    //}
243
  }
244
  return 0;
245
}
246

  
247
#endif //////////////////////////////////////////////
scout_avr/src/stepper.cpp
43 43

  
44 44
void step_enable()
45 45
{
46
  return; // stepper is temporarily disabled for demo
46 47
  PORTF &= ~_BV(S_EN);
47 48
}
48 49

  
......
82 83

  
83 84
void step_do_step()
84 85
{
86
  return; // stepper is temporarily disabled for demo
85 87
  if(step.dir==0) return; //do not step if not enabled
86 88
  PORTD |= (1<<S_STEP); //step once 
87 89
  _delay_us(1); //conform with step timing

Also available in: Unified diff