IOTBot.h
Go to the documentation of this file.
1 #ifndef IOTBOT_H_
2 #define IOTBOT_H_
3 
4 #include <ros/ros.h>
5 #include <sensor_msgs/Joy.h>
6 #include <geometry_msgs/Twist.h>
7 #include <std_msgs/Float32.h>
8 #include <std_msgs/Float32MultiArray.h>
9 #include <std_srvs/SetBool.h>
10 #include <std_srvs/Empty.h>
11 #include <sensor_msgs/Imu.h>
12 #include <geometry_msgs/PoseStamped.h>
13 #include <iostream>
14 #include "IOTShield.h"
15 
16 using namespace std;
17 
18 namespace iotbot
19 {
20 
27 {
28  float gearRatio;
29  float encoderRatio;
30  float rpmMax;
32  float kp;
33  float ki;
34  float kd;
37 
42  {
43  gearRatio = 0.f;
44  encoderRatio = 0.f;
45  rpmMax = 0.f;
46  controlFrequency = 16000;
47  kp = 0.f;
48  ki = 0.f;
49  kd = 0.f;
50  lowPassInputFilter = 1.f;
51  lowPassEncoderTicks = 1.f;
52  }
53 
59  {
60  gearRatio = p.gearRatio;
61  encoderRatio = p.encoderRatio;
62  rpmMax = p.rpmMax;
63  controlFrequency = p.controlFrequency;
64  kp = p.kp;
65  ki = p.ki;
66  kd = p.kd;
67  lowPassInputFilter = p.lowPassInputFilter;
68  lowPassEncoderTicks = p.lowPassEncoderTicks;
69  }
70 };
71 
78 {
79  float track;
80  float wheelBase;
86  int direction;
88 
90  {
91  track = 0.f;
92  wheelBase = 0.f;
93  wheelDiameter = 0.f;
94  chFrontLeft = 0;
95  chFrontRight = 0;
96  chRearLeft = 0;
97  chRearRight = 0;
98  direction = 0;
99  enableYMotion = 0;
100  }
101 };
102 
108 class IOTBot
109 {
110 public:
111 
117  IOTBot(ChassisParams &chassisParams, MotorParams &motorParams);
118 
122  ~IOTBot();
123 
127  void run();
128 
129 private:
130 
137  bool enableCallback(std_srvs::SetBool::Request& request, std_srvs::SetBool::Response& response);
138 
143  bool calibrateCallback(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response);
144 
151  bool fixIMUZAxisCallback(std_srvs::SetBool::Request& request, std_srvs::SetBool::Response& response);
152 
157  void joyCallback(const sensor_msgs::Joy::ConstPtr& joy);
158 
163  void velocityCallback(const geometry_msgs::Twist::ConstPtr& cmd);
164 
171  void controlMotors(float vFwd, float vLeft, float omega);
172 
189 
190  // revolutions per minute for each channel
191  float _rpm[4];
192 
193  // maximum velocity [m/s]
194  float _vMax;
195 
196  // maximum rotating rate [rad]
197  float _omegaMax;
198 
199  // conversion from [m/s] to revolutions per minute [RPM]
200  float _ms2rpm;
201 
202  // conversion from revolutions per minute [RPM] to [m/s]
203  float _rpm2ms;
204 
205  // conversion from [rad/s] to revolutions per minute [RPM]
206  float _rad2rpm;
207 
208  // conversion from revolutions per minute [RPM] to [rad/s]
209  float _rpm2rad;
210 
211  // enable motion in direction of the y-axis. This is only meaningful for mecanum steering.
213 
214  // RGB values of lighting system
215  unsigned char _rgb[3];
216 
217  // time elapsed since last call
219 };
220 
221 } // end namespace
222 
223 #endif
response
const std::string response
iotbot::MotorParams::rpmMax
float rpmMax
Definition: IOTBot.h:30
iotbot::IOTBot::_motorParams
MotorParams * _motorParams
Definition: IOTBot.h:187
iotbot::IOTBot::_pubCurrent
ros::Publisher _pubCurrent
Definition: IOTBot.h:182
iotbot::IOTBot::_nh
ros::NodeHandle _nh
Definition: IOTBot.h:173
ros::Publisher
iotbot::MotorParams::lowPassEncoderTicks
float lowPassEncoderTicks
Definition: IOTBot.h:36
iotbot::ChassisParams
Definition: IOTBot.h:77
iotbot::MotorParams::controlFrequency
int controlFrequency
Definition: IOTBot.h:31
iotbot::ChassisParams::chRearLeft
int chRearLeft
Definition: IOTBot.h:84
iotbot::MotorParams::ki
float ki
Definition: IOTBot.h:33
iotbot::IOTBot::_enableYMotion
bool _enableYMotion
Definition: IOTBot.h:212
iotbot::IOTBot::_srvEnable
ros::ServiceServer _srvEnable
Definition: IOTBot.h:176
ros.h
iotbot::MotorParams::MotorParams
MotorParams(const MotorParams &p)
Definition: IOTBot.h:58
iotbot::MotorParams::MotorParams
MotorParams()
Definition: IOTBot.h:41
IOTShield.h
iotbot::ChassisParams::chRearRight
int chRearRight
Definition: IOTBot.h:85
iotbot::IOTBot::_pubIMU
ros::Publisher _pubIMU
Definition: IOTBot.h:183
iotbot::IOTBot::_pubRPM
ros::Publisher _pubRPM
Definition: IOTBot.h:180
iotbot::IOTBot::_ms2rpm
float _ms2rpm
Definition: IOTBot.h:200
iotbot::ChassisParams::ChassisParams
ChassisParams()
Definition: IOTBot.h:89
iotbot::IOTBot::_lastCmd
ros::Time _lastCmd
Definition: IOTBot.h:218
ros::ServiceServer
iotbot::MotorParams::kp
float kp
Definition: IOTBot.h:32
iotbot::MotorParams::kd
float kd
Definition: IOTBot.h:34
iotbot::IOTShield
Interface class to IOTShield via UART.
Definition: IOTShield.h:78
iotbot::IOTBot::_vMax
float _vMax
Definition: IOTBot.h:194
iotbot::MotorParams::gearRatio
float gearRatio
Definition: IOTBot.h:28
iotbot::ChassisParams::wheelDiameter
float wheelDiameter
Definition: IOTBot.h:81
iotbot
Definition: IOTBot.cpp:6
iotbot::IOTBot::_subJoy
ros::Subscriber _subJoy
Definition: IOTBot.h:174
iotbot::IOTBot::_rpm2rad
float _rpm2rad
Definition: IOTBot.h:209
iotbot::IOTBot::_omegaMax
float _omegaMax
Definition: IOTBot.h:197
iotbot::IOTBot::_rpm2ms
float _rpm2ms
Definition: IOTBot.h:203
iotbot::ChassisParams::wheelBase
float wheelBase
Definition: IOTBot.h:80
iotbot::ChassisParams::chFrontLeft
int chFrontLeft
Definition: IOTBot.h:82
iotbot::IOTBot::_srvCali
ros::ServiceServer _srvCali
Definition: IOTBot.h:177
iotbot::IOTBot::_pubTemp
ros::Publisher _pubTemp
Definition: IOTBot.h:185
iotbot::MotorParams
Definition: IOTBot.h:26
iotbot::IOTBot::_subVel
ros::Subscriber _subVel
Definition: IOTBot.h:175
iotbot::IOTBot
Definition: IOTBot.h:108
iotbot::ChassisParams::direction
int direction
Definition: IOTBot.h:86
iotbot::IOTBot::_chassisParams
ChassisParams _chassisParams
Definition: IOTBot.h:186
iotbot::IOTBot::_pubToF
ros::Publisher _pubToF
Definition: IOTBot.h:179
ros::Time
std
iotbot::IOTBot::_srvFix
ros::ServiceServer _srvFix
Definition: IOTBot.h:178
iotbot::MotorParams::lowPassInputFilter
float lowPassInputFilter
Definition: IOTBot.h:35
iotbot::IOTBot::_pubVoltage
ros::Publisher _pubVoltage
Definition: IOTBot.h:181
iotbot::IOTBot::_shield
IOTShield * _shield
Definition: IOTBot.h:188
iotbot::IOTBot::_rad2rpm
float _rad2rpm
Definition: IOTBot.h:206
iotbot::ChassisParams::enableYMotion
int enableYMotion
Definition: IOTBot.h:87
iotbot::ChassisParams::chFrontRight
int chFrontRight
Definition: IOTBot.h:83
iotbot::MotorParams::encoderRatio
float encoderRatio
Definition: IOTBot.h:29
iotbot::IOTBot::_pubPose
ros::Publisher _pubPose
Definition: IOTBot.h:184
iotbot::ChassisParams::track
float track
Definition: IOTBot.h:79
ros::NodeHandle
ros::Subscriber


iotbot
Author(s): Stefan May (EduArt Robotik)
autogenerated on Wed May 24 2023 02:13:39