3 #include <sensor_msgs/Imu.h> 4 #include <geometry_msgs/WrenchStamped.h> 5 #include <sensor_msgs/Temperature.h> 8 #include <boost/math/constants/constants.hpp> 26 static constexpr
double DEG_TO_RAD = boost::math::constants::pi<double>() / 180;
sensor_msgs::Temperature TempType
const WrenchType & getWrench() const
Gets the wrench variable.
ImuType & getImu()
Non-const version of getImu() const. Gets the imu variable.
Class representing the readings received from the rokubi mini devices.
geometry_msgs::WrenchStamped WrenchType
Class representing the different states the communication or the sensors can be in.
Reading()=default
Default constructor.
const ImuType & getExternalImu() const
Gets the externalImu variable.
bool isForceTorqueSaturated() const
Gets the isForceTorqueSaturated flag.
WrenchType & getWrench()
Non-const version of getWrench() const. Gets the wrench variable.
Statusword statusword_
The statusword variable.
void setStatusword(const Statusword &statusword)
Sets the statusword variable.
bool isForceTorqueSaturated_
The isForceTorqueSaturated variable.
void setForceTorqueSaturated(const bool isForceTorqueSaturated)
Sets the isForceTorqueSaturated variable.
TempType & getTemperature()
ImuType & getExternalImu()
Non-const version of getExternalImu() const. Gets the externalImu variable.
void setTemperature(const TempType &temperature)
Sets the temperature variable.
static constexpr double G_TO_METERS_PER_SECOND_SQUARED
g to m/s^2 abbreviation for convenience.
ImuType externalImu_
The externalImu variable.
const Statusword & getStatusword() const
Gets the statusword variable.
WrenchType wrench_
The wrench variable.
TempType temperature_
The temperature variable.
const TempType & getTemperature() const
Gets the temperature flag.
virtual ~Reading()=default
ImuType imu_
The imu variable.
const ImuType & getImu() const
Gets the imu variable.
static constexpr double DEG_TO_RAD
degrees to rad abbreviation for convenience.