blob: b6216d00ebdccfe153dac9e1e3ccd026a84f4c06 [file] [log] [blame]
Brian Silverman26e4e522015-12-17 01:56:40 -05001/*----------------------------------------------------------------------------*/
Brian Silverman1a675112016-02-20 20:42:49 -05002/* Copyright (c) FIRST 2008-2016. All Rights Reserved. */
Brian Silverman26e4e522015-12-17 01:56:40 -05003/* Open Source Software - may be modified and shared by FRC teams. The code */
Brian Silverman1a675112016-02-20 20:42:49 -05004/* must be accompanied by the FIRST BSD license file in the root directory of */
5/* the project. */
Brian Silverman26e4e522015-12-17 01:56:40 -05006/*----------------------------------------------------------------------------*/
7
8#include "RobotDrive.h"
Brian Silverman26e4e522015-12-17 01:56:40 -05009//#include "CANJaguar.h"
10#include "GenericHID.h"
11#include "Joystick.h"
Brian Silverman1a675112016-02-20 20:42:49 -050012#include "Talon.h"
Brian Silverman26e4e522015-12-17 01:56:40 -050013#include "Utility.h"
14#include "WPIErrors.h"
15#include <math.h>
16
17#undef max
18#include <algorithm>
19
20const int32_t RobotDrive::kMaxNumberOfMotors;
21
Brian Silverman1a675112016-02-20 20:42:49 -050022static auto make_shared_nodelete(SpeedController *ptr) {
23 return std::shared_ptr<SpeedController>(ptr, NullDeleter<SpeedController>());
24}
25
Brian Silverman26e4e522015-12-17 01:56:40 -050026/*
27 * Driving functions
28 * These functions provide an interface to multiple motors that is used for C programming
29 * The Drive(speed, direction) function is the main part of the set that makes it easy
30 * to set speeds and direction independently in one call.
31 */
32
33/**
34 * Common function to initialize all the robot drive constructors.
35 * Create a motor safety object (the real reason for the common code) and
36 * initialize all the motor assignments. The default timeout is set for the robot drive.
37 */
38void RobotDrive::InitRobotDrive() {
39 // FIXME: m_safetyHelper = new MotorSafetyHelper(this);
40 // FIXME: m_safetyHelper->SetSafetyEnabled(true);
41}
42
43/** Constructor for RobotDrive with 2 motors specified with channel numbers.
44 * Set up parameters for a two wheel drive system where the
45 * left and right motor pwm channels are specified in the call.
Brian Silverman1a675112016-02-20 20:42:49 -050046 * This call assumes Talosn for controlling the motors.
Brian Silverman26e4e522015-12-17 01:56:40 -050047 * @param leftMotorChannel The PWM channel number that drives the left motor.
48 * @param rightMotorChannel The PWM channel number that drives the right motor.
49 */
50RobotDrive::RobotDrive(uint32_t leftMotorChannel, uint32_t rightMotorChannel)
51{
52 InitRobotDrive();
Brian Silverman1a675112016-02-20 20:42:49 -050053 m_rearLeftMotor = std::make_shared<Talon>(leftMotorChannel);
54 m_rearRightMotor = std::make_shared<Talon>(rightMotorChannel);
Brian Silverman26e4e522015-12-17 01:56:40 -050055 SetLeftRightMotorOutputs(0.0, 0.0);
56 m_deleteSpeedControllers = true;
57}
58
59/**
60 * Constructor for RobotDrive with 4 motors specified with channel numbers.
61 * Set up parameters for a four wheel drive system where all four motor
62 * pwm channels are specified in the call.
Brian Silverman1a675112016-02-20 20:42:49 -050063 * This call assumes Talons for controlling the motors.
Brian Silverman26e4e522015-12-17 01:56:40 -050064 * @param frontLeftMotor Front left motor channel number
65 * @param rearLeftMotor Rear Left motor channel number
66 * @param frontRightMotor Front right motor channel number
67 * @param rearRightMotor Rear Right motor channel number
68 */
69RobotDrive::RobotDrive(uint32_t frontLeftMotor, uint32_t rearLeftMotor,
70 uint32_t frontRightMotor, uint32_t rearRightMotor)
71{
72 InitRobotDrive();
Brian Silverman1a675112016-02-20 20:42:49 -050073 m_rearLeftMotor = std::make_shared<Talon>(rearLeftMotor);
74 m_rearRightMotor = std::make_shared<Talon>(rearRightMotor);
75 m_frontLeftMotor = std::make_shared<Talon>(frontLeftMotor);
76 m_frontRightMotor = std::make_shared<Talon>(frontRightMotor);
Brian Silverman26e4e522015-12-17 01:56:40 -050077 SetLeftRightMotorOutputs(0.0, 0.0);
78 m_deleteSpeedControllers = true;
79}
80
81/**
82 * Constructor for RobotDrive with 2 motors specified as SpeedController objects.
83 * The SpeedController version of the constructor enables programs to use the RobotDrive classes with
84 * subclasses of the SpeedController objects, for example, versions with ramping or reshaping of
85 * the curve to suit motor bias or deadband elimination.
86 * @param leftMotor The left SpeedController object used to drive the robot.
87 * @param rightMotor the right SpeedController object used to drive the robot.
88 */
Brian Silverman1a675112016-02-20 20:42:49 -050089RobotDrive::RobotDrive(SpeedController *leftMotor,
90 SpeedController *rightMotor) {
Brian Silverman26e4e522015-12-17 01:56:40 -050091 InitRobotDrive();
Brian Silverman1a675112016-02-20 20:42:49 -050092 if (leftMotor == nullptr || rightMotor == nullptr) {
Brian Silverman26e4e522015-12-17 01:56:40 -050093 wpi_setWPIError(NullParameter);
94 m_rearLeftMotor = m_rearRightMotor = nullptr;
95 return;
96 }
Brian Silverman1a675112016-02-20 20:42:49 -050097 m_rearLeftMotor = make_shared_nodelete(leftMotor);
98 m_rearRightMotor = make_shared_nodelete(rightMotor);
Brian Silverman26e4e522015-12-17 01:56:40 -050099}
100
Brian Silverman1a675112016-02-20 20:42:49 -0500101//TODO: Change to rvalue references & move syntax.
102RobotDrive::RobotDrive(SpeedController &leftMotor,
103 SpeedController &rightMotor) {
Brian Silverman26e4e522015-12-17 01:56:40 -0500104 InitRobotDrive();
Brian Silverman1a675112016-02-20 20:42:49 -0500105 m_rearLeftMotor = make_shared_nodelete(&leftMotor);
106 m_rearRightMotor = make_shared_nodelete(&rightMotor);
107}
108
109RobotDrive::RobotDrive(std::shared_ptr<SpeedController> leftMotor,
110 std::shared_ptr<SpeedController> rightMotor) {
111 InitRobotDrive();
112 if (leftMotor == nullptr || rightMotor == nullptr) {
113 wpi_setWPIError(NullParameter);
114 m_rearLeftMotor = m_rearRightMotor = nullptr;
115 return;
Brian Silverman26e4e522015-12-17 01:56:40 -0500116 }
Brian Silverman1a675112016-02-20 20:42:49 -0500117 m_rearLeftMotor = leftMotor;
118 m_rearRightMotor = rightMotor;
Brian Silverman26e4e522015-12-17 01:56:40 -0500119}
120
121/**
122 * Constructor for RobotDrive with 4 motors specified as SpeedController objects.
123 * Speed controller input version of RobotDrive (see previous comments).
124 * @param rearLeftMotor The back left SpeedController object used to drive the robot.
125 * @param frontLeftMotor The front left SpeedController object used to drive the robot
126 * @param rearRightMotor The back right SpeedController object used to drive the robot.
127 * @param frontRightMotor The front right SpeedController object used to drive the robot.
128 */
Brian Silverman1a675112016-02-20 20:42:49 -0500129RobotDrive::RobotDrive(SpeedController *frontLeftMotor,
130 SpeedController *rearLeftMotor,
131 SpeedController *frontRightMotor,
132 SpeedController *rearRightMotor) {
Brian Silverman26e4e522015-12-17 01:56:40 -0500133 InitRobotDrive();
Brian Silverman1a675112016-02-20 20:42:49 -0500134 if (frontLeftMotor == nullptr || rearLeftMotor == nullptr ||
135 frontRightMotor == nullptr || rearRightMotor == nullptr) {
136 wpi_setWPIError(NullParameter);
137 return;
138 }
139 m_frontLeftMotor = make_shared_nodelete(frontLeftMotor);
140 m_rearLeftMotor = make_shared_nodelete(rearLeftMotor);
141 m_frontRightMotor = make_shared_nodelete(frontRightMotor);
142 m_rearRightMotor = make_shared_nodelete(rearRightMotor);
143}
144
145RobotDrive::RobotDrive(SpeedController &frontLeftMotor,
146 SpeedController &rearLeftMotor,
147 SpeedController &frontRightMotor,
148 SpeedController &rearRightMotor) {
149 InitRobotDrive();
150 m_frontLeftMotor = make_shared_nodelete(&frontLeftMotor);
151 m_rearLeftMotor = make_shared_nodelete(&rearLeftMotor);
152 m_frontRightMotor = make_shared_nodelete(&frontRightMotor);
153 m_rearRightMotor = make_shared_nodelete(&rearRightMotor);
154}
155
156RobotDrive::RobotDrive(std::shared_ptr<SpeedController> frontLeftMotor,
157 std::shared_ptr<SpeedController> rearLeftMotor,
158 std::shared_ptr<SpeedController> frontRightMotor,
159 std::shared_ptr<SpeedController> rearRightMotor) {
160 InitRobotDrive();
161 if (frontLeftMotor == nullptr || rearLeftMotor == nullptr ||
162 frontRightMotor == nullptr || rearRightMotor == nullptr) {
Brian Silverman26e4e522015-12-17 01:56:40 -0500163 wpi_setWPIError(NullParameter);
164 return;
165 }
166 m_frontLeftMotor = frontLeftMotor;
167 m_rearLeftMotor = rearLeftMotor;
168 m_frontRightMotor = frontRightMotor;
169 m_rearRightMotor = rearRightMotor;
Brian Silverman26e4e522015-12-17 01:56:40 -0500170}
171
172/**
173 * Drive the motors at "outputMagnitude" and "curve".
174 * Both outputMagnitude and curve are -1.0 to +1.0 values, where 0.0 represents
175 * stopped and not turning. curve < 0 will turn left and curve > 0 will turn
176 * right.
177 *
178 * The algorithm for steering provides a constant turn radius for any normal
179 * speed range, both forward and backward. Increasing m_sensitivity causes
180 * sharper turns for fixed values of curve.
181 *
182 * This function will most likely be used in an autonomous routine.
183 *
184 * @param outputMagnitude The speed setting for the outside wheel in a turn,
185 * forward or backwards, +1 to -1.
186 * @param curve The rate of turn, constant for different forward speeds. Set
187 * curve < 0 for left turn or curve > 0 for right turn.
188 * Set curve = e^(-r/w) to get a turn radius r for wheelbase w of your robot.
189 * Conversely, turn radius r = -ln(curve)*w for a given value of curve and
190 * wheelbase w.
191 */
192void RobotDrive::Drive(float outputMagnitude, float curve)
193{
194 float leftOutput, rightOutput;
195 static bool reported = false;
196 if (!reported)
197 {
198 reported = true;
199 }
200
201 if (curve < 0)
202 {
203 float value = log(-curve);
204 float ratio = (value - m_sensitivity)/(value + m_sensitivity);
205 if (ratio == 0) ratio =.0000000001;
206 leftOutput = outputMagnitude / ratio;
207 rightOutput = outputMagnitude;
208 }
209 else if (curve > 0)
210 {
211 float value = log(curve);
212 float ratio = (value - m_sensitivity)/(value + m_sensitivity);
213 if (ratio == 0) ratio =.0000000001;
214 leftOutput = outputMagnitude;
215 rightOutput = outputMagnitude / ratio;
216 }
217 else
218 {
219 leftOutput = outputMagnitude;
220 rightOutput = outputMagnitude;
221 }
222 SetLeftRightMotorOutputs(leftOutput, rightOutput);
223}
224
225/**
226 * Provide tank steering using the stored robot configuration.
227 * Drive the robot using two joystick inputs. The Y-axis will be selected from
228 * each Joystick object.
229 * @param leftStick The joystick to control the left side of the robot.
230 * @param rightStick The joystick to control the right side of the robot.
231 */
232void RobotDrive::TankDrive(GenericHID *leftStick, GenericHID *rightStick, bool squaredInputs)
233{
234 if (leftStick == nullptr || rightStick == nullptr)
235 {
236 wpi_setWPIError(NullParameter);
237 return;
238 }
239 TankDrive(leftStick->GetY(), rightStick->GetY(), squaredInputs);
240}
241
242void RobotDrive::TankDrive(GenericHID &leftStick, GenericHID &rightStick, bool squaredInputs)
243{
244 TankDrive(leftStick.GetY(), rightStick.GetY(), squaredInputs);
245}
246
247/**
248 * Provide tank steering using the stored robot configuration.
249 * This function lets you pick the axis to be used on each Joystick object for the left
250 * and right sides of the robot.
251 * @param leftStick The Joystick object to use for the left side of the robot.
252 * @param leftAxis The axis to select on the left side Joystick object.
253 * @param rightStick The Joystick object to use for the right side of the robot.
254 * @param rightAxis The axis to select on the right side Joystick object.
255 */
256void RobotDrive::TankDrive(GenericHID *leftStick, uint32_t leftAxis,
257 GenericHID *rightStick, uint32_t rightAxis, bool squaredInputs)
258{
259 if (leftStick == nullptr || rightStick == nullptr)
260 {
261 wpi_setWPIError(NullParameter);
262 return;
263 }
264 TankDrive(leftStick->GetRawAxis(leftAxis), rightStick->GetRawAxis(rightAxis), squaredInputs);
265}
266
267void RobotDrive::TankDrive(GenericHID &leftStick, uint32_t leftAxis,
268 GenericHID &rightStick, uint32_t rightAxis, bool squaredInputs)
269{
270 TankDrive(leftStick.GetRawAxis(leftAxis), rightStick.GetRawAxis(rightAxis), squaredInputs);
271}
272
273
274/**
275 * Provide tank steering using the stored robot configuration.
276 * This function lets you directly provide joystick values from any source.
277 * @param leftValue The value of the left stick.
278 * @param rightValue The value of the right stick.
279 */
280void RobotDrive::TankDrive(float leftValue, float rightValue, bool squaredInputs)
281{
282 static bool reported = false;
283 if (!reported)
284 {
285 reported = true;
286 }
287
288 // square the inputs (while preserving the sign) to increase fine control while permitting full power
289 leftValue = Limit(leftValue);
290 rightValue = Limit(rightValue);
291 if(squaredInputs)
292 {
293 if (leftValue >= 0.0)
294 {
295 leftValue = (leftValue * leftValue);
296 }
297 else
298 {
299 leftValue = -(leftValue * leftValue);
300 }
301 if (rightValue >= 0.0)
302 {
303 rightValue = (rightValue * rightValue);
304 }
305 else
306 {
307 rightValue = -(rightValue * rightValue);
308 }
309 }
310
311 SetLeftRightMotorOutputs(leftValue, rightValue);
312}
313
314/**
315 * Arcade drive implements single stick driving.
316 * Given a single Joystick, the class assumes the Y axis for the move value and the X axis
317 * for the rotate value.
318 * (Should add more information here regarding the way that arcade drive works.)
319 * @param stick The joystick to use for Arcade single-stick driving. The Y-axis will be selected
320 * for forwards/backwards and the X-axis will be selected for rotation rate.
321 * @param squaredInputs If true, the sensitivity will be increased for small values
322 */
323void RobotDrive::ArcadeDrive(GenericHID *stick, bool squaredInputs)
324{
325 // simply call the full-featured ArcadeDrive with the appropriate values
326 ArcadeDrive(stick->GetY(), stick->GetX(), squaredInputs);
327}
328
329/**
330 * Arcade drive implements single stick driving.
331 * Given a single Joystick, the class assumes the Y axis for the move value and the X axis
332 * for the rotate value.
333 * (Should add more information here regarding the way that arcade drive works.)
334 * @param stick The joystick to use for Arcade single-stick driving. The Y-axis will be selected
335 * for forwards/backwards and the X-axis will be selected for rotation rate.
336 * @param squaredInputs If true, the sensitivity will be increased for small values
337 */
338void RobotDrive::ArcadeDrive(GenericHID &stick, bool squaredInputs)
339{
340 // simply call the full-featured ArcadeDrive with the appropriate values
341 ArcadeDrive(stick.GetY(), stick.GetX(), squaredInputs);
342}
343
344/**
345 * Arcade drive implements single stick driving.
346 * Given two joystick instances and two axis, compute the values to send to either two
347 * or four motors.
348 * @param moveStick The Joystick object that represents the forward/backward direction
349 * @param moveAxis The axis on the moveStick object to use for fowards/backwards (typically Y_AXIS)
350 * @param rotateStick The Joystick object that represents the rotation value
351 * @param rotateAxis The axis on the rotation object to use for the rotate right/left (typically X_AXIS)
352 * @param squaredInputs Setting this parameter to true increases the sensitivity at lower speeds
353 */
354void RobotDrive::ArcadeDrive(GenericHID* moveStick, uint32_t moveAxis,
355 GenericHID* rotateStick, uint32_t rotateAxis,
356 bool squaredInputs)
357{
358 float moveValue = moveStick->GetRawAxis(moveAxis);
359 float rotateValue = rotateStick->GetRawAxis(rotateAxis);
360
361 ArcadeDrive(moveValue, rotateValue, squaredInputs);
362}
363
364/**
365 * Arcade drive implements single stick driving.
366 * Given two joystick instances and two axis, compute the values to send to either two
367 * or four motors.
368 * @param moveStick The Joystick object that represents the forward/backward direction
369 * @param moveAxis The axis on the moveStick object to use for fowards/backwards (typically Y_AXIS)
370 * @param rotateStick The Joystick object that represents the rotation value
371 * @param rotateAxis The axis on the rotation object to use for the rotate right/left (typically X_AXIS)
372 * @param squaredInputs Setting this parameter to true increases the sensitivity at lower speeds
373 */
374
375void RobotDrive::ArcadeDrive(GenericHID &moveStick, uint32_t moveAxis,
376 GenericHID &rotateStick, uint32_t rotateAxis,
377 bool squaredInputs)
378{
379 float moveValue = moveStick.GetRawAxis(moveAxis);
380 float rotateValue = rotateStick.GetRawAxis(rotateAxis);
381
382 ArcadeDrive(moveValue, rotateValue, squaredInputs);
383}
384
385/**
386 * Arcade drive implements single stick driving.
387 * This function lets you directly provide joystick values from any source.
388 * @param moveValue The value to use for fowards/backwards
389 * @param rotateValue The value to use for the rotate right/left
390 * @param squaredInputs If set, increases the sensitivity at low speeds
391 */
392void RobotDrive::ArcadeDrive(float moveValue, float rotateValue, bool squaredInputs)
393{
394 static bool reported = false;
395 if (!reported)
396 {
397 reported = true;
398 }
399
400 // local variables to hold the computed PWM values for the motors
401 float leftMotorOutput;
402 float rightMotorOutput;
403
404 moveValue = Limit(moveValue);
405 rotateValue = Limit(rotateValue);
406
407 if (squaredInputs)
408 {
409 // square the inputs (while preserving the sign) to increase fine control while permitting full power
410 if (moveValue >= 0.0)
411 {
412 moveValue = (moveValue * moveValue);
413 }
414 else
415 {
416 moveValue = -(moveValue * moveValue);
417 }
418 if (rotateValue >= 0.0)
419 {
420 rotateValue = (rotateValue * rotateValue);
421 }
422 else
423 {
424 rotateValue = -(rotateValue * rotateValue);
425 }
426 }
427
428 if (moveValue > 0.0)
429 {
430 if (rotateValue > 0.0)
431 {
432 leftMotorOutput = moveValue - rotateValue;
433 rightMotorOutput = std::max(moveValue, rotateValue);
434 }
435 else
436 {
437 leftMotorOutput = std::max(moveValue, -rotateValue);
438 rightMotorOutput = moveValue + rotateValue;
439 }
440 }
441 else
442 {
443 if (rotateValue > 0.0)
444 {
445 leftMotorOutput = - std::max(-moveValue, rotateValue);
446 rightMotorOutput = moveValue + rotateValue;
447 }
448 else
449 {
450 leftMotorOutput = moveValue - rotateValue;
451 rightMotorOutput = - std::max(-moveValue, -rotateValue);
452 }
453 }
454 SetLeftRightMotorOutputs(leftMotorOutput, rightMotorOutput);
455}
456
457/**
458 * Drive method for Mecanum wheeled robots.
459 *
460 * A method for driving with Mecanum wheeled robots. There are 4 wheels
461 * on the robot, arranged so that the front and back wheels are toed in 45 degrees.
462 * When looking at the wheels from the top, the roller axles should form an X across the robot.
463 *
464 * This is designed to be directly driven by joystick axes.
465 *
466 * @param x The speed that the robot should drive in the X direction. [-1.0..1.0]
467 * @param y The speed that the robot should drive in the Y direction.
468 * This input is inverted to match the forward == -1.0 that joysticks produce. [-1.0..1.0]
469 * @param rotation The rate of rotation for the robot that is completely independent of
470 * the translation. [-1.0..1.0]
471 * @param gyroAngle The current angle reading from the gyro. Use this to implement field-oriented controls.
472 */
473void RobotDrive::MecanumDrive_Cartesian(float x, float y, float rotation, float gyroAngle)
474{
475 static bool reported = false;
476 if (!reported)
477 {
478 reported = true;
479 }
480
481 double xIn = x;
482 double yIn = y;
483 // Negate y for the joystick.
484 yIn = -yIn;
485 // Compenstate for gyro angle.
486 RotateVector(xIn, yIn, gyroAngle);
487
488 double wheelSpeeds[kMaxNumberOfMotors];
489 wheelSpeeds[kFrontLeftMotor] = xIn + yIn + rotation;
490 wheelSpeeds[kFrontRightMotor] = -xIn + yIn - rotation;
491 wheelSpeeds[kRearLeftMotor] = -xIn + yIn + rotation;
492 wheelSpeeds[kRearRightMotor] = xIn + yIn - rotation;
493
494 Normalize(wheelSpeeds);
495
496 uint8_t syncGroup = 0x80;
497
498 m_frontLeftMotor->Set(wheelSpeeds[kFrontLeftMotor] * m_invertedMotors[kFrontLeftMotor] * m_maxOutput, syncGroup);
499 m_frontRightMotor->Set(wheelSpeeds[kFrontRightMotor] * m_invertedMotors[kFrontRightMotor] * m_maxOutput, syncGroup);
500 m_rearLeftMotor->Set(wheelSpeeds[kRearLeftMotor] * m_invertedMotors[kRearLeftMotor] * m_maxOutput, syncGroup);
501 m_rearRightMotor->Set(wheelSpeeds[kRearRightMotor] * m_invertedMotors[kRearRightMotor] * m_maxOutput, syncGroup);
502
503 // CANJaguar::UpdateSyncGroup(syncGroup);
504
505 // FIXME: m_safetyHelper->Feed();
506}
507
508/**
509 * Drive method for Mecanum wheeled robots.
510 *
511 * A method for driving with Mecanum wheeled robots. There are 4 wheels
512 * on the robot, arranged so that the front and back wheels are toed in 45 degrees.
513 * When looking at the wheels from the top, the roller axles should form an X across the robot.
514 *
515 * @param magnitude The speed that the robot should drive in a given direction. [-1.0..1.0]
516 * @param direction The direction the robot should drive in degrees. The direction and maginitute are
517 * independent of the rotation rate.
518 * @param rotation The rate of rotation for the robot that is completely independent of
519 * the magnitute or direction. [-1.0..1.0]
520 */
521void RobotDrive::MecanumDrive_Polar(float magnitude, float direction, float rotation)
522{
523 static bool reported = false;
524 if (!reported)
525 {
526 reported = true;
527 }
528
529 // Normalized for full power along the Cartesian axes.
530 magnitude = Limit(magnitude) * sqrt(2.0);
531 // The rollers are at 45 degree angles.
532 double dirInRad = (direction + 45.0) * 3.14159 / 180.0;
533 double cosD = cos(dirInRad);
534 double sinD = sin(dirInRad);
535
536 double wheelSpeeds[kMaxNumberOfMotors];
537 wheelSpeeds[kFrontLeftMotor] = sinD * magnitude + rotation;
538 wheelSpeeds[kFrontRightMotor] = cosD * magnitude - rotation;
539 wheelSpeeds[kRearLeftMotor] = cosD * magnitude + rotation;
540 wheelSpeeds[kRearRightMotor] = sinD * magnitude - rotation;
541
542 Normalize(wheelSpeeds);
543
544 uint8_t syncGroup = 0x80;
545
546 m_frontLeftMotor->Set(wheelSpeeds[kFrontLeftMotor] * m_invertedMotors[kFrontLeftMotor] * m_maxOutput, syncGroup);
547 m_frontRightMotor->Set(wheelSpeeds[kFrontRightMotor] * m_invertedMotors[kFrontRightMotor] * m_maxOutput, syncGroup);
548 m_rearLeftMotor->Set(wheelSpeeds[kRearLeftMotor] * m_invertedMotors[kRearLeftMotor] * m_maxOutput, syncGroup);
549 m_rearRightMotor->Set(wheelSpeeds[kRearRightMotor] * m_invertedMotors[kRearRightMotor] * m_maxOutput, syncGroup);
550
551 // CANJaguar::UpdateSyncGroup(syncGroup);
552
553 // FIXME: m_safetyHelper->Feed();
554}
555
556/**
557 * Holonomic Drive method for Mecanum wheeled robots.
558 *
559 * This is an alias to MecanumDrive_Polar() for backward compatability
560 *
561 * @param magnitude The speed that the robot should drive in a given direction. [-1.0..1.0]
562 * @param direction The direction the robot should drive. The direction and maginitute are
563 * independent of the rotation rate.
564 * @param rotation The rate of rotation for the robot that is completely independent of
565 * the magnitute or direction. [-1.0..1.0]
566 */
567void RobotDrive::HolonomicDrive(float magnitude, float direction, float rotation)
568{
569 MecanumDrive_Polar(magnitude, direction, rotation);
570}
571
572/** Set the speed of the right and left motors.
573 * This is used once an appropriate drive setup function is called such as
574 * TwoWheelDrive(). The motors are set to "leftOutput" and "rightOutput"
575 * and includes flipping the direction of one side for opposing motors.
576 * @param leftOutput The speed to send to the left side of the robot.
577 * @param rightOutput The speed to send to the right side of the robot.
578 */
579void RobotDrive::SetLeftRightMotorOutputs(float leftOutput, float rightOutput)
580{
581 wpi_assert(m_rearLeftMotor != nullptr && m_rearRightMotor != nullptr);
582
583 uint8_t syncGroup = 0x80;
584
585 if (m_frontLeftMotor != nullptr)
586 m_frontLeftMotor->Set(Limit(leftOutput) * m_invertedMotors[kFrontLeftMotor] * m_maxOutput, syncGroup);
587 m_rearLeftMotor->Set(Limit(leftOutput) * m_invertedMotors[kRearLeftMotor] * m_maxOutput, syncGroup);
588
589 if (m_frontRightMotor != nullptr)
590 m_frontRightMotor->Set(-Limit(rightOutput) * m_invertedMotors[kFrontRightMotor] * m_maxOutput, syncGroup);
591 m_rearRightMotor->Set(-Limit(rightOutput) * m_invertedMotors[kRearRightMotor] * m_maxOutput, syncGroup);
592
593 // CANJaguar::UpdateSyncGroup(syncGroup);
594
595 // FIXME: m_safetyHelper->Feed();
596}
597
598/**
599 * Limit motor values to the -1.0 to +1.0 range.
600 */
601float RobotDrive::Limit(float num)
602{
603 if (num > 1.0)
604 {
605 return 1.0;
606 }
607 if (num < -1.0)
608 {
609 return -1.0;
610 }
611 return num;
612}
613
614/**
615 * Normalize all wheel speeds if the magnitude of any wheel is greater than 1.0.
616 */
617void RobotDrive::Normalize(double *wheelSpeeds)
618{
619 double maxMagnitude = fabs(wheelSpeeds[0]);
620 int32_t i;
621 for (i=1; i<kMaxNumberOfMotors; i++)
622 {
623 double temp = fabs(wheelSpeeds[i]);
624 if (maxMagnitude < temp) maxMagnitude = temp;
625 }
626 if (maxMagnitude > 1.0)
627 {
628 for (i=0; i<kMaxNumberOfMotors; i++)
629 {
630 wheelSpeeds[i] = wheelSpeeds[i] / maxMagnitude;
631 }
632 }
633}
634
635/**
636 * Rotate a vector in Cartesian space.
637 */
638void RobotDrive::RotateVector(double &x, double &y, double angle)
639{
640 double cosA = cos(angle * (3.14159 / 180.0));
641 double sinA = sin(angle * (3.14159 / 180.0));
642 double xOut = x * cosA - y * sinA;
643 double yOut = x * sinA + y * cosA;
644 x = xOut;
645 y = yOut;
646}
647
648/*
649 * Invert a motor direction.
650 * This is used when a motor should run in the opposite direction as the drive
651 * code would normally run it. Motors that are direct drive would be inverted, the
652 * Drive code assumes that the motors are geared with one reversal.
653 * @param motor The motor index to invert.
654 * @param isInverted True if the motor should be inverted when operated.
655 */
656void RobotDrive::SetInvertedMotor(MotorType motor, bool isInverted)
657{
658 if (motor < 0 || motor > 3)
659 {
660 wpi_setWPIError(InvalidMotorIndex);
661 return;
662 }
663 m_invertedMotors[motor] = isInverted ? -1 : 1;
664}
665
666/**
667 * Set the turning sensitivity.
668 *
669 * This only impacts the Drive() entry-point.
670 * @param sensitivity Effectively sets the turning sensitivity (or turn radius for a given value)
671 */
672void RobotDrive::SetSensitivity(float sensitivity)
673{
674 m_sensitivity = sensitivity;
675}
676
677/**
678 * Configure the scaling factor for using RobotDrive with motor controllers in a mode other than PercentVbus.
679 * @param maxOutput Multiplied with the output percentage computed by the drive functions.
680 */
681void RobotDrive::SetMaxOutput(double maxOutput)
682{
683 m_maxOutput = maxOutput;
684}
685
686
687
688void RobotDrive::SetExpiration(float timeout)
689{
690 // FIXME: m_safetyHelper->SetExpiration(timeout);
691}
692
693float RobotDrive::GetExpiration() const
694{
695 return -1; // FIXME: return m_safetyHelper->GetExpiration();
696}
697
698bool RobotDrive::IsAlive() const
699{
700 return true; // FIXME: m_safetyHelper->IsAlive();
701}
702
703bool RobotDrive::IsSafetyEnabled() const
704{
705 return false; // FIXME: return m_safetyHelper->IsSafetyEnabled();
706}
707
708void RobotDrive::SetSafetyEnabled(bool enabled)
709{
710 // FIXME: m_safetyHelper->SetSafetyEnabled(enabled);
711}
712
713void RobotDrive::GetDescription(std::ostringstream& desc) const
714{
715 desc << "RobotDrive";
716}
717
718void RobotDrive::StopMotor()
719{
720 if (m_frontLeftMotor != nullptr) m_frontLeftMotor->Disable();
721 if (m_frontRightMotor != nullptr) m_frontRightMotor->Disable();
722 if (m_rearLeftMotor != nullptr) m_rearLeftMotor->Disable();
723 if (m_rearRightMotor != nullptr) m_rearRightMotor->Disable();
724}