Public Member Functions | Private Member Functions | Private Attributes | List of all members
iotbot::IOTBot Class Reference

#include <IOTBot.h>

Public Member Functions

 IOTBot (ChassisParams &chassisParams, MotorParams &motorParams)
 
void run ()
 
 ~IOTBot ()
 

Private Member Functions

bool calibrateCallback (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
 
void controlMotors (float vFwd, float vLeft, float omega)
 
bool enableCallback (std_srvs::SetBool::Request &request, std_srvs::SetBool::Response &response)
 
bool fixIMUZAxisCallback (std_srvs::SetBool::Request &request, std_srvs::SetBool::Response &response)
 
void joyCallback (const sensor_msgs::Joy::ConstPtr &joy)
 
void velocityCallback (const geometry_msgs::Twist::ConstPtr &cmd)
 

Private Attributes

ChassisParams _chassisParams
 
bool _enableYMotion
 
ros::Time _lastCmd
 
MotorParams_motorParams
 
float _ms2rpm
 
ros::NodeHandle _nh
 
float _omegaMax
 
ros::Publisher _pubCurrent
 
ros::Publisher _pubIMU
 
ros::Publisher _pubPose
 
ros::Publisher _pubRPM
 
ros::Publisher _pubTemp
 
ros::Publisher _pubToF
 
ros::Publisher _pubVoltage
 
float _rad2rpm
 
unsigned char _rgb [3]
 
float _rpm [4]
 
float _rpm2ms
 
float _rpm2rad
 
IOTShield_shield
 
ros::ServiceServer _srvCali
 
ros::ServiceServer _srvEnable
 
ros::ServiceServer _srvFix
 
ros::Subscriber _subJoy
 
ros::Subscriber _subVel
 
float _vMax
 

Detailed Description

Definition at line 108 of file IOTBot.h.

Constructor & Destructor Documentation

◆ IOTBot()

iotbot::IOTBot::IOTBot ( ChassisParams chassisParams,
MotorParams motorParams 
)

Standard Constructor @params[in] chassisParams chassis parameters, including the map for assigning channels to position of wheels @params[in] motorParams motor parameters

Definition at line 9 of file IOTBot.cpp.

◆ ~IOTBot()

iotbot::IOTBot::~IOTBot ( )

Destructor

Definition at line 63 of file IOTBot.cpp.

Member Function Documentation

◆ calibrateCallback()

bool iotbot::IOTBot::calibrateCallback ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response 
)
private

ROS service callback for triggering IMU calibration

Returns
success state

Definition at line 183 of file IOTBot.cpp.

◆ controlMotors()

void iotbot::IOTBot::controlMotors ( float  vFwd,
float  vLeft,
float  omega 
)
private

Normalize motion command and assign it to the channels

Parameters
[in]vFwdforward velocity (x-axis)
[in]vLeftvelocity to the left (y-axis)
[in]omegaangular velocity (around z-axis)

Definition at line 299 of file IOTBot.cpp.

◆ enableCallback()

bool iotbot::IOTBot::enableCallback ( std_srvs::SetBool::Request &  request,
std_srvs::SetBool::Response &  response 
)
private

ROS service callback for enabling robot

Parameters
[in]requestservice request data
[out]responseservice response data
Returns
success state

Definition at line 167 of file IOTBot.cpp.

◆ fixIMUZAxisCallback()

bool iotbot::IOTBot::fixIMUZAxisCallback ( std_srvs::SetBool::Request &  request,
std_srvs::SetBool::Response &  response 
)
private

ROS service callback for fixing the IMU's yaw angle estimation

Parameters
[in]requestservice request data
[out]responseservice response data
Returns
success state

Definition at line 190 of file IOTBot.cpp.

◆ joyCallback()

void iotbot::IOTBot::joyCallback ( const sensor_msgs::Joy::ConstPtr &  joy)
private

ROS joystick callback

Parameters
[in]joymessage with joystick command

Definition at line 198 of file IOTBot.cpp.

◆ run()

void iotbot::IOTBot::run ( )

ROS main loop (blocking method)

Definition at line 70 of file IOTBot.cpp.

◆ velocityCallback()

void iotbot::IOTBot::velocityCallback ( const geometry_msgs::Twist::ConstPtr &  cmd)
private

ROS command velocity callback

Parameters
[in]cmdmessage with velocity command

Definition at line 294 of file IOTBot.cpp.

Member Data Documentation

◆ _chassisParams

ChassisParams iotbot::IOTBot::_chassisParams
private

Definition at line 186 of file IOTBot.h.

◆ _enableYMotion

bool iotbot::IOTBot::_enableYMotion
private

Definition at line 212 of file IOTBot.h.

◆ _lastCmd

ros::Time iotbot::IOTBot::_lastCmd
private

Definition at line 218 of file IOTBot.h.

◆ _motorParams

MotorParams* iotbot::IOTBot::_motorParams
private

Definition at line 187 of file IOTBot.h.

◆ _ms2rpm

float iotbot::IOTBot::_ms2rpm
private

Definition at line 200 of file IOTBot.h.

◆ _nh

ros::NodeHandle iotbot::IOTBot::_nh
private

Definition at line 173 of file IOTBot.h.

◆ _omegaMax

float iotbot::IOTBot::_omegaMax
private

Definition at line 197 of file IOTBot.h.

◆ _pubCurrent

ros::Publisher iotbot::IOTBot::_pubCurrent
private

Definition at line 182 of file IOTBot.h.

◆ _pubIMU

ros::Publisher iotbot::IOTBot::_pubIMU
private

Definition at line 183 of file IOTBot.h.

◆ _pubPose

ros::Publisher iotbot::IOTBot::_pubPose
private

Definition at line 184 of file IOTBot.h.

◆ _pubRPM

ros::Publisher iotbot::IOTBot::_pubRPM
private

Definition at line 180 of file IOTBot.h.

◆ _pubTemp

ros::Publisher iotbot::IOTBot::_pubTemp
private

Definition at line 185 of file IOTBot.h.

◆ _pubToF

ros::Publisher iotbot::IOTBot::_pubToF
private

Definition at line 179 of file IOTBot.h.

◆ _pubVoltage

ros::Publisher iotbot::IOTBot::_pubVoltage
private

Definition at line 181 of file IOTBot.h.

◆ _rad2rpm

float iotbot::IOTBot::_rad2rpm
private

Definition at line 206 of file IOTBot.h.

◆ _rgb

unsigned char iotbot::IOTBot::_rgb[3]
private

Definition at line 215 of file IOTBot.h.

◆ _rpm

float iotbot::IOTBot::_rpm[4]
private

Definition at line 191 of file IOTBot.h.

◆ _rpm2ms

float iotbot::IOTBot::_rpm2ms
private

Definition at line 203 of file IOTBot.h.

◆ _rpm2rad

float iotbot::IOTBot::_rpm2rad
private

Definition at line 209 of file IOTBot.h.

◆ _shield

IOTShield* iotbot::IOTBot::_shield
private

Definition at line 188 of file IOTBot.h.

◆ _srvCali

ros::ServiceServer iotbot::IOTBot::_srvCali
private

Definition at line 177 of file IOTBot.h.

◆ _srvEnable

ros::ServiceServer iotbot::IOTBot::_srvEnable
private

Definition at line 176 of file IOTBot.h.

◆ _srvFix

ros::ServiceServer iotbot::IOTBot::_srvFix
private

Definition at line 178 of file IOTBot.h.

◆ _subJoy

ros::Subscriber iotbot::IOTBot::_subJoy
private

Definition at line 174 of file IOTBot.h.

◆ _subVel

ros::Subscriber iotbot::IOTBot::_subVel
private

Definition at line 175 of file IOTBot.h.

◆ _vMax

float iotbot::IOTBot::_vMax
private

Definition at line 194 of file IOTBot.h.


The documentation for this class was generated from the following files:


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