Project

General

Profile

Revision f34d6221

IDf34d6221684d4fffd096c9993f00d63c17377537
Parent f79fbce2
Child aa84b67c, e1a60f89

Added by Priya about 12 years ago

Ok fixed compilation issues from last commit

View differences:

scout/libscout/src/BehaviorList.h
4 4
#include "Behavior.h"
5 5
#include "behaviors/draw_cw_circle.h"
6 6
#include "behaviors/draw_ccw_circle.h"
7
#include "behaviors/Odometry.h"
7 8

  
8 9
class BehaviorList
9 10
{
scout/libscout/src/EncodersControl.cpp
31 31
 * @author Alex Zirbel
32 32
 */
33 33

  
34
#include "SonarControl.h"
34
#include "EncodersControl.h"
35 35

  
36 36
using namespace std;
37 37

  
......
54 54
    // Set scan range
55 55
    encoders::query_encoders srv;
56 56

  
57
    encoders_readings cur_readings;
57
    encoder_readings cur_readings;
58 58

  
59 59
    if (!query_client.call(srv))
60 60
    {
scout/libscout/src/EncodersControl.h
31 31
 * @author Alex Zirbel
32 32
 **/
33 33

  
34
#ifndef _SONAR_CONTROL_H_
35
#define _SONAR_CONTROL_H_
34
#ifndef _ENCODERS_CONTROL_H_
35
#define _ENCODERS_CONTROL_H_
36 36

  
37 37
#include <ros/ros.h>
38 38
#include <encoders/query_encoders.h>
......
41 41

  
42 42
typedef struct encoder_readings
43 43
{
44
    unsigned int fl_distance;
45
    unsigned int fr_distance;
44
    unsigned int fl_ticks;
45
    unsigned int fr_ticks;
46 46
    unsigned int bl_ticks;
47 47
    unsigned int br_ticks;
48 48
} encoder_readings;
......
55 55
                        std::string scoutname);
56 56

  
57 57
        /** Use ROS to get the current encoder position. */
58
        void query();
58
        encoder_readings query();
59 59

  
60 60
    private:
61 61

  
scout/libscout/src/behaviors/Odometry.cpp
47 47
    get_position();
48 48
    ROS_INFO("Scout is at x: %f  y: %f \n", scout_pos->x, scout_pos->y);
49 49
  }
50
  return 0;
51 50
}

Also available in: Unified diff