Project

General

Profile

Statistics
| Branch: | Revision:

scoutos / scout / motors / src / motors.cpp @ 2814387f

History | View | Annotate | Download (4.51 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 "motors_util.cpp"
38
#include "motors.h"
39
//#include "libscout/src/constants.h"
40
#include <cstdlib>
41

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

    
49

    
50

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

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

    
87
    /** @todo Add code to write speeds to hardware */
88
    ROS_DEBUG("Motor speeds set");
89
}
90

    
91
/**
92
 * @brief Outputs current motor speeds
93
 *
94
 * Serves the service query_motors by responding to service requests with the
95
 * speeds of the motors.
96
 * @param req The request. The only field is the units requested.
97
 * @param res The response. The fields will be filled with values.
98
 */
99
bool motors_query(motors::query_motors::Request &req,
100
                  motors::query_motors::Response &res)
101
{
102
    int units = req.units;
103
    res.fl_speed = motors_abs_to_rel(motor_fl_speed, units);
104
    res.fr_speed = motors_abs_to_rel(motor_fr_speed, units);
105
    res.bl_speed = motors_abs_to_rel(motor_bl_speed, units);
106
    res.br_speed = motors_abs_to_rel(motor_br_speed, units);
107

    
108
    ROS_DEBUG("Motor speeds queried");
109
    return true;
110
}
111

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

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

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

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

    
139
    ROS_INFO("Ready to set motors.");
140
    ros::spin();
141

    
142
    return 0;
143
}
144

    
145
/** @} **/