Project

General

Profile

Statistics
| Branch: | Revision:

root / scout / motors / src / motors.cpp @ c492be62

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

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

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

    
47
/* Motor state variables
48
 * Speeds expressed as absolute speed out of max speed (0 - +-MAXSPEED)
49
 * Absolute speed is the speed written to the hardware to move the motors
50
 */
51
static int motor_fl_speed; /**< The current speed of the front left motor. */
52
static int motor_fr_speed; /**< The current speed of the front right motor. */
53
static int motor_bl_speed; /**< The current speed of the back left motor. */
54
static int motor_br_speed; /**< The current speed of the back right motor. */
55

    
56
/**
57
 * @brief Sets motor speed
58
 *
59
 * Sets the motor speeds based on subscription to the set_motors topic.
60
 *
61
 * @param msg The message from the set_motors topic, containing speeds and
62
 *  motor configuration settings.
63
 */
64
void motors_set(const motors::set_motors::ConstPtr& msg)
65
{
66
    if(msg->fl_set)
67
    {
68
      motor_fl_speed = msg->fl_speed;
69
    }
70
    if(msg->fr_set)
71
    {
72
      motor_fr_speed = msg->fr_speed;
73
    }
74
    if(msg->bl_set)
75
    {
76
      motor_bl_speed = msg->bl_speed;
77
    }
78
    if(msg->br_set)
79
    {
80
      motor_br_speed = msg->br_speed;
81
    }
82

    
83
    /** @todo Add code to write speeds to hardware */
84

    
85
    ROS_DEBUG("Motor speeds set");
86
}
87

    
88
/**
89
 * @brief Outputs current motor speeds
90
 *
91
 * Serves the service query_motors by responding to service requests with the
92
 * speeds of the motors.
93
 * @param req The request. The only field is the units requested.
94
 * @param res The response. The fields will be filled with values.
95
 */
96
bool motors_query(motors::query_motors::Request &req,
97
                  motors::query_motors::Response &res)
98
{
99
    /** @todo Are we checking hardware or just using the saved values?
100
     *  Saved values sound fine to me (Alex). Pleas confirm. */
101
    res.fl_speed = motor_fl_speed;
102
    res.fr_speed = motor_fr_speed;
103
    res.bl_speed = motor_bl_speed;
104
    res.br_speed = motor_br_speed;
105

    
106
    ROS_DEBUG("Motor speeds queried");
107

    
108
    return true;
109
}
110

    
111
/**
112
 * @brief Motors driver. This is a ROS node that controls motor speeds.
113
 *
114
 * This is the main function for the motors node. It is run when the node
115
 * starts and initializes the motors. It then subscribes to the
116
 * set_motors, and set_motor_speeds topics, and advertises the
117
 * query_motors service.
118
 * 
119
 * @param argc The number of command line arguments (should be 1)
120
 * @param argv The array of command line arguments
121
 **/
122
int main(int argc, char **argv)
123
{
124
    /* Initialize in ROS the motors driver node */
125
    ros::init(argc, argv, "motors_driver");
126

    
127
    /* Advertise that this serves the query_motors service */
128
    ros::NodeHandle node;
129
    ros::ServiceServer service = node.advertiseService("query_motors",
130
                                                       motors_query);
131

    
132
    /* Subscribe to the set_motors topic */
133
    ros::Subscriber sub0 = node.subscribe("set_motors", QUEUE_SIZE, motors_set);
134

    
135
    /* Initialize hardware for motors */
136
    // Hardware init functions here
137

    
138
    ROS_INFO("Motors node ready.");
139
    ros::spin();
140

    
141
    return 0;
142
}
143

    
144
/** @} **/