Project

General

Profile

Revision 572adceb

ID572adceb0cf28fd95b170901a03524c93d9a3580
Parent 9b11c5b3
Child ce559b91

Added by Alex Zirbel about 12 years ago

Fixed the analog node.

Only a couple small changes were needed here. For the most part, good job Dev - looks like this is set up correctly for a skeleton. Changes were debugging only.

View differences:

scout/analog/CMakeLists.txt
17 17
set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
18 18

  
19 19
#uncomment if you have defined messages
20
rosbuild_genmsg()
20
#rosbuild_genmsg()
21 21
#uncomment if you have defined services
22 22
rosbuild_gensrv()
23 23

  
scout/analog/src/analog.cpp
33 33
 * @author Dev Gurjar
34 34
 **/
35 35

  
36
#include "ros/ros.h"
36
#include <ros/ros.h>
37

  
37 38
#include "analog.h"
38
//#include "libscout/src/constants.h"
39
#include <cstdlib>
40 39

  
41 40
/**
42 41
 * @defgroup analog Analog
......
49 48
/** @todo Fix types: static */
50 49
unsigned int port; /**< The current port from which we are reading from. */
51 50

  
52

  
53 51
/**
54 52
 * @brief Outputs current analog data at a given port
55 53
 *
......
58 56
 * @param req The request. The only field is the units requested.
59 57
 * @param res The response. The fields will be filled with values.
60 58
 */
61
bool analog_query(motors::query_analog::Request &req,
62
                  motors::query_analog::Response &res)
59
bool analog_query(analog::query_analog::Request &req,
60
                  analog::query_analog::Response &res)
63 61
{
64
    int port = port;
62
    int port = req.port;
65 63
    res.sensor_data = get_sensor_data(port);
66 64

  
67 65
    ROS_DEBUG("Analog data queried");
......
75 73
 * 
76 74
 * @param port The port we want to read from
77 75
 */
78
unsigned int get_sensor_data(int port){
79

  
80
    ROS_DEBUG("Got Analog data from the sensor");
76
unsigned int get_sensor_data(int port)
77
{
78
    ROS_DEBUG("Got Analog data from the sensor [Unimplemented]");
81 79
    return 0;
82 80
}
83 81

  
84 82
/**
85
 * @brief Motors driver. This is a ROS node that controls motor speeds.
86
 *
87
 * This is the main function for the motors node. It is run when the node
88
 * starts and initializes the motors. It then subscribes to the
89
 * set_motors, and set_motor_speeds topics, and advertises the
90
 * query_motors service.
91
 * 
92
 * @param argc The number of command line arguments (should be 1)
93
 * @param argv The array of command line arguments
94
 **/
83
 * @brief Analog driver. Provides an interface to read data from analog ports.
84
 */
95 85
int main(int argc, char **argv)
96 86
{
97 87
    /* Initialize in ROS the motors driver node */
......
102 92
    ros::ServiceServer service = n.advertiseService("query_analog",
103 93
                                                    analog_query);
104 94

  
105
    /* Initialize hardware for motors */
95
    /* Initialize hardware for analog */
96

  
106 97
    // Hardware init functions here
107 98
    ros::spin();
108 99

  
scout/analog/src/analog.h
38 38
#define _ANALOG_H_
39 39

  
40 40
#include "analog/query_analog.h"
41
//#include "analog/set_motors.h"
42 41

  
43 42
/** @brief Analog port 0 **/
44 43
#define AN0 0x00
......
74 73
#define AN15 0x0F
75 74

  
76 75
/** @brief Struct to hold the value of a particular analog port **/
77
typedef struct {
76
typedef struct
77
{
78 78
  uint8_t adc8;
79 79
  uint16_t adc10;
80 80
} adc_t;
81 81

  
82 82
/* The number of messages in the queue. If messages arrive faster than they are
83 83
 * handled, old ones are thrown out */
84
#define QUEUE_SIZE 4
84
#define QUEUE_SIZE 10
85 85

  
86 86
/** @brief Initialize the analog module and driver. **/
87 87
int main(int argc, char **argv);

Also available in: Unified diff