scoutos / scout / encoders / src / encoders.cpp @ c492be62
History | View | Annotate | Download (6.99 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 |
/**
|
28 |
* @file encoders.cpp
|
29 |
* @brief Encoders
|
30 |
*
|
31 |
* Implementation of functions for encoder use.
|
32 |
*
|
33 |
* @author Colony Project, CMU Robotics Club
|
34 |
**/
|
35 |
|
36 |
#include "ros/ros.h" |
37 |
#include "encoders.h" |
38 |
//#include "libscout/src/constants.h"
|
39 |
#include <cstdlib> |
40 |
|
41 |
/**
|
42 |
* @defgroup encoders Encoders
|
43 |
* @brief Functions for using the encoders
|
44 |
*
|
45 |
**/
|
46 |
|
47 |
/* Encoder state variables */
|
48 |
/** \todo Fix types: static */
|
49 |
/** \todo Fix integer overflow possibility */
|
50 |
/* The current position of each encoder, measured in encoder ticks */
|
51 |
int encoder_fl_index; /**< The current state of the front left encoder. */ |
52 |
int encoder_fr_index; /**< The current state of the front right encoder. */ |
53 |
int encoder_bl_index; /**< The current state of the back left encoder. */ |
54 |
int encoder_br_index; /**< The current state of the back right encoder. */ |
55 |
/* The current velocity of each encoder, measured in ticks per second */
|
56 |
int encoder_fl_velocity;
|
57 |
int encoder_fr_velocity;
|
58 |
int encoder_bl_velocity;
|
59 |
int encoder_br_velocity;
|
60 |
/* The current distance each encoder has traveled in ticks from last reset */
|
61 |
int encoder_fl_distance;
|
62 |
int encoder_fr_distance;
|
63 |
int encoder_bl_distance;
|
64 |
int encoder_br_distance;
|
65 |
/* The units that the encoder measurements will be published in */
|
66 |
char encoder_units;
|
67 |
|
68 |
|
69 |
/*!
|
70 |
* \brief Encoders driver. This is a ROS node that controls encoders.
|
71 |
*
|
72 |
* This is the main function for the encoders node. It is run when the node
|
73 |
* starts and initializes the encoders. It then publishes to the
|
74 |
* encoder_state topic and advertises the query_encoders service.
|
75 |
*
|
76 |
* \param argc The number of command line arguments (should be 1)
|
77 |
* \param argv The array of command line arguments
|
78 |
**/
|
79 |
int main(int argc, char **argv){ |
80 |
/* Initialize in ROS the encoders driver node */
|
81 |
ros::init(argc, argv, "encoders_driver");
|
82 |
|
83 |
/* Advertise that this serves the query_encoders service */
|
84 |
ros::NodeHandle n; |
85 |
ros::ServiceServer service = n.advertiseService("query_encoders", encoders_query);
|
86 |
|
87 |
/* Subscribe to the encoder_state topic */
|
88 |
ros::Subscriber sub0 = n.subscribe("encoder_state", 4, encoder_state); |
89 |
|
90 |
/* Initialize hardware for motors */
|
91 |
// Hardware init functions here
|
92 |
|
93 |
ROS_INFO("Ready to set encoders.");
|
94 |
ros::spin(); |
95 |
|
96 |
return 0; |
97 |
} |
98 |
|
99 |
/*!
|
100 |
* \brief Gets encoder state
|
101 |
*
|
102 |
* Sets the encoder state based on subscription to the encoder_state topic.
|
103 |
*
|
104 |
* \todo Make this function set the state properly. Probably requires
|
105 |
* creating a new msg type for the mode set.
|
106 |
*
|
107 |
* \param msg The message from the encoder_state topic, containing encoder
|
108 |
* configuration settings.
|
109 |
*/
|
110 |
void encoder_set_mode(const encoders::encoder_state::ConstPtr& msg) |
111 |
{ |
112 |
|
113 |
} |
114 |
|
115 |
/*!
|
116 |
* \brief Publishes encoder state
|
117 |
*
|
118 |
* Publishes the current encoders position, velocty, and distance from last
|
119 |
* reset.
|
120 |
*/
|
121 |
void encoders_state_publish()
|
122 |
{ |
123 |
encoders::encoders_state msg; |
124 |
|
125 |
if(!ros::ok())
|
126 |
{ |
127 |
return LIB_ERROR;
|
128 |
} |
129 |
|
130 |
/* Put index, velocity, and distance data in message */
|
131 |
msg.fl_index = encoders_ticks_to_units(encoder_fl_index, encoder_units); |
132 |
msg.fr_index = encoders_ticks_to_units(encoder_fr_index, encoder_units); |
133 |
msg.bl_index = encoders_ticks_to_units(encoder_bl_index, encoder_units); |
134 |
msg.br_index = encoders_ticks_to_units(encoder_br_index, encoder_units); |
135 |
msg.fl_speed = encoders_ticks_to_units(encoder_fl_velocity, encoder_units); |
136 |
msg.fr_speed = encoders_ticks_to_units(encoder_fr_velocity, encoder_units); |
137 |
msg.bl_speed = encoders_ticks_to_units(encoder_bl_velocity, encoder_units); |
138 |
msg.br_speed = encoders_ticks_to_units(encoder_br_velocity, encoder_units); |
139 |
msg.fl_distance = encoders_ticks_to_units(encoder_fl_distance, encoder_units); |
140 |
msg.fr_distance = encoders_ticks_to_units(encoder_fr_distance, encoder_units); |
141 |
msg.bl_distance = encoders_ticks_to_units(encoder_bl_distance, encoder_units); |
142 |
msg.br_distance = encoders_ticks_to_units(encoder_br_distance, encoder_units); |
143 |
/* Specifies which units the encoder values are given in */
|
144 |
msg.units = encoder_units; |
145 |
|
146 |
/* Publishes message to encoders_state */
|
147 |
encoders_state_publisher.publish(msg); |
148 |
ros::spinOnce(); |
149 |
|
150 |
return LIB_OK;
|
151 |
} |
152 |
|
153 |
/*!
|
154 |
* \brief Outputs current encoder data
|
155 |
*
|
156 |
* Serves the service query_encoders by responding to service requests with the
|
157 |
* encoder values.
|
158 |
* \param req The request. The units that the response should be in.
|
159 |
* \param res The response. The fields will be filled with values.
|
160 |
*/
|
161 |
bool encoders_query(encoders::query_encoders::Request &req,
|
162 |
encoders::query_encoders::Response &res) |
163 |
{ |
164 |
int units = req.units;
|
165 |
|
166 |
/* Put index, velocity, and distance data in message */
|
167 |
res.fl_index = encoders_ticks_to_units(encoder_fl_index, units); |
168 |
res.fr_index = encoders_ticks_to_units(encoder_fr_index, units); |
169 |
res.bl_index = encoders_ticks_to_units(encoder_bl_index, units); |
170 |
res.br_index = encoders_ticks_to_units(encoder_br_index, units); |
171 |
res.fl_speed = encoders_ticks_to_units(encoder_fl_velocity, units); |
172 |
res.fr_speed = encoders_ticks_to_units(encoder_fr_velocity, units); |
173 |
res.bl_speed = encoders_ticks_to_units(encoder_bl_velocity, units); |
174 |
res.br_speed = encoders_ticks_to_units(encoder_br_velocity, units); |
175 |
res.fl_distance = encoders_ticks_to_units(encoder_fl_distance, units); |
176 |
res.fr_distance = encoders_ticks_to_units(encoder_fr_distance, units); |
177 |
res.bl_distance = encoders_ticks_to_units(encoder_bl_distance, units); |
178 |
res.br_distance = encoders_ticks_to_units(encoder_br_distance, units); |
179 |
|
180 |
ROS_DEBUG("Encoder values queried");
|
181 |
return true; |
182 |
} |
183 |
|
184 |
int encoders_ticks_to_units(int ticks, char units) |
185 |
{ |
186 |
switch(encoder_units)
|
187 |
{ |
188 |
case ENCODER_TICKS: /* Just return ticks */ |
189 |
return ticks;
|
190 |
case ENCODER_MM: /* Return mm of linear travel by the wheel */ |
191 |
return ticks * (2 * PI * WHEEL_RADIUS_MM / NUM_TICKS); |
192 |
case ENCODER_CM: /* Return cm of linear travel by the wheel */ |
193 |
return ticks * (2 * PI * WHEEL_RADIUS_MM / NUM_TICKS) / 10; |
194 |
case ENCODER_DEG: /* Return degrees of travel from last reset */ |
195 |
return ticks * (360 / NUM_TICKS); |
196 |
default: /* The units aren't recognized. Return ticks. */ |
197 |
return ticks;
|
198 |
} |
199 |
} |