#include <ros.h>
#include <diffbot_msgs/EncodersStamped.h>
#include <diffbot_msgs/WheelsCmdStamped.h>
#include <diffbot_msgs/AngularVelocities.h>
#include <diffbot_msgs/PIDStamped.h>
#include <std_msgs/Empty.h>
#include <sensor_msgs/JointState.h>
#include "diffbot_base_config.h"
#include "encoder_diffbot.h"
#include "adafruit_feather_wing/adafruit_feather_wing.h"
#include "pid.h"
Go to the source code of this file.
Classes | |
class | diffbot::BaseController< TMotorController, TMotorDriver > |
Communicates with the high level hardware_interface::RobotHW and interacts with the robot hardware sensors (e.g. encoders) and actuators (e.g. motor driver). More... | |
struct | diffbot::BaseController< TMotorController, TMotorDriver >::LastUpdateTime |
Keeps track of the last update times. More... | |
struct | diffbot::BaseController< TMotorController, TMotorDriver >::UpdateRate::Period |
Inverse of the update rates for control, (optional) imu and debug output. More... | |
struct | diffbot::BaseController< TMotorController, TMotorDriver >::UpdateRate |
Stores update rate frequencies (Hz) for the main control loop, (optinal) imu and debug output. More... | |
Namespaces | |
diffbot | |
Typedefs | |
template<typename TMotorController , typename TMotorDriver > | |
using | BC = diffbot::BaseController< TMotorController, TMotorDriver > |
using BC = diffbot::BaseController<TMotorController, TMotorDriver> |
Definition at line 380 of file base_controller.h.