Project

General

Profile

Statistics
| Branch: | Revision:

scoutos / scout / motors / src / motors.cpp @ 18e2028b

History | View | Annotate | Download (3.9 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 Benjamin Wasserman
34
 **/
35

    
36
#include "ros/ros.h"
37
#include "motors.h"
38
//#include "libscout/src/constants.h"
39
#include <cstdlib>
40

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

    
48
/* Motor state variables */
49
/** @todo Fix types: static */
50
int motor_fl_speed; /**< The current speed of the front left motor. */
51
int motor_fr_speed; /**< The current speed of the front right motor. */
52
int motor_bl_speed; /**< The current speed of the back left motor. */
53
int motor_br_speed; /**< The current speed of the back right motor. */
54

    
55
/**
56
 * @brief Sets motor speed
57
 *
58
 * Sets the motor speeds based on subscription to the set_motors topic.
59
 *
60
 * @param msg The message from the set_motors topic, containing speeds and
61
 *  motor configuration settings.
62
 */
63
void motors_set(const motors::set_motors::ConstPtr& msg)
64
{
65
    /** @todo Edit to only set requested motors, not all */ 
66
    motor_fl_speed = msg->fl_speed;
67
    motor_fr_speed = msg->fr_speed;
68
    motor_bl_speed = msg->bl_speed;
69
    motor_br_speed = msg->br_speed;
70
}
71

    
72
/**
73
 * @brief Outputs current motor speeds
74
 *
75
 * Serves the service query_motors by responding to service requests with the
76
 * speeds of the motors.
77
 * @param req The request. Should be empty.
78
 * @param res The response. The fields will be filled with values.
79
 */
80
bool motors_query(motors::query_motors::Request &req,
81
                  motors::query_motors::Response &res)
82
{
83
    res.fl_speed = motor_fl_speed;
84
    res.fr_speed = motor_fr_speed;
85
    res.bl_speed = motor_bl_speed;
86
    res.br_speed = motor_br_speed;
87

    
88
    ROS_DEBUG("Motor speeds queried");
89
    return true;
90
}
91

    
92
/**
93
 * @brief Motors driver. This is a ROS node that controls motor speeds.
94
 *
95
 * This is the main function for the motors node. It is run when the node
96
 * starts and initializes the motors. It then subscribes to the
97
 * set_motors, and set_motor_speeds topics, and advertises the
98
 * query_motors service.
99
 * 
100
 * @param argc The number of command line arguments (should be 1)
101
 * @param argv The array of command line arguments
102
 **/
103
int main(int argc, char **argv)
104
{
105
    /* Initialize in ROS the motors driver node */
106
    ros::init(argc, argv, "motors_driver");
107

    
108
    /* Advertise that this serves the query_motors service */
109
    ros::NodeHandle n;
110
    ros::ServiceServer service = n.advertiseService("query_motors",
111
                                                    motors_query);
112

    
113
    /* Subscribe to the set_motors topic */
114
    ros::Subscriber sub0 = n.subscribe("set_motors", 4, motors_set);
115

    
116
    /* Initialize hardware for motors */
117
    // Hardware init functions here
118

    
119
    ROS_INFO("Ready to set motors.");
120
    ros::spin();
121

    
122
    return 0;
123
}
124

    
125
/** @} **/