-
-
Notifications
You must be signed in to change notification settings - Fork 95
/
Copy pathmain.cpp
85 lines (70 loc) · 2.71 KB
/
main.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
#include <ros.h>
#include "diffbot_base_config.h"
#include "base_controller.h"
#include "adafruit_feather_wing/adafruit_feather_wing.h"
ros::NodeHandle nh;
using namespace diffbot;
AdafruitMotorController motor_controller_right = AdafruitMotorController(MOTOR_RIGHT);
AdafruitMotorController motor_controller_left = AdafruitMotorController(MOTOR_LEFT);
BaseController<AdafruitMotorController, Adafruit_MotorShield> base_controller(nh, &motor_controller_left, &motor_controller_right);
void setup()
{
base_controller.setup();
base_controller.init();
nh.loginfo("Initialize DiffBot Motor Controllers");
motor_controller_left.begin();
motor_controller_right.begin();
nh.loginfo("Setup finished");
}
void loop()
{
static bool imu_is_initialized;
// The main control loop for the base_conroller.
// This block drives the robot based on a defined control rate
ros::Duration command_dt = nh.now() - base_controller.lastUpdateTime().control;
if (command_dt.toSec() >= ros::Duration(1.0 / base_controller.publishRate().control_, 0).toSec())
{
base_controller.read();
base_controller.write();
base_controller.lastUpdateTime().control = nh.now();
}
// This block stops the motor when no wheel command is received
// from the high level hardware_interface::RobotHW
command_dt = nh.now() - base_controller.lastUpdateTime().command_received;
if (command_dt.toSec() >= ros::Duration(E_STOP_COMMAND_RECEIVED_DURATION, 0).toSec())
{
nh.logwarn("Emergency STOP");
base_controller.eStop();
}
// This block publishes the IMU data based on a defined imu rate
ros::Duration imu_dt = nh.now() - base_controller.lastUpdateTime().imu;
if (imu_dt.toSec() >= base_controller.publishRate().period().imu_)
{
// Sanity check if the IMU is connected
if (!imu_is_initialized)
{
//imu_is_initialized = initIMU();
if(imu_is_initialized)
nh.loginfo("IMU Initialized");
else
nh.logfatal("IMU failed to initialize. Check your IMU connection.");
}
else
{
//publishIMU();
}
base_controller.lastUpdateTime().imu = nh.now();
}
// This block displays the encoder readings. change DEBUG to 0 if you don't want to display
if(base_controller.debug())
{
ros::Duration debug_dt = nh.now() - base_controller.lastUpdateTime().debug;
if (debug_dt.toSec() >= base_controller.publishRate().period().debug_)
{
base_controller.printDebug();
base_controller.lastUpdateTime().debug = nh.now();
}
}
// Call all the callbacks waiting to be called
nh.spinOnce();
}