Project

General

Profile

Statistics
| Branch: | Revision:

root / scout / encoders / src / encoders.cpp @ dbbad8ed

History | View | Annotate | Download (4.37 KB)

1
/**
2
 * Copyright (c) 2011 Colony Project
3
 * 
4
 * Permission is hereby granted, free of charge, to any person
5
 * obtaining a copy of this software and associated documentation
6
 * files (the "Software"), to deal in the Software without
7
 * restriction, including without limitation the rights to use,
8
 * copy, modify, merge, publish, distribute, sublicense, and/or sell
9
 * copies of the Software, and to permit persons to whom the
10
 * Software is furnished to do so, subject to the following
11
 * conditions:
12
 * 
13
 * The above copyright notice and this permission notice shall be
14
 * included in all copies or substantial portions of the Software.
15
 * 
16
 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
17
 * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES
18
 * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
19
 * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT
20
 * HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY,
21
 * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
22
 * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR
23
 * OTHER DEALINGS IN THE SOFTWARE.
24
 */
25

    
26
/**
27
 * @file encoders.cpp
28
 * @brief Encoders
29
 *
30
 * Implementation of functions for encoder use.
31
 *
32
 * @author Colony Project, CMU Robotics Club
33
 * @author Alex Zirbel
34
 * @author Tom Mullins
35

36
 * @defgroup encoders Encoders
37
 * @brief Functions for using the encoders
38
 *
39
 * @{
40
 **/
41

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

    
46
/* Encoder instances */
47
/* @todo make sure these are the correct numbers */
48
static Encoder encoder_fl(0);
49
static Encoder encoder_fr(1);
50
static Encoder encoder_bl(2);
51
static Encoder encoder_br(3);
52

    
53
/**
54
 * @brief Encoder constructor
55
 *
56
 * Opens device file, which is read at every call to get_ticks
57
 *
58
 * @param n The encoder number to read, between 0 and 3 inclusive
59
 */
60
Encoder::Encoder(int n)
61
{
62
    sprintf(filename, "/sys/class/encoder/enc%d/ticks", n);
63
}
64

    
65
/**
66
 * @brief Returns the current tick count
67
 *
68
 * This will actually read from the encoder ticks file to get the latest value
69
 * from the driver
70
 */
71
int Encoder::get_ticks()
72
{
73
    // open device file
74
    std::fstream fticks(filename, std::ios::in);
75

    
76
    int ticks;
77
    fticks >> ticks;
78

    
79
    return ticks;
80
}
81

    
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
/**
94
 * @brief Outputs current encoder data
95
 *
96
 * Serves the service query_encoders by responding to service requests with the
97
 * encoder values.
98
 * @param req The request. The units that the response should be in.
99
 * @param res The response. The fields will be filled with values.
100
 */
101
bool handle_encoders_query(::messages::query_encoders::Request  &req,
102
                           ::messages::query_encoders::Response &res)
103
{
104
    /* Put index, velocity, and distance data in message */
105
    res.fl_distance = -encoder_fl.get_ticks();
106
    res.fr_distance = encoder_fr.get_ticks();
107
    res.bl_distance = encoder_bl.get_ticks();
108
    res.br_distance = encoder_br.get_ticks();
109

    
110
    /* @todo maybe return value based on whether reads succeeded */
111

    
112
    ROS_DEBUG("Encoder values queried");
113
    ROS_INFO("Encoder values queried %d  %d  %d   %d", res.fl_distance, res.fr_distance, res.bl_distance, res.br_distance);
114
    return true;
115
}
116

    
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
/**
135
 * @brief Encoders driver. This is a ROS node that controls encoders.
136
 *
137
 * This is the main function for the encoders node. It is run when the node
138
 * starts and initializes the encoders. It then publishes to the
139
 * encoder_state topic and advertises the query_encoders service.
140
 */
141
int main(int argc, char **argv)
142
{
143
    /* Initialize in ROS the encoders driver node */
144
    ros::init(argc, argv, "encoders_driver");
145

    
146
    /* Advertise that this serves the query_encoders service */
147
    ros::NodeHandle n;
148
    ros::ServiceServer service =
149
        n.advertiseService("query_encoders",
150
                           handle_encoders_query);
151

    
152
    ROS_INFO("Ready to set encoders.");
153

    
154
    ros::spin();
155

    
156
    return 0;
157
}
158

    
159
/** @} */