45 |
45 |
* @{
|
46 |
46 |
**/
|
47 |
47 |
|
48 |
|
/* Motor state variables */
|
|
48 |
/* Motor state variables
|
|
49 |
* Speeds expressed as absolute speed out of max speed (0 - +-MAXSPEED)
|
|
50 |
* Absolute speed is the speed written to the hardware to move the motors
|
|
51 |
*/
|
49 |
52 |
/** @todo Fix types: static */
|
50 |
53 |
int motor_fl_speed; /**< The current speed of the front left motor. */
|
51 |
54 |
int motor_fr_speed; /**< The current speed of the front right motor. */
|
... | ... | |
62 |
65 |
*/
|
63 |
66 |
void motors_set(const motors::set_motors::ConstPtr& msg)
|
64 |
67 |
{
|
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;
|
|
68 |
/** @todo Edit to only set requested motors, not all */
|
|
69 |
int which = msg->which;
|
|
70 |
if(which & MOTOR_FL_REV)
|
|
71 |
{
|
|
72 |
motor_fl_speed = -1 * motors_rel_to_abs(msg->fl_speed, msg->units);
|
|
73 |
}
|
|
74 |
if(which & MOTOR_FR_REV)
|
|
75 |
{
|
|
76 |
motor_fr_speed = -1 * motors_rel_to_abs(msg->fr_speed, msg->units);
|
|
77 |
}
|
|
78 |
if(which & MOTOR_BL_REV)
|
|
79 |
{
|
|
80 |
motor_bl_speed = -1 * motors_rel_to_abs(msg->bl_speed, msg->units);
|
|
81 |
}
|
|
82 |
if(which & MOTOR_BR_REV)
|
|
83 |
{
|
|
84 |
motor_br_speed = -1 * motors_rel_to_abs(msg->br_speed, msg->units);
|
|
85 |
}
|
|
86 |
if(which & MOTOR_FL)
|
|
87 |
{
|
|
88 |
motor_fl_speed = motors_rel_to_abs(msg->fl_speed, msg->units);
|
|
89 |
}
|
|
90 |
if(which & MOTOR_FR)
|
|
91 |
{
|
|
92 |
motor_fr_speed = motors_rel_to_abs(msg->fr_speed, msg->units);
|
|
93 |
}
|
|
94 |
if(which & MOTOR_BL)
|
|
95 |
{
|
|
96 |
motor_bl_speed = motors_rel_to_abs(msg->bl_speed, msg->units);
|
|
97 |
}
|
|
98 |
if(which & MOTOR_BR)
|
|
99 |
{
|
|
100 |
motor_br_speed = motors_rel_to_abs(msg->br_speed, msg->units);
|
|
101 |
}
|
|
102 |
|
|
103 |
/* Write speeds to hardware */
|
|
104 |
/** @todo Add code to write speeds to hardware */
|
70 |
105 |
}
|
71 |
106 |
|
72 |
107 |
/**
|
... | ... | |
74 |
109 |
*
|
75 |
110 |
* Serves the service query_motors by responding to service requests with the
|
76 |
111 |
* speeds of the motors.
|
77 |
|
* @param req The request. Should be empty.
|
|
112 |
* @param req The request. The only field is the units requested.
|
78 |
113 |
* @param res The response. The fields will be filled with values.
|
79 |
114 |
*/
|
80 |
115 |
bool motors_query(motors::query_motors::Request &req,
|
81 |
116 |
motors::query_motors::Response &res)
|
82 |
117 |
{
|
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;
|
|
118 |
int units = req.units;
|
|
119 |
res.fl_speed = motors_abs_to_rel(motor_fl_speed, units);
|
|
120 |
res.fr_speed = motors_abs_to_rel(motor_fr_speed, units);
|
|
121 |
res.bl_speed = motors_abs_to_rel(motor_bl_speed, units);
|
|
122 |
res.br_speed = motors_abs_to_rel(motor_br_speed, units);
|
87 |
123 |
|
88 |
124 |
ROS_DEBUG("Motor speeds queried");
|
89 |
125 |
return true;
|
90 |
126 |
}
|
91 |
127 |
|
92 |
128 |
/**
|
|
129 |
* @brief Converts set speeds (of various units) to absolute speeds.
|
|
130 |
*
|
|
131 |
* @param speed The speed expressed in the desired units
|
|
132 |
* @param units The units the desired speed is measured in
|
|
133 |
* @return The absolute speed of the motor
|
|
134 |
**/
|
|
135 |
int motors_rel_to_abs(int rel_speed, int units)
|
|
136 |
{
|
|
137 |
switch(units)
|
|
138 |
{
|
|
139 |
case MOTOR_ABSOLUTE:/* Speed given as absolute */
|
|
140 |
return rel_speed;
|
|
141 |
case MOTOR_PERCENT:/* Convert from percentage */
|
|
142 |
return rel_speed * MAXSPEED / 100;
|
|
143 |
case MOTOR_MMS:/* Convert from mm/s */
|
|
144 |
/** @todo Make math to do this conversion **/
|
|
145 |
return rel_speed;
|
|
146 |
case MOTOR_CMS:/* Convert from cm/s */
|
|
147 |
/** @todo Make math to do this conversion **/
|
|
148 |
return rel_speed;
|
|
149 |
default: /* The units aren't recognized */
|
|
150 |
/** @todo Decide on default case. Either percent or absolute. **/
|
|
151 |
return rel_speed;
|
|
152 |
}
|
|
153 |
}
|
|
154 |
|
|
155 |
/**
|
|
156 |
* @brief Convert absolute speeds to speeds of various units.
|
|
157 |
*
|
|
158 |
* @param speed The speed expressed in absolute units.
|
|
159 |
* @param units The units the desired speed is measured in.
|
|
160 |
* @return The relative speed of the motor in desired units.
|
|
161 |
**/
|
|
162 |
int motors_abs_to_rel(int abs_speed, int units)
|
|
163 |
{
|
|
164 |
switch(units)
|
|
165 |
{
|
|
166 |
case MOTOR_ABSOLUTE:/* Speed given as absolute */
|
|
167 |
return abs_speed;
|
|
168 |
case MOTOR_PERCENT:/* Convert from percentage */
|
|
169 |
return abs_speed * 100 / MAXSPEED;
|
|
170 |
case MOTOR_MMS:/* Convert from mm/s */
|
|
171 |
/** @todo Make math to do this conversion **/
|
|
172 |
return abs_speed;
|
|
173 |
case MOTOR_CMS:/* Convert from cm/s */
|
|
174 |
/** @todo Make math to do this conversion **/
|
|
175 |
return abs_speed;
|
|
176 |
default: /* The units aren't recognized */
|
|
177 |
/** @todo Decide on default case. Either percent or absolute. **/
|
|
178 |
return abs_speed;
|
|
179 |
}
|
|
180 |
}
|
|
181 |
|
|
182 |
/**
|
93 |
183 |
* @brief Motors driver. This is a ROS node that controls motor speeds.
|
94 |
184 |
*
|
95 |
185 |
* This is the main function for the motors node. It is run when the node
|