Revision 18e2028b
Updated motors.cpp and motors.h to comply with coding standards and doxygen.
Changed the module comments so motors are properly labeled as a the motor module.
Chaned indentation to four spaces.
Put braces on a new line.
scout/motors/src/motors.cpp | ||
---|---|---|
23 | 23 |
* OTHER DEALINGS IN THE SOFTWARE. |
24 | 24 |
**/ |
25 | 25 |
|
26 |
|
|
27 | 26 |
/** |
28 | 27 |
* @file motors.cpp |
29 |
* @brief Motors
|
|
28 |
* @brief Contains code to control the motors.
|
|
30 | 29 |
* |
31 | 30 |
* Implementation of functions for motor use. |
32 | 31 |
* |
... | ... | |
43 | 42 |
* @defgroup motors Motors |
44 | 43 |
* @brief Functions for using the motors |
45 | 44 |
* |
45 |
* @{ |
|
46 | 46 |
**/ |
47 | 47 |
|
48 | 48 |
/* Motor state variables */ |
49 |
/** \todo Fix types: static */
|
|
49 |
/** @todo Fix types: static */
|
|
50 | 50 |
int motor_fl_speed; /**< The current speed of the front left motor. */ |
51 | 51 |
int motor_fr_speed; /**< The current speed of the front right motor. */ |
52 | 52 |
int motor_bl_speed; /**< The current speed of the back left motor. */ |
53 | 53 |
int motor_br_speed; /**< The current speed of the back right motor. */ |
54 | 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 |
|
55 |
/** |
|
56 |
* @brief Sets motor speed |
|
88 | 57 |
* |
89 | 58 |
* Sets the motor speeds based on subscription to the set_motors topic. |
90 | 59 |
* |
91 |
* \param msg The message from the set_motors topic, containing speeds and
|
|
60 |
* @param msg The message from the set_motors topic, containing speeds and
|
|
92 | 61 |
* motor configuration settings. |
93 | 62 |
*/ |
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; |
|
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; |
|
100 | 70 |
} |
101 | 71 |
|
102 |
/*!
|
|
103 |
* \brief Outputs current motor speeds
|
|
72 |
/**
|
|
73 |
* @brief Outputs current motor speeds
|
|
104 | 74 |
* |
105 | 75 |
* Serves the service query_motors by responding to service requests with the |
106 | 76 |
* speeds of the motors. |
107 |
* \param req The request. Should be empty.
|
|
108 |
* \param res The response. The fields will be filled with values.
|
|
77 |
* @param req The request. Should be empty.
|
|
78 |
* @param res The response. The fields will be filled with values.
|
|
109 | 79 |
*/ |
110 | 80 |
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; |
|
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(); |
|
117 | 121 |
|
118 |
ROS_DEBUG("Motor speeds queried"); |
|
119 |
return true; |
|
122 |
return 0; |
|
120 | 123 |
} |
121 | 124 |
|
125 |
/** @} **/ |
scout/motors/src/motors.h | ||
---|---|---|
1 | 1 |
/** |
2 |
*Copyright (c) 2007 Colony Project |
|
2 |
* Copyright (c) 2007 Colony Project
|
|
3 | 3 |
* |
4 | 4 |
* Permission is hereby granted, free of charge, to any person |
5 | 5 |
* obtaining a copy of this software and associated documentation |
... | ... | |
23 | 23 |
* OTHER DEALINGS IN THE SOFTWARE. |
24 | 24 |
**/ |
25 | 25 |
|
26 |
|
|
27 | 26 |
/** |
28 | 27 |
* @file motors.h |
29 |
* @brief Contains motor declarations and functions |
|
28 |
* @brief Contains motor declarations and functions.
|
|
30 | 29 |
* |
31 | 30 |
* Contains functions and definitions for the use of |
32 |
* motors |
|
31 |
* motors.
|
|
33 | 32 |
* |
34 | 33 |
* @author Colony Project, CMU Robotics Club |
34 |
* @author Benjamin Wasserman |
|
35 | 35 |
**/ |
36 | 36 |
|
37 |
/* Author: Ben Wasserman |
|
38 |
*/ |
|
39 |
|
|
40 | 37 |
#ifndef _MOTORS_H_ |
41 | 38 |
#define _MOTORS_H_ |
42 | 39 |
|
43 | 40 |
#include "motors/query_motors.h" |
44 | 41 |
#include "motors/set_motors.h" |
45 | 42 |
|
46 |
|
|
47 |
/** @brief Initialize the motors module and driver **/ |
|
43 |
/** @brief Initialize the motors module and driver. **/ |
|
48 | 44 |
int main(int argc, char **argv); |
49 |
/** @brief Responds to topic to set motor speeds and configs **/ |
|
45 |
|
|
46 |
/** @brief Responds to topic to set motor speeds and configs. **/ |
|
50 | 47 |
void motors_set(const motors::set_motors::ConstPtr& msg); |
51 |
/** @brief Responds to service to query motor speeds **/ |
|
48 |
|
|
49 |
/** @brief Responds to service to query motor speeds. **/ |
|
52 | 50 |
bool motors_query(motors::query_motors::Request &req, |
53 |
motors::query_motors::Response &res); |
|
51 |
motors::query_motors::Response &res);
|
|
54 | 52 |
|
55 | 53 |
#endif |
Also available in: Unified diff