Project

General

Profile

Statistics
| Branch: | Revision:

scoutos / scout / buttons / src / buttons.cpp @ 04f50f8a

History | View | Annotate | Download (6.45 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 buttons.cpp
28
 * @brief Contains code to control the buttons.
29
 *
30
 * Implementation of functions for button use.
31
 *
32
 * @author Colony Project, CMU Robotics Club
33
 * @author Priyanka Deo
34
 **/
35

    
36
#include "ros/ros.h"
37
#include "buttons.h"
38
#include <cstdlib>
39

    
40
/**
41
 * @defgroup buttons Buttons
42
 * @brief Functions for using the buttons
43
 *
44
 * @{
45
 **/
46

    
47
/* Button state variables
48
 */
49
static int button1_pressed; /**< Whether or not button 1 is pressed. */
50
static int button2_pressed; /**< Whether or not button 2 is pressed. */
51

    
52
/**
53
 * @brief Sets motor speed
54
 *
55
 * Sets the motor speeds based on subscription to the set_motors topic.
56
 *
57
 * @param msg The message from the set_motors topic, containing speeds and
58
 *  motor configuration settings.
59
 */
60
void motors_set(const motors::set_motors::ConstPtr& msg)
61
{
62
    /** @todo Edit to only set requested motors, not all */
63
    int which = msg->which;
64
    if(which & MOTOR_FL_REV)
65
    {
66
      motor_fl_speed = -1 * motors_rel_to_abs(msg->fl_speed, msg->units);
67
    }
68
    if(which & MOTOR_FR_REV)
69
    {
70
      motor_fr_speed = -1 * motors_rel_to_abs(msg->fr_speed, msg->units);
71
    }
72
    if(which & MOTOR_BL_REV)
73
    {
74
      motor_bl_speed = -1 * motors_rel_to_abs(msg->bl_speed, msg->units);
75
    }
76
    if(which & MOTOR_BR_REV)
77
    {
78
      motor_br_speed = -1 * motors_rel_to_abs(msg->br_speed, msg->units);
79
    }
80
    if(which & MOTOR_FL)
81
    {
82
      motor_fl_speed = motors_rel_to_abs(msg->fl_speed, msg->units);
83
    }
84
    if(which & MOTOR_FR)
85
    {
86
      motor_fr_speed = motors_rel_to_abs(msg->fr_speed, msg->units);
87
    }
88
    if(which & MOTOR_BL)
89
    {
90
      motor_bl_speed = motors_rel_to_abs(msg->bl_speed, msg->units);
91
    }
92
    if(which & MOTOR_BR)
93
    {
94
      motor_br_speed = motors_rel_to_abs(msg->br_speed, msg->units);
95
    }
96

    
97
    /* Write speeds to hardware */
98
    /** @todo Add code to write speeds to hardware */
99
}
100

    
101
/**
102
 * @brief Outputs current motor speeds
103
 *
104
 * Serves the service query_motors by responding to service requests with the
105
 * speeds of the motors.
106
 * @param req The request. The only field is the units requested.
107
 * @param res The response. The fields will be filled with values.
108
 */
109
bool motors_query(motors::query_motors::Request &req,
110
                  motors::query_motors::Response &res)
111
{
112
    int units = req.units;
113
    res.fl_speed = motors_abs_to_rel(motor_fl_speed, units);
114
    res.fr_speed = motors_abs_to_rel(motor_fr_speed, units);
115
    res.bl_speed = motors_abs_to_rel(motor_bl_speed, units);
116
    res.br_speed = motors_abs_to_rel(motor_br_speed, units);
117

    
118
    ROS_DEBUG("Motor speeds queried");
119
    return true;
120
}
121

    
122
/**
123
 * @brief Converts set speeds (of various units) to absolute speeds.
124
 *
125
 * @param speed The speed expressed in the desired units
126
 * @param units The units the desired speed is measured in
127
 * @return The absolute speed of the motor
128
 **/
129
int motors_rel_to_abs(int rel_speed, int units)
130
{
131
    switch(units)
132
    {
133
      case MOTOR_ABSOLUTE:/* Speed given as absolute */
134
        return rel_speed;
135
      case MOTOR_PERCENT:/* Convert from percentage */
136
        return rel_speed * MAXSPEED / 100;
137
      case MOTOR_MMS:/* Convert from mm/s */
138
        /** @todo Make math to do this conversion **/
139
        return rel_speed;
140
      case MOTOR_CMS:/* Convert from cm/s */
141
        /** @todo Make math to do this conversion **/
142
        return rel_speed;
143
      default: /* The units aren't recognized */
144
        /** @todo Decide on default case. Either percent or absolute. **/
145
        return rel_speed;
146
    }
147
}
148

    
149
/**
150
 * @brief Convert absolute speeds to speeds of various units.
151
 *
152
 * @param speed The speed expressed in absolute units.
153
 * @param units The units the desired speed is measured in.
154
 * @return The relative speed of the motor in desired units.
155
 **/
156
int motors_abs_to_rel(int abs_speed, int units)
157
{
158
    switch(units)
159
    {
160
      case MOTOR_ABSOLUTE:/* Speed given as absolute */
161
        return abs_speed;
162
      case MOTOR_PERCENT:/* Convert from percentage */
163
        return abs_speed * 100 / MAXSPEED;
164
      case MOTOR_MMS:/* Convert from mm/s */
165
        /** @todo Make math to do this conversion **/
166
        return abs_speed;
167
      case MOTOR_CMS:/* Convert from cm/s */
168
        /** @todo Make math to do this conversion **/
169
        return abs_speed;
170
      default: /* The units aren't recognized */
171
        /** @todo Decide on default case. Either percent or absolute. **/
172
        return abs_speed;
173
    }
174
}
175

    
176
/**
177
 * @brief Motors driver. This is a ROS node that controls motor speeds.
178
 *
179
 * This is the main function for the motors node. It is run when the node
180
 * starts and initializes the motors. It then subscribes to the
181
 * set_motors, and set_motor_speeds topics, and advertises the
182
 * query_motors service.
183
 * 
184
 * @param argc The number of command line arguments (should be 1)
185
 * @param argv The array of command line arguments
186
 **/
187
int main(int argc, char **argv)
188
{
189
    /* Initialize in ROS the motors driver node */
190
    ros::init(argc, argv, "motors_driver");
191

    
192
    /* Advertise that this serves the query_motors service */
193
    ros::NodeHandle n;
194
    ros::ServiceServer service = n.advertiseService("query_motors",
195
                                                    motors_query);
196

    
197
    /* Subscribe to the set_motors topic */
198
    ros::Subscriber sub0 = n.subscribe("set_motors", 4, motors_set);
199

    
200
    /* Initialize hardware for motors */
201
    // Hardware init functions here
202

    
203
    ROS_INFO("Ready to set motors.");
204
    ros::spin();
205

    
206
    return 0;
207
}
208

    
209
/** @} **/