BipedalLocomotion::RobotInterface::ISensorBridge class

Sensor bridge interface.

Derived classes

class YarpSensorBridge
YarpSensorBridge Yarp implementation of the ISensorBridge interface Currently available interfaces.

Public types

using unique_ptr = std::unique_ptr<ISensorBridge>
using shared_ptr = std::shared_ptr<ISensorBridge>
using weak_ptr = std::weak_ptr<ISensorBridge>
using OptionalDoubleRef = std::optional<std::reference_wrapper<double>>
using Vector12d = Eigen::Matrix<double, 12, 1>
using Vector6d = Eigen::Matrix<double, 6, 1>

Constructors, destructors, conversion operators

~ISensorBridge() defaulted virtual
Destructor.

Public functions

auto getJointsList(std::vector<std::string>& jointsList) -> bool virtual
Get joints list.
auto getIMUsList(std::vector<std::string>& IMUsList) -> bool virtual
Get imu sensors.
auto getLinearAccelerometersList(std::vector<std::string>& linearAccelerometersList) -> bool virtual
Get linear accelerometers.
auto getGyroscopesList(std::vector<std::string>& gyroscopesList) -> bool virtual
Get gyroscopes.
auto getOrientationSensorsList(std::vector<std::string>& orientationSensorsList) -> bool virtual
Get orientation sensors.
auto getMagnetometersList(std::vector<std::string>& magnetometersList) -> bool virtual
Get magnetometers sensors.
auto getSixAxisForceTorqueSensorsList(std::vector<std::string>& sixAxisForceTorqueSensorsList) -> bool virtual
Get 6 axis FT sensors.
auto getThreeAxisForceTorqueSensorsList(std::vector<std::string>& threeAxisForceTorqueSensorsList) -> bool virtual
Get 6 axis FT sensors.
auto getCartesianWrenchesList(std::vector<std::string>& cartesianWrenchesList) -> bool virtual
Get cartesian wrenches.
auto getTemperatureSensorsList(std::vector<std::string>& temperatureSensorsList) -> bool virtual
Get temperature sensors.
auto getJointPosition(const std::string& jointName, double& jointPosition, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get joint position in radians.
auto getJointPositions(Eigen::Ref<Eigen::VectorXd> jointPositions, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get all joints' positions in radians.
auto getJointVelocity(const std::string& jointName, double& jointVelocity, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get joint velocity in rad/s.
auto getJointVelocities(Eigen::Ref<Eigen::VectorXd> jointVelocties, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get all joints' velocities in rad/s.
auto getJointAcceleration(const std::string& jointName, double& jointAcceleration, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get joint acceleration in rad/s^2.
auto getJointAccelerations(Eigen::Ref<Eigen::VectorXd> jointAccelerations, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get all joints' accelerations in rad/s^2.
auto getIMUMeasurement(const std::string& imuName, Eigen::Ref<Vector12d> imuMeasurement, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get IMU measurement The serialization of measurments is as follows, (rpy acc omega mag)
auto getLinearAccelerometerMeasurement(const std::string& accName, Eigen::Ref<Eigen::Vector3d> accMeasurement, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get linear accelerometer measurement in m/s^2.
auto getGyroscopeMeasure(const std::string& gyroName, Eigen::Ref<Eigen::Vector3d> gyroMeasurement, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get gyroscope measurement in rad/s.
auto getOrientationSensorMeasurement(const std::string& rpyName, Eigen::Ref<Eigen::Vector3d> rpyMeasurement, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get orientation sensor measurement in radians as roll pitch yaw Euler angles.
auto getMagnetometerMeasurement(const std::string& magName, Eigen::Ref<Eigen::Vector3d> magMeasurement, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get magentometer measurement in tesla.
auto getSixAxisForceTorqueMeasurement(const std::string& ftName, Eigen::Ref<Vector6d> ftMeasurement, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get six axis force torque measurement.
auto getThreeAxisForceTorqueMeasurement(const std::string& ftName, Eigen::Ref<Eigen::Vector3d> ftMeasurement, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get three axis force-torque measurement containing normal force (N) and tangential moments (Nm)
auto getCartesianWrench(const std::string& cartesianWrenchName, Eigen::Ref<Vector6d> cartesianWrenchMeasurement, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get 6D end effector wrenches in N and Nm for forces and torques respectively.
auto getTemperature(const std::string& temperatureSensorName, double& temperature, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get temperature measurement.
auto getMotorCurrent(const std::string& jointName, double& motorCurrent, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get motor currents in ampere.
auto getMotorCurrents(Eigen::Ref<Eigen::VectorXd> motorCurrents, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get all motors' current in ampere.
auto getMotorPWM(const std::string& jointName, double& motorPWM, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get motor PWM.
auto getMotorPWMs(Eigen::Ref<Eigen::VectorXd> motorPWMs, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get all motors' PWM.
auto getJointTorque(const std::string& jointName, double& jointTorque, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get joint torques in Nm.
auto getJointTorques(Eigen::Ref<Eigen::VectorXd> jointTorques, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get all joints' torque in Nm.
auto getPidPosition(const std::string& jointName, double& pidPosition, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get pid position in rad.
auto getPidPositions(Eigen::Ref<Eigen::VectorXd> pidPositions, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get all pid positions in rad.
auto getPidPositionError(const std::string& jointName, double& pidPositionError, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get pid position error in rad.
auto getPidPositionErrors(Eigen::Ref<Eigen::VectorXd> pidPositionErrors, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get all pid position errors in rad.
auto getMotorPosition(const std::string& jointName, double& motorPosition, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get motor position in rad.
auto getMotorPositions(Eigen::Ref<Eigen::VectorXd> motorPositions, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get all motors' positions in rad.
auto getMotorVelocity(const std::string& jointName, double& motorVelocity, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get motor velocity in rad/s.
auto getMotorVelocities(Eigen::Ref<Eigen::VectorXd> motorVelocties, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get all motors' velocities in rad/s.
auto getMotorAcceleration(const std::string& jointName, double& motorAcceleration, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get motor acceleration in rad/s^2.
auto getMotorAccelerations(Eigen::Ref<Eigen::VectorXd> motorAccelerations, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool virtual
Get all motors' accelerations in rad/s^2.

Protected functions

auto populateSensorBridgeOptionsFromConfig(std::weak_ptr<const ParametersHandler::IParametersHandler> handler, SensorBridgeOptions& sensorBridgeOptions) -> bool virtual
Helper method to maintain SensorBridgeOptions struct by populating it from the configuration parameters.
auto populateSensorListsFromConfig(std::weak_ptr<const ParametersHandler::IParametersHandler> handler, const SensorBridgeOptions& sensorBridgeOptions, SensorLists& sensorLists) -> bool virtual
Helper method to maintain SensorLists struct by populating it from the configuration parameters.
auto populateSensorBridgeMetaDataFromConfig(std::weak_ptr<const ParametersHandler::IParametersHandler> handler, SensorBridgeMetaData& sensorBridgeMetaData) -> bool virtual
Helper method to maintain SensorBridgeMetaData struct by populating it from the configuration parameters.

Function documentation

bool BipedalLocomotion::RobotInterface::ISensorBridge::getJointsList(std::vector<std::string>& jointsList) virtual

Get joints list.

Parameters
jointsList out list of joints attached to the bridge
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getIMUsList(std::vector<std::string>& IMUsList) virtual

Get imu sensors.

Parameters
IMUsList out list of IMUs attached to the bridge
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getLinearAccelerometersList(std::vector<std::string>& linearAccelerometersList) virtual

Get linear accelerometers.

Parameters
linearAccelerometersList out list of linear accelerometers attached to the bridge
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getGyroscopesList(std::vector<std::string>& gyroscopesList) virtual

Get gyroscopes.

Parameters
gyroscopesList out list of gyroscopes attached to the bridge
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getOrientationSensorsList(std::vector<std::string>& orientationSensorsList) virtual

Get orientation sensors.

Parameters
orientationSensorsList out list of orientation sensors attached to the bridge
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getMagnetometersList(std::vector<std::string>& magnetometersList) virtual

Get magnetometers sensors.

Parameters
magnetometersList out list of magnetometers attached to the bridge
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getSixAxisForceTorqueSensorsList(std::vector<std::string>& sixAxisForceTorqueSensorsList) virtual

Get 6 axis FT sensors.

Parameters
sixAxisForceTorqueSensorsList out list of 6 axis force torque sensors attached to the bridge
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getThreeAxisForceTorqueSensorsList(std::vector<std::string>& threeAxisForceTorqueSensorsList) virtual

Get 6 axis FT sensors.

Parameters
threeAxisForceTorqueSensorsList out list of 3 axis force torque sensors attached to the bridge
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getCartesianWrenchesList(std::vector<std::string>& cartesianWrenchesList) virtual

Get cartesian wrenches.

Parameters
cartesianWrenchesList out list of cartesian wrenches attached to the bridge
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getTemperatureSensorsList(std::vector<std::string>& temperatureSensorsList) virtual

Get temperature sensors.

Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getJointPosition(const std::string& jointName, double& jointPosition, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get joint position in radians.

Parameters
jointName in name of the joint
jointPosition out joint position in radians
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getJointPositions(Eigen::Ref<Eigen::VectorXd> jointPositions, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get all joints' positions in radians.

Parameters
jointPositions out all joints' position in radians
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getJointVelocity(const std::string& jointName, double& jointVelocity, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get joint velocity in rad/s.

Parameters
jointName in name of the joint
jointVelocity out joint velocity in radians per second
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getJointVelocities(Eigen::Ref<Eigen::VectorXd> jointVelocties, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get all joints' velocities in rad/s.

Parameters
jointVelocties out all joints' velocities in radians per second
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getJointAcceleration(const std::string& jointName, double& jointAcceleration, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get joint acceleration in rad/s^2.

Parameters
jointName in name of the joint
jointAcceleration out joint acceleration in radians per second squared
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getJointAccelerations(Eigen::Ref<Eigen::VectorXd> jointAccelerations, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get all joints' accelerations in rad/s^2.

Parameters
jointAccelerations out all joints' accelerations in radians per second squared
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getIMUMeasurement(const std::string& imuName, Eigen::Ref<Vector12d> imuMeasurement, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get IMU measurement The serialization of measurments is as follows, (rpy acc omega mag)

Parameters
imuName in name of the IMU
imuMeasurement out imu measurement of size 12
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure
  • rpy in radians Roll-Pitch-Yaw Euler angles
  • acc in m/s^2 linear accelerometer measurements
  • omega in rad/s gyroscope measurements
  • mag in tesla magnetometer measurements

bool BipedalLocomotion::RobotInterface::ISensorBridge::getLinearAccelerometerMeasurement(const std::string& accName, Eigen::Ref<Eigen::Vector3d> accMeasurement, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get linear accelerometer measurement in m/s^2.

Parameters
accName in name of the linear accelerometer
accMeasurement out linear accelerometer measurements of size 3
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getGyroscopeMeasure(const std::string& gyroName, Eigen::Ref<Eigen::Vector3d> gyroMeasurement, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get gyroscope measurement in rad/s.

Parameters
gyroName in name of the gyroscope
gyroMeasurement out gyroscope measurements of size 3
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getOrientationSensorMeasurement(const std::string& rpyName, Eigen::Ref<Eigen::Vector3d> rpyMeasurement, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get orientation sensor measurement in radians as roll pitch yaw Euler angles.

Parameters
rpyName in name of the orientation sensor
rpyMeasurement out rpy measurements of size 3
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getMagnetometerMeasurement(const std::string& magName, Eigen::Ref<Eigen::Vector3d> magMeasurement, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get magentometer measurement in tesla.

Parameters
magName in name of the magnetometer
magMeasurement out magnetometer measurements of size 3
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getSixAxisForceTorqueMeasurement(const std::string& ftName, Eigen::Ref<Vector6d> ftMeasurement, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get six axis force torque measurement.

Parameters
ftName in name of the FT sensor
ftMeasurement out FT measurements of size 6 containing 3d forces and 3d torques
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getThreeAxisForceTorqueMeasurement(const std::string& ftName, Eigen::Ref<Eigen::Vector3d> ftMeasurement, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get three axis force-torque measurement containing normal force (N) and tangential moments (Nm)

Parameters
ftName in name of the FT sensor
ftMeasurement out FT measurements of size 3 containing tau_x tau_y and fz
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getCartesianWrench(const std::string& cartesianWrenchName, Eigen::Ref<Vector6d> cartesianWrenchMeasurement, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get 6D end effector wrenches in N and Nm for forces and torques respectively.

Parameters
cartesianWrenchName in name of the end effector wrench
cartesianWrenchMeasurement out end effector wrench measurement of size 6
receiveTimeInSeconds
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getTemperature(const std::string& temperatureSensorName, double& temperature, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get temperature measurement.

Parameters
temperatureSensorName in name of the temperature sensor
temperature out temperature measurement
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getMotorCurrent(const std::string& jointName, double& motorCurrent, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get motor currents in ampere.

Parameters
jointName in name of the joint
motorCurrent out motor current in ampere
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getMotorCurrents(Eigen::Ref<Eigen::VectorXd> motorCurrents, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get all motors' current in ampere.

Parameters
motorCurrents out all motors' current in ampere
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getMotorPWM(const std::string& jointName, double& motorPWM, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get motor PWM.

Parameters
jointName in name of the joint
motorPWM out motor PWM
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getMotorPWMs(Eigen::Ref<Eigen::VectorXd> motorPWMs, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get all motors' PWM.

Parameters
motorPWMs out all motors' PWM
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getJointTorque(const std::string& jointName, double& jointTorque, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get joint torques in Nm.

Parameters
jointName in name of the joint
jointTorque out motor torque in Nm
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getJointTorques(Eigen::Ref<Eigen::VectorXd> jointTorques, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get all joints' torque in Nm.

Parameters
jointTorques out all motors' torque in Nm
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getPidPosition(const std::string& jointName, double& pidPosition, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get pid position in rad.

Parameters
jointName in name of the joint
pidPosition out pid position in radians
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getPidPositions(Eigen::Ref<Eigen::VectorXd> pidPositions, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get all pid positions in rad.

Parameters
pidPositions out all pid positions in radians
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getPidPositionError(const std::string& jointName, double& pidPositionError, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get pid position error in rad.

Parameters
jointName in name of the joint
pidPositionError out pid position error in radians
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getPidPositionErrors(Eigen::Ref<Eigen::VectorXd> pidPositionErrors, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get all pid position errors in rad.

Parameters
pidPositionErrors out all pid position errors in radians
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getMotorPosition(const std::string& jointName, double& motorPosition, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get motor position in rad.

Parameters
jointName in name of the joint
motorPosition out motor position in radians
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getMotorPositions(Eigen::Ref<Eigen::VectorXd> motorPositions, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get all motors' positions in rad.

Parameters
motorPositions out all motors' position in radians
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getMotorVelocity(const std::string& jointName, double& motorVelocity, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get motor velocity in rad/s.

Parameters
jointName in name of the joint
motorVelocity out motor velocity in radians per second
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getMotorVelocities(Eigen::Ref<Eigen::VectorXd> motorVelocties, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get all motors' velocities in rad/s.

Parameters
motorVelocties out all motors' velocities in radians per second
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getMotorAcceleration(const std::string& jointName, double& motorAcceleration, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get motor acceleration in rad/s^2.

Parameters
jointName in name of the joint
motorAcceleration out motor acceleration in radians per second squared
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::getMotorAccelerations(Eigen::Ref<Eigen::VectorXd> motorAccelerations, OptionalDoubleRef receiveTimeInSeconds = {}) virtual

Get all motors' accelerations in rad/s^2.

Parameters
motorAccelerations out all motors' accelerations in radians per second squared
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::RobotInterface::ISensorBridge::populateSensorBridgeOptionsFromConfig(std::weak_ptr<const ParametersHandler::IParametersHandler> handler, SensorBridgeOptions& sensorBridgeOptions) virtual protected

Helper method to maintain SensorBridgeOptions struct by populating it from the configuration parameters.

Parameters
handler in Parameters handler
sensorBridgeOptions in SensorBridgeOptions to hold the bridge options for streaming sensor measurements

bool BipedalLocomotion::RobotInterface::ISensorBridge::populateSensorListsFromConfig(std::weak_ptr<const ParametersHandler::IParametersHandler> handler, const SensorBridgeOptions& sensorBridgeOptions, SensorLists& sensorLists) virtual protected

Helper method to maintain SensorLists struct by populating it from the configuration parameters.

Parameters
handler in Parameters handler
sensorBridgeOptions in configured object of SensorBridgeOptions
sensorLists in SensorLists object holding list of connected sensor devices

bool BipedalLocomotion::RobotInterface::ISensorBridge::populateSensorBridgeMetaDataFromConfig(std::weak_ptr<const ParametersHandler::IParametersHandler> handler, SensorBridgeMetaData& sensorBridgeMetaData) virtual protected

Helper method to maintain SensorBridgeMetaData struct by populating it from the configuration parameters.

Parameters
handler in Parameters handler
sensorBridgeMetaData in configured object of SensorBridgeMetadata