Project

General

Profile

Statistics
| Branch: | Revision:

scoutos / scout / motors / src / motors.cpp @ 0121ead7

History | View | Annotate | Download (3.74 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 motors.cpp
29
 * @brief Motors
30
 *
31
 * Implementation of functions for motor use.
32
 *
33
 * @author Colony Project, CMU Robotics Club
34
 * @author Benjamin Wasserman
35
 **/
36

    
37
#include "ros/ros.h"
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
/* 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 Motors driver. This is a ROS node that controls motor speeds.
57
 *
58
 * This is the main function for the motors node. It is run when the node
59
 * starts and initializes the motors. It then subscribes to the
60
 * set_motors, and set_motor_speeds topics, and advertises the
61
 * query_motors service.
62
 * 
63
 * \param argc The number of command line arguments (should be 1)
64
 * \param argv The array of command line arguments
65
 **/
66
int main(int argc, char **argv){
67
  /* Initialize in ROS the motors driver node */
68
  ros::init(argc, argv, "motors_driver");
69
  
70
  /* Advertise that this serves the query_motors service */
71
  ros::NodeHandle n;
72
  ros::ServiceServer service = n.advertiseService("query_motors", motors_query);
73

    
74
  /* Subscribe to the set_motors topic */
75
  ros::Subscriber sub0 = n.subscribe("set_motors", 4, motors_set);
76

    
77
  /* Initialize hardware for motors */
78
  // Hardware init functions here
79

    
80
  ROS_INFO("Ready to set motors.");
81
  ros::spin();
82

    
83
  return 0;
84
}
85

    
86
/*!
87
 * \brief Sets motor speed
88
 *
89
 * Sets the motor speeds based on subscription to the set_motors topic.
90
 *
91
 * \param msg The message from the set_motors topic, containing speeds and
92
 *  motor configuration settings.
93
 */
94
void motors_set(const motors::set_motors::ConstPtr& msg){
95
  /** \todo Edit to only set requested motors, not all */ 
96
  motor_fl_speed = msg->fl_speed;
97
  motor_fr_speed = msg->fr_speed;
98
  motor_bl_speed = msg->bl_speed;
99
  motor_br_speed = msg->br_speed;
100
}
101

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

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