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


diffbot_base
Author(s):
autogenerated on Thu Sep 7 2023 02:35:23