Public Types | Public Member Functions | Protected Attributes | List of all members
rokubimini::Reading Class Reference

Class representing the readings received from the rokubi mini devices. More...

#include <Reading.hpp>

Public Types

using ImuType = sensor_msgs::Imu
 
using TempType = sensor_msgs::Temperature
 
using WrenchType = geometry_msgs::WrenchStamped
 

Public Member Functions

const ImuTypegetExternalImu () const
 Gets the externalImu variable. More...
 
ImuTypegetExternalImu ()
 Non-const version of getExternalImu() const. Gets the externalImu variable. More...
 
const ImuTypegetImu () const
 Gets the imu variable. More...
 
ImuTypegetImu ()
 Non-const version of getImu() const. Gets the imu variable. More...
 
const StatuswordgetStatusword () const
 Gets the statusword variable. More...
 
const TempTypegetTemperature () const
 Gets the temperature flag. More...
 
TempTypegetTemperature ()
 
const WrenchTypegetWrench () const
 Gets the wrench variable. More...
 
WrenchTypegetWrench ()
 Non-const version of getWrench() const. Gets the wrench variable. More...
 
bool isForceTorqueSaturated () const
 Gets the isForceTorqueSaturated flag. More...
 
 Reading ()=default
 Default constructor. More...
 
void setForceTorqueSaturated (const bool isForceTorqueSaturated)
 Sets the isForceTorqueSaturated variable. More...
 
void setStatusword (const Statusword &statusword)
 Sets the statusword variable. More...
 
void setTemperature (const TempType &temperature)
 Sets the temperature variable. More...
 
virtual ~Reading ()=default
 

Protected Attributes

ImuType externalImu_
 The externalImu variable. More...
 
ImuType imu_
 The imu variable. More...
 
bool isForceTorqueSaturated_ { false }
 The isForceTorqueSaturated variable. More...
 
Statusword statusword_
 The statusword variable. More...
 
TempType temperature_
 The temperature variable. More...
 
WrenchType wrench_
 The wrench variable. More...
 

Detailed Description

Class representing the readings received from the rokubi mini devices.

Definition at line 35 of file Reading.hpp.

Member Typedef Documentation

using rokubimini::Reading::ImuType = sensor_msgs::Imu

Definition at line 38 of file Reading.hpp.

using rokubimini::Reading::TempType = sensor_msgs::Temperature

Definition at line 40 of file Reading.hpp.

using rokubimini::Reading::WrenchType = geometry_msgs::WrenchStamped

Definition at line 39 of file Reading.hpp.

Constructor & Destructor Documentation

rokubimini::Reading::Reading ( )
default

Default constructor.

virtual rokubimini::Reading::~Reading ( )
virtualdefault

Member Function Documentation

const ImuType & rokubimini::Reading::getExternalImu ( ) const
inline

Gets the externalImu variable.

Returns
The externalImu values.

Definition at line 107 of file Reading.hpp.

ImuType & rokubimini::Reading::getExternalImu ( )
inline

Non-const version of getExternalImu() const. Gets the externalImu variable.

Returns
The externalImu values.

Definition at line 119 of file Reading.hpp.

const ImuType & rokubimini::Reading::getImu ( ) const
inline

Gets the imu variable.

Returns
The imu values.

Definition at line 58 of file Reading.hpp.

ImuType & rokubimini::Reading::getImu ( )
inline

Non-const version of getImu() const. Gets the imu variable.

Returns
The imu values.

Definition at line 70 of file Reading.hpp.

const Statusword & rokubimini::Reading::getStatusword ( ) const
inline

Gets the statusword variable.

Returns
The statusword value.

Definition at line 131 of file Reading.hpp.

TempType rokubimini::Reading::getTemperature ( ) const
inline

Gets the temperature flag.

Returns
The temperature value.

Definition at line 179 of file Reading.hpp.

TempType& rokubimini::Reading::getTemperature ( )
inline

Definition at line 191 of file Reading.hpp.

const WrenchType & rokubimini::Reading::getWrench ( ) const
inline

Gets the wrench variable.

Returns
The wrench values.

Definition at line 83 of file Reading.hpp.

WrenchType & rokubimini::Reading::getWrench ( )
inline

Non-const version of getWrench() const. Gets the wrench variable.

Returns
The wrench values.

Definition at line 95 of file Reading.hpp.

bool rokubimini::Reading::isForceTorqueSaturated ( ) const
inline

Gets the isForceTorqueSaturated flag.

Returns
The isForceTorqueSaturated value.

Definition at line 155 of file Reading.hpp.

void rokubimini::Reading::setForceTorqueSaturated ( const bool  isForceTorqueSaturated)
inline

Sets the isForceTorqueSaturated variable.

Parameters
isForceTorqueSaturatedThe value to set.

Definition at line 167 of file Reading.hpp.

void rokubimini::Reading::setStatusword ( const Statusword statusword)
inline

Sets the statusword variable.

Parameters
statuswordThe value to set.

Definition at line 143 of file Reading.hpp.

void rokubimini::Reading::setTemperature ( const TempType temperature)
inline

Sets the temperature variable.

Parameters
temperatureThe value to set.

Definition at line 203 of file Reading.hpp.

Member Data Documentation

ImuType rokubimini::Reading::externalImu_
protected

The externalImu variable.

Definition at line 231 of file Reading.hpp.

ImuType rokubimini::Reading::imu_
protected

The imu variable.

Definition at line 215 of file Reading.hpp.

bool rokubimini::Reading::isForceTorqueSaturated_ { false }
protected

The isForceTorqueSaturated variable.

Definition at line 239 of file Reading.hpp.

float rokubimini::Reading::statusword_
protected

The statusword variable.

Definition at line 255 of file Reading.hpp.

TempType rokubimini::Reading::temperature_
protected

The temperature variable.

Definition at line 247 of file Reading.hpp.

WrenchType rokubimini::Reading::wrench_
protected

The wrench variable.

Definition at line 223 of file Reading.hpp.


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


rokubimini
Author(s):
autogenerated on Wed Mar 3 2021 03:09:12