Skip to content

Commit 54e130b

Browse files
committed
fix: test_encoders.cpp include name
1 parent 1330318 commit 54e130b

File tree

1 file changed

+11
-4
lines changed

1 file changed

+11
-4
lines changed

diffbot_base/scripts/base_controller/test/encoders/test_encoders.cpp

Lines changed: 11 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -5,31 +5,38 @@
55
* Turn the wheels by hand and check the output in the serial monitor.
66
*/
77

8+
// Include unity library
9+
// For details see https://docs.platformio.org/en/latest/plus/unit-testing.html#api
810
#include <unity.h>
911

12+
#include <ros.h>
1013
#include "diffbot_base_config.h"
11-
#include "encoder.h"
14+
#include "encoder_diffbot.h"
1215

1316

17+
// ROS node handle
18+
ros::NodeHandle nh;
19+
1420
// Encoder setup
1521
// Change these pin numbers to the pins connected to your encoder.
1622
// Best Performance: both pins have interrupt capability
1723
// Good Performance: only the first pin has interrupt capability
1824
// Low Performance: neither pin has interrupt capability
19-
diffbot::Encoder encoderLeft(ENCODER_LEFT_H1, ENCODER_LEFT_H2); // Default pins 5, 6
20-
diffbot::Encoder encoderRight(ENCODER_RIGHT_H1, ENCODER_RIGHT_H2); // Default pins 7, 8
25+
diffbot::Encoder encoderLeft(nh, ENCODER_LEFT_H1, ENCODER_LEFT_H2, ENCODER_RESOLUTION); // Default pins 5, 6
26+
diffbot::Encoder encoderRight(nh, ENCODER_RIGHT_H1, ENCODER_RIGHT_H2, ENCODER_RESOLUTION); // Default pins 7, 8
2127
// avoid using pins with LEDs attached
2228

2329
void setup() {
2430
Serial.begin(115200);
2531
Serial.println("DiffBot Wheel Encoders:");
32+
Serial.println("Trun wheels by hand to check for correct encoder output.");
2633
}
2734

2835
long positionLeft = -999;
2936
long positionRight = -999;
3037

3138
int test_start_time = millis();
32-
int test_max_time = 5000;
39+
int test_max_time = 8000;
3340

3441
void loop() {
3542
UNITY_BEGIN();

0 commit comments

Comments
 (0)