root / scout / libscout / src / libmotors.cpp @ 0121ead7
History | View | Annotate | Download (3.98 KB)
1 | c406f16b | Ben | /**
|
---|---|---|---|
2 | 0121ead7 | bwasserm | * Copyright (c) 2011 Colony Project
|
3 | c406f16b | Ben | *
|
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 libmotors.cpp
|
||
29 | * @brief Contains motor declarations and functions
|
||
30 | *
|
||
31 | * Contains functions and definitions for the use of
|
||
32 | * motors
|
||
33 | *
|
||
34 | * @author Colony Project, CMU Robotics Club
|
||
35 | **/
|
||
36 | |||
37 | /* Author: Ben Wasserman
|
||
38 | */
|
||
39 | |||
40 | #include "libmotors.h" |
||
41 | |||
42 | 0121ead7 | bwasserm | /* ROS node created in libscout.cpp */
|
43 | extern ros::NodeHandle libscout_node;
|
||
44 | |||
45 | /** ROS publisher and client declaration */
|
||
46 | ros::Publisher set_motors_publisher; |
||
47 | ros::ServiceClient query_motors_client; |
||
48 | |||
49 | /*!
|
||
50 | * \brief Initialize the motors module of libscout.
|
||
51 | *
|
||
52 | * Initialize the libscout node as a publisher of set_motors and a client of
|
||
53 | * query_motors.
|
||
54 | */
|
||
55 | c406f16b | Ben | void libmotors_init(){
|
56 | set_motors_publisher = libscout_node.advertise<motors::set_motors>("libmotors", 10); |
||
57 | query_motors_client = libscout_node.serviceClient<motors::query_motors>("libmotors");
|
||
58 | } |
||
59 | |||
60 | 0121ead7 | bwasserm | /*!
|
61 | * \brief Set motor speeds
|
||
62 | * Sets the speeds of the motors as a percentage of top speed. Can selectively
|
||
63 | * select which motors to set, and which to remain at previous speed.
|
||
64 | * \param speed The speed the motors should be set to
|
||
65 | * \param which A bitmask of which motors should be set
|
||
66 | * \return Function status
|
||
67 | */
|
||
68 | int motors_set(int speed, int which, char units=MOTOR_PERCENT){ |
||
69 | c406f16b | Ben | /** \todo Set fields of the message based on params */
|
70 | |||
71 | if(!ros::ok()){
|
||
72 | return LIB_ERROR;
|
||
73 | } |
||
74 | 0121ead7 | bwasserm | |
75 | /* Set the speed for each motor according to the which bitmask*/
|
||
76 | c406f16b | Ben | motors::set_motors msg; |
77 | 0121ead7 | bwasserm | if(which & MOTOR_FL_REV){
|
78 | msg.fl_speed = -1 * speed;
|
||
79 | } |
||
80 | if(which & MOTOR_FR_REV){
|
||
81 | msg.fr_speed = -1 * speed;
|
||
82 | } |
||
83 | if(which & MOTOR_BL_REV){
|
||
84 | msg.bl_speed = -1 * speed;
|
||
85 | } |
||
86 | if(which & MOTOR_BR_REV){
|
||
87 | msg.br_speed = -1 * speed;
|
||
88 | }if(which & MOTOR_FL){
|
||
89 | msg.fl_speed = speed; |
||
90 | } |
||
91 | if(which & MOTOR_FR){
|
||
92 | msg.fr_speed = speed; |
||
93 | } |
||
94 | if(which & MOTOR_BL){
|
||
95 | msg.bl_speed = speed; |
||
96 | } |
||
97 | if(which & MOTOR_BR){
|
||
98 | msg.br_speed = speed; |
||
99 | } |
||
100 | |||
101 | /* Specify which units the speeds are given in */
|
||
102 | msg.units = units; |
||
103 | c406f16b | Ben | |
104 | 0121ead7 | bwasserm | /* Publishes message to set_motors topic */
|
105 | set_motors_publisher.publish(msg); |
||
106 | c406f16b | Ben | ros::spinOnce(); |
107 | |||
108 | return LIB_OK;
|
||
109 | } |
||
110 | |||
111 | 0121ead7 | bwasserm | /*!
|
112 | * \brief Query the current speeds of the motors
|
||
113 | *
|
||
114 | * Sends a request to the query_motors service which will reply with the
|
||
115 | * current speed of each motor.
|
||
116 | *
|
||
117 | * \param which A bitmask that will specify which motor speed should be
|
||
118 | * returned
|
||
119 | * \return The speed of the selected motor, or LIB_ERR if no motor selected
|
||
120 | */
|
||
121 | c406f16b | Ben | |
122 | int motors_query(int which){ |
||
123 | motors::query_motors srv; |
||
124 | if(query_motors_client.call(srv)){
|
||
125 | switch(which){
|
||
126 | case MOTOR_FL:
|
||
127 | return srv.response.fl_speed;
|
||
128 | case MOTOR_FR:
|
||
129 | return srv.response.fr_speed;
|
||
130 | case MOTOR_BL:
|
||
131 | return srv.response.bl_speed;
|
||
132 | case MOTOR_BR:
|
||
133 | return srv.response.br_speed;
|
||
134 | 0121ead7 | bwasserm | default:
|
135 | c406f16b | Ben | ROS_WARN("Bad WHICH in motors_query.");
|
136 | return LIB_ERROR;
|
||
137 | } |
||
138 | }else{
|
||
139 | ROS_ERROR("Failed to call service query_motors");
|
||
140 | return LIB_ERROR;
|
||
141 | } |
||
142 | |||
143 | return 0; |
||
144 | } |