class
YarpSensorBridgeYarpSensorBridge Yarp implementation of the ISensorBridge interface Currently available interfaces.
- Remapped Remote Control Board for joint states
- Inertial Measurement Units through generic sensor interface and remapped multiple analog sensor interface
- Whole Body Dynamics Estimated end effector wrenches through a generic sensor interface
- Force Torque Sensors through analog sensor interface and remapped multiple analog sensor interface
- Depth Cameras through RGBD sensor interface
- Camera images through OpenCV Grabber interface
The YarpSensorBridge expects a list of device drivers through the yarp::dev::PolyDriverList object. Each PolyDriver object in the list is compared with the configured sensor names and the assumptions listed below to infer the sensor types and relevant interfaces in order to to read the relevant data.
MAJOR ASSUMPTIONS
- Every sensor unit(device driver) attached to this Bridge is identified by a unique name
- A single instance of a remote control board remapper and a multiple analog sensor remapper is expected if the suer wants to use the control board interfaces and multiple analog sensor interfaces
- Any generic sensor interface with channel dimensions of 6 is considered to be a cartesian wrench interface
- Any generic sensor interface with channel dimensions of 12 is considered as a IMU interface (server inertial)
- Any analog sensor interface with channel dimensions of 6 is considered as a force torque sensor interface
- The current internal design (read all sensors in a serial fashion) may not be suitable for a heavy measurement set
The parameters for writing the configuration file for this class is given as,
Group | Parameter | Type | Description |
---|---|---|---|
check_for_nan | boolean | flag to activate checking for NANs in the incoming measurement buffers, not applicable for images | |
stream_joint_states | boolean | Flag to activate the attachment to remapped control boards for joint states reading | |
stream_inertials | boolean | Flag to activate the attachment to IMU sensor devices | |
stream_cartesian_wrenches | boolean | Flag to activate the attachment to Cartesian wrench related devices | |
stream_forcetorque_sensors | boolean | Flag to activate the attachment to six axis FT sensor devices | |
stream_cameras | boolean | Flag to activate the attachment to Cameras devices | |
stream_pids | boolean | Flag to activate the attachment to remapped control boards for pids reading | |
stream_motor_states | boolean | Flag to activate the attachment to remapped control boards for motor states reading | |
stream_motor_PWM | boolean | Flag to activate the attachment to remapped control boards for PWM reading | |
stream_temperatures | boolean | Flag to activate the attachment to MAS temperature sensors | |
RemoteControlBoardRemapper | Expects only one remapped remotecontrolboard device attached to it, if there multiple remote control boards, then use a remapper to create a single remotecontrolboard | ||
joints_list | vector of strings | This parameter is optional. The joints list used to open the remote control board remapper. If the list is not passed, the order of the joint stored in the PolyDriver is used | |
InertialSensors | Expects IMU to be opened as genericSensorClient devices communicating through the inertial server and other inertials as a part multiple analog sensors remapper ("multipleanalogsensorsremapper") | ||
imu_list | vector of strings | list of the names of devices opened as genericSensorClient device and having a channel dimension of 12 | |
gyroscopes_list | vector of strings | list of the names of devices opened with ThreeAxisGyroscope interface remapped through the "multipleanalogsensorsremapper" interfaces and having a channel dimension of 3 | |
accelerometers_list | vector of strings | list of the names of devices opened with ThreeAxisLinearAccelerometers interface remapped through the "multipleanalogsensorsremapper" interfaces and having a channel dimension of 3 | |
orientation_sensors_list | vector of strings | list of the names of devices opened with OrientationSensors interface remapped through the "multipleanalogsensorsremapper" interfaces and having a channel dimension of 3 | |
magnetometers_list | vector of strings | list of the names of devices opened with ThreeAxisMagnetometer interface remapped through the "multipleanalogsensorsremapper" interfaces and having a channel dimension of 3 | |
CartesianWrenches | Expects the devices wrapping the cartesian wrenches ports to be opened as "genericSensorClient" device and have a channel dimension of 6 | ||
cartesian_wrenches_list | vector of strings | list of the names of devices opened as genericSensorClient device and having a channel dimension of 6 | |
SixAxisForceTorqueSensors | Expects the Six axis FT sensors to be opened with SixAxisForceTorqueSensors interface remapped through multiple analog sensors remapper ("multipleanalogsensorsremapper") or to be opened as analog sensor ("analogsensorclient") device having channel dimensions as 6 | ||
sixaxis_forcetorque_sensors_list | vector of strings | list of six axis FT sensors (the difference between a MAS FT and an analog FT is done internally assuming that the names are distinct form each other) | |
TemperatureSensors | Expects the temperature sensors to be opened with TemperatureSensors interface remapped through multiple analog sensors remapper | ||
temperature_sensors_list | vector of strings | list containing the devices opened with TemperatureSensors interface |
Base classes
- class ISensorBridge
- Sensor bridge interface.
-
template<class Output>class BipedalLocomotion::System::Source<SensorBridgeMetaData>
- Source is a template specialization of Advanceable and represents a block that does not contains input.
Public types
- struct Impl
Constructors, destructors, conversion operators
- YarpSensorBridge()
- Constructor.
- ~YarpSensorBridge()
- Destructor.
Public functions
-
auto initialize(std::weak_ptr<const ParametersHandler::
IParametersHandler> handler) -> bool final - Initialize estimator.
- auto setDriversList(const yarp::dev::PolyDriverList& deviceDriversList) -> bool
- Set the list of device drivers from which the sensor measurements need to be streamed.
- auto advance() -> bool final
- Advance the internal state.
- auto isOutputValid() const -> bool final
- Determines the validity of the object retrieved with get()
- auto getFailedSensorReads() const -> std::vector<std::string>
- list of sensors that was failed to be read in the current advance() step
- auto getOutput() const -> const SensorBridgeMetaData& final
- Get the object.
- auto getJointsList(std::vector<std::string>& jointsList) -> bool final
- Get joints list.
- auto getIMUsList(std::vector<std::string>& IMUsList) -> bool final
- Get imu sensors.
- auto getLinearAccelerometersList(std::vector<std::string>& linearAccelerometersList) -> bool final
- Get linear accelerometers.
- auto getGyroscopesList(std::vector<std::string>& gyroscopesList) -> bool final
- Get gyroscopes.
- auto getOrientationSensorsList(std::vector<std::string>& orientationSensorsList) -> bool final
- Get orientation sensors.
- auto getMagnetometersList(std::vector<std::string>& magnetometersList) -> bool final
- Get magnetometers sensors.
- auto getSixAxisForceTorqueSensorsList(std::vector<std::string>& sixAxisForceTorqueSensorsList) -> bool final
- Get 6 axis FT sensors.
- auto getThreeAxisForceTorqueSensorsList(std::vector<std::string>& threeAxisForceTorqueSensorsList) -> bool final
- Get 6 axis FT sensors.
- auto getCartesianWrenchesList(std::vector<std::string>& cartesianWrenchesList) -> bool final
- Get cartesian wrenches.
- auto getTemperatureSensorsList(std::vector<std::string>& temperatureSensorsList) -> bool final
- Get temperature sensors.
- auto getJointsList() const -> const std::vector<std::string>&
- auto getIMUsList() const -> const std::vector<std::string>&
- auto getLinearAccelerometersList() const -> const std::vector<std::string>&
- auto getGyroscopesList() const -> const std::vector<std::string>&
- auto getOrientationSensorsList() const -> const std::vector<std::string>&
- auto getMagnetometersList() const -> const std::vector<std::string>&
- auto getSixAxisForceTorqueSensorsList() const -> const std::vector<std::string>&
- auto getTemperatureSensorsList() const -> const std::vector<std::string>&
- auto getCartesianWrenchesList() const -> const std::vector<std::string>&
- auto getJointPosition(const std::string& jointName, double& jointPosition, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- Get joint position in radians.
- auto getJointPositions(Eigen::Ref<Eigen::VectorXd> jointPositions, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- Get all joints' positions in radians.
- auto getJointVelocity(const std::string& jointName, double& jointVelocity, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- Get joint velocity in rad/s.
- auto getJointVelocities(Eigen::Ref<Eigen::VectorXd> jointVelocties, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- Get all joints' velocities in rad/s.
- auto getJointAcceleration(const std::string& jointName, double& jointAcceleration, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- Get joint acceleration in rad/s^2.
- auto getJointAccelerations(Eigen::Ref<Eigen::VectorXd> jointAccelerations, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- Get all joints' accelerations in rad/s^2.
- auto getIMUMeasurement(const std::string& imuName, Eigen::Ref<Vector12d> imuMeasurement, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- 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 final
- Get linear accelerometer measurement in m/s^2.
- auto getGyroscopeMeasure(const std::string& gyroName, Eigen::Ref<Eigen::Vector3d> gyroMeasurement, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- Get gyroscope measurement in rad/s.
- auto getOrientationSensorMeasurement(const std::string& rpyName, Eigen::Ref<Eigen::Vector3d> rpyMeasurement, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- 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 final
- Get magentometer measurement in tesla.
- auto getSixAxisForceTorqueMeasurement(const std::string& ftName, Eigen::Ref<Vector6d> ftMeasurement, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- Get six axis force torque measurement.
- auto getThreeAxisForceTorqueMeasurement(const std::string& ftName, Eigen::Ref<Eigen::Vector3d> ftMeasurement, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- 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 final
- 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 final
- Get temperature measurement.
- auto getMotorCurrent(const std::string& jointName, double& motorCurrent, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- Get motor current in ampere.
- auto getMotorCurrents(Eigen::Ref<Eigen::VectorXd> motorCurrents, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- Get all motors' currents in ampere.
- auto getMotorPWM(const std::string& jointName, double& motorPWM, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- Get motor PWM.
- auto getMotorPWMs(Eigen::Ref<Eigen::VectorXd> motorPWMs, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- Get all motors' PWMs.
- auto getJointTorque(const std::string& jointName, double& jointTorque, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- Get motor torque in Nm.
- auto getJointTorques(Eigen::Ref<Eigen::VectorXd> jointTorques, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- Get all motors' torques in Nm.
- auto getPidPosition(const std::string& jointName, double& pidPosition, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- Get pid position in rad.
- auto getPidPositions(Eigen::Ref<Eigen::VectorXd> pidPositions, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- Get all pid positions in rad.
- auto getPidPositionError(const std::string& jointName, double& pidPositionError, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- Get pid position error in rad.
- auto getPidPositionErrors(Eigen::Ref<Eigen::VectorXd> pidPositionErrors, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- Get all pid position errors in rad.
- auto getMotorPosition(const std::string& jointName, double& motorPosition, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- Get motor position in rad.
- auto getMotorPositions(Eigen::Ref<Eigen::VectorXd> motorPositions, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- Get all motors' positions in rad.
- auto getMotorVelocity(const std::string& jointName, double& motorVelocity, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- Get motor velocity in rad/s.
- auto getMotorVelocities(Eigen::Ref<Eigen::VectorXd> motorVelocties, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- Get all motors' velocities in rad/s.
- auto getMotorAcceleration(const std::string& jointName, double& motorAcceleration, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- Get motor acceleration in rad/s^2.
- auto getMotorAccelerations(Eigen::Ref<Eigen::VectorXd> motorAccelerations, OptionalDoubleRef receiveTimeInSeconds = {}) -> bool final
- Get all motors' accelerations in rad/s.
Function documentation
bool BipedalLocomotion:: RobotInterface:: YarpSensorBridge:: initialize(std::weak_ptr<const ParametersHandler:: IParametersHandler> handler) final
Initialize estimator.
Parameters | |
---|---|
handler in | Parameters handler |
bool BipedalLocomotion:: RobotInterface:: YarpSensorBridge:: setDriversList(const yarp::dev::PolyDriverList& deviceDriversList)
Set the list of device drivers from which the sensor measurements need to be streamed.
Parameters | |
---|---|
deviceDriversList | device drivers holding the pointer to sensor interfaces |
Returns | True/False in case of success/failure. |
bool BipedalLocomotion:: RobotInterface:: YarpSensorBridge:: isOutputValid() const final
Determines the validity of the object retrieved with get()
Returns | True if the object is valid, false otherwise. |
---|
std::vector<std::string> BipedalLocomotion:: RobotInterface:: YarpSensorBridge:: getFailedSensorReads() const
list of sensors that was failed to be read in the current advance() step
Returns | list of sensors as a vector of strings |
---|
const SensorBridgeMetaData& BipedalLocomotion:: RobotInterface:: YarpSensorBridge:: getOutput() const final
Get the object.
Returns | a const reference of the requested object. |
---|
bool BipedalLocomotion:: RobotInterface:: YarpSensorBridge:: getJointsList(std::vector<std::string>& jointsList) final
Get joints list.
Parameters | |
---|---|
jointsList out | list of joints attached to the bridge |
Returns | true/false in case of success/failure |
bool BipedalLocomotion:: RobotInterface:: YarpSensorBridge:: getIMUsList(std::vector<std::string>& IMUsList) final
Get imu sensors.
Parameters | |
---|---|
IMUsList out | list of IMUs attached to the bridge |
Returns | true/false in case of success/failure |
bool BipedalLocomotion:: RobotInterface:: YarpSensorBridge:: getLinearAccelerometersList(std::vector<std::string>& linearAccelerometersList) final
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:: YarpSensorBridge:: getGyroscopesList(std::vector<std::string>& gyroscopesList) final
Get gyroscopes.
Parameters | |
---|---|
gyroscopesList out | list of gyroscopes attached to the bridge |
Returns | true/false in case of success/failure |
bool BipedalLocomotion:: RobotInterface:: YarpSensorBridge:: getOrientationSensorsList(std::vector<std::string>& orientationSensorsList) final
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:: YarpSensorBridge:: getMagnetometersList(std::vector<std::string>& magnetometersList) final
Get magnetometers sensors.
Parameters | |
---|---|
magnetometersList out | list of magnetometers attached to the bridge |
Returns | true/false in case of success/failure |
bool BipedalLocomotion:: RobotInterface:: YarpSensorBridge:: getSixAxisForceTorqueSensorsList(std::vector<std::string>& sixAxisForceTorqueSensorsList) final
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:: YarpSensorBridge:: getThreeAxisForceTorqueSensorsList(std::vector<std::string>& threeAxisForceTorqueSensorsList) final
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:: YarpSensorBridge:: getCartesianWrenchesList(std::vector<std::string>& cartesianWrenchesList) final
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:: YarpSensorBridge:: getTemperatureSensorsList(std::vector<std::string>& temperatureSensorsList) final
Get temperature sensors.
Returns | true/false in case of success/failure |
---|
bool BipedalLocomotion:: RobotInterface:: YarpSensorBridge:: getJointPosition(const std::string& jointName,
double& jointPosition,
OptionalDoubleRef receiveTimeInSeconds = {}) final
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:: YarpSensorBridge:: getJointPositions(Eigen::Ref<Eigen::VectorXd> jointPositions,
OptionalDoubleRef receiveTimeInSeconds = {}) final
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:: YarpSensorBridge:: getJointVelocity(const std::string& jointName,
double& jointVelocity,
OptionalDoubleRef receiveTimeInSeconds = {}) final
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:: YarpSensorBridge:: getJointVelocities(Eigen::Ref<Eigen::VectorXd> jointVelocties,
OptionalDoubleRef receiveTimeInSeconds = {}) final
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:: YarpSensorBridge:: getJointAcceleration(const std::string& jointName,
double& jointAcceleration,
OptionalDoubleRef receiveTimeInSeconds = {}) final
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:: YarpSensorBridge:: getJointAccelerations(Eigen::Ref<Eigen::VectorXd> jointAccelerations,
OptionalDoubleRef receiveTimeInSeconds = {}) final
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:: YarpSensorBridge:: getIMUMeasurement(const std::string& imuName,
Eigen::Ref<Vector12d> imuMeasurement,
OptionalDoubleRef receiveTimeInSeconds = {}) final
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:: YarpSensorBridge:: getLinearAccelerometerMeasurement(const std::string& accName,
Eigen::Ref<Eigen::Vector3d> accMeasurement,
OptionalDoubleRef receiveTimeInSeconds = {}) final
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:: YarpSensorBridge:: getGyroscopeMeasure(const std::string& gyroName,
Eigen::Ref<Eigen::Vector3d> gyroMeasurement,
OptionalDoubleRef receiveTimeInSeconds = {}) final
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:: YarpSensorBridge:: getOrientationSensorMeasurement(const std::string& rpyName,
Eigen::Ref<Eigen::Vector3d> rpyMeasurement,
OptionalDoubleRef receiveTimeInSeconds = {}) final
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:: YarpSensorBridge:: getMagnetometerMeasurement(const std::string& magName,
Eigen::Ref<Eigen::Vector3d> magMeasurement,
OptionalDoubleRef receiveTimeInSeconds = {}) final
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:: YarpSensorBridge:: getSixAxisForceTorqueMeasurement(const std::string& ftName,
Eigen::Ref<Vector6d> ftMeasurement,
OptionalDoubleRef receiveTimeInSeconds = {}) final
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:: YarpSensorBridge:: getThreeAxisForceTorqueMeasurement(const std::string& ftName,
Eigen::Ref<Eigen::Vector3d> ftMeasurement,
OptionalDoubleRef receiveTimeInSeconds = {}) final
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:: YarpSensorBridge:: getCartesianWrench(const std::string& cartesianWrenchName,
Eigen::Ref<Vector6d> cartesianWrenchMeasurement,
OptionalDoubleRef receiveTimeInSeconds = {}) final
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:: YarpSensorBridge:: getTemperature(const std::string& temperatureSensorName,
double& temperature,
OptionalDoubleRef receiveTimeInSeconds = {}) final
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:: YarpSensorBridge:: getMotorCurrent(const std::string& jointName,
double& motorCurrent,
OptionalDoubleRef receiveTimeInSeconds = {}) final
Get motor current 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:: YarpSensorBridge:: getMotorCurrents(Eigen::Ref<Eigen::VectorXd> motorCurrents,
OptionalDoubleRef receiveTimeInSeconds = {}) final
Get all motors' currents 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:: YarpSensorBridge:: getMotorPWM(const std::string& jointName,
double& motorPWM,
OptionalDoubleRef receiveTimeInSeconds = {}) final
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:: YarpSensorBridge:: getMotorPWMs(Eigen::Ref<Eigen::VectorXd> motorPWMs,
OptionalDoubleRef receiveTimeInSeconds = {}) final
Get all motors' PWMs.
Parameters | |
---|---|
motorPWMs out | all motors' PWM in ampere |
receiveTimeInSeconds out | time at which the measurement was received |
Returns | true/false in case of success/failure |
bool BipedalLocomotion:: RobotInterface:: YarpSensorBridge:: getJointTorque(const std::string& jointName,
double& jointTorque,
OptionalDoubleRef receiveTimeInSeconds = {}) final
Get motor torque 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:: YarpSensorBridge:: getJointTorques(Eigen::Ref<Eigen::VectorXd> jointTorques,
OptionalDoubleRef receiveTimeInSeconds = {}) final
Get all motors' torques in Nm.
Parameters | |
---|---|
jointTorques out | all motors' torque in Nm |
receiveTimeInSeconds out | time at which the measurement was receivedW |
Returns | true/false in case of success/failure |
bool BipedalLocomotion:: RobotInterface:: YarpSensorBridge:: getPidPosition(const std::string& jointName,
double& pidPosition,
OptionalDoubleRef receiveTimeInSeconds = {}) final
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:: YarpSensorBridge:: getPidPositions(Eigen::Ref<Eigen::VectorXd> pidPositions,
OptionalDoubleRef receiveTimeInSeconds = {}) final
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:: YarpSensorBridge:: getPidPositionError(const std::string& jointName,
double& pidPositionError,
OptionalDoubleRef receiveTimeInSeconds = {}) final
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:: YarpSensorBridge:: getPidPositionErrors(Eigen::Ref<Eigen::VectorXd> pidPositionErrors,
OptionalDoubleRef receiveTimeInSeconds = {}) final
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:: YarpSensorBridge:: getMotorPosition(const std::string& jointName,
double& motorPosition,
OptionalDoubleRef receiveTimeInSeconds = {}) final
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:: YarpSensorBridge:: getMotorPositions(Eigen::Ref<Eigen::VectorXd> motorPositions,
OptionalDoubleRef receiveTimeInSeconds = {}) final
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:: YarpSensorBridge:: getMotorVelocity(const std::string& jointName,
double& motorVelocity,
OptionalDoubleRef receiveTimeInSeconds = {}) final
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:: YarpSensorBridge:: getMotorVelocities(Eigen::Ref<Eigen::VectorXd> motorVelocties,
OptionalDoubleRef receiveTimeInSeconds = {}) final
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:: YarpSensorBridge:: getMotorAcceleration(const std::string& jointName,
double& motorAcceleration,
OptionalDoubleRef receiveTimeInSeconds = {}) final
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:: YarpSensorBridge:: getMotorAccelerations(Eigen::Ref<Eigen::VectorXd> motorAccelerations,
OptionalDoubleRef receiveTimeInSeconds = {}) final
Get all motors' accelerations in rad/s.
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 |