Project

General

Profile

Revision dbbad8ed

IDdbbad8ed5cba08f5500e7d333beab2d089f9956c
Parent f3bfb5b5
Child a1219504

Added by Thomas Mullins about 11 years ago

Added a reset() function to EncodersControl. Untested.

View differences:

scout/encoders/src/encoders.cpp
39 39
 * @{
40 40
 **/
41 41

  
42
#include <fstream>
42 43
#include <ros/ros.h>
43 44
#include "encoders.h"
44 45

  
......
70 71
int Encoder::get_ticks()
71 72
{
72 73
    // open device file
73
    fticks.open(filename, std::ios::in);
74
    std::fstream fticks(filename, std::ios::in);
74 75

  
75 76
    int ticks;
76 77
    fticks >> ticks;
77 78

  
78
    fticks.close();
79 79
    return ticks;
80 80
}
81 81

  
82 82
/**
83
 * @brief Resets the encoder
84
 *
85
 * Sets the encoder's ticks value back to 0
86
 */
87
void Encoder::reset()
88
{
89
    std::fstream fticks(filename, std::ios::out);
90
    fticks << 0;
91
}
92

  
93
/**
83 94
 * @brief Outputs current encoder data
84 95
 *
85 96
 * Serves the service query_encoders by responding to service requests with the
......
104 115
}
105 116

  
106 117
/**
118
 * @brief Resets all four encoders
119
 *
120
 * Serves the service reset_encoders
121
 * @param req The request. Empty.
122
 * @param res The response. Empty.
123
 */
124
bool handle_reset_query(::messages::reset_encoders::Request &req,
125
                        ::messages::reset_encoders::Response &res)
126
{
127
    encoder_fl.reset();
128
    encoder_fr.reset();
129
    encoder_bl.reset();
130
    encoder_br.reset();
131
    return true;
132
}
133

  
134
/**
107 135
 * @brief Encoders driver. This is a ROS node that controls encoders.
108 136
 *
109 137
 * This is the main function for the encoders node. It is run when the node
scout/encoders/src/encoders.h
35 35
#ifndef _ENCODERS_H_
36 36
#define _ENCODERS_H_
37 37

  
38
#include <fstream>
39 38
#include <messages/query_encoders.h>
39
#include <messages/reset_encoders.h>
40 40

  
41 41
class Encoder
42 42
{
43 43
    public:
44 44
        Encoder(int n);
45 45
        int get_ticks();
46
        void reset();
46 47
    private:
47 48
        char filename[60];
48
        std::fstream fticks; /**< The file in sysfs containing tick count */
49 49
};
50 50

  
51 51
int main(int argc, char **argv);
scout/libscout/src/EncodersControl.cpp
42 42
                                 string scoutname)
43 43
    : node(libscout_node)
44 44
{
45
    query_client =
46
        node.serviceClient< ::messages::query_encoders>(scoutname+"/query_encoders");
45
    query_client = node.serviceClient< ::messages::query_encoders>(
46
            scoutname+"/query_encoders");
47
    reset_client = node.serviceClient< ::messages::reset_encoders>(
48
            scoutname+"/reset_encoders");
47 49
}
48 50

  
49 51
/**
......
69 71
    return cur_readings;
70 72
}
71 73

  
74
/**
75
 * @brief Resets the encoder tick count to 0.
76
 */
77
void EncodersControl::reset()
78
{
79
    ::messages::reset_encoders srv;
80
    if (!reset_client.call(srv))
81
    {
82
        ROS_ERROR("EncodersControl reset failed.");
83
    }
84
}
scout/libscout/src/EncodersControl.h
36 36

  
37 37
#include <ros/ros.h>
38 38
#include <messages/query_encoders.h>
39
#include <messages/reset_encoders.h>
39 40

  
40 41
#include "constants.h"
41 42

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

  
61
        /** User ROS to reset the encoder count. */
62
        void reset();
63

  
60 64
    private:
61 65

  
62 66
        /* ROS publisher and client declaration */
63 67
        ros::ServiceClient query_client;
68
        ros::ServiceClient reset_client;
64 69
        ros::NodeHandle node;
65 70
};
66 71

  
scout/messages/srv/reset_encoders.srv
1
---

Also available in: Unified diff