Ignition Gazebo

API Reference

4.1.0
OpticalTactilePluginVisualization Class Reference

#include <Visualization.hh>

Public Member Functions

 OpticalTactilePluginVisualization (std::string &_modelName, ignition::math::Vector3d &_sensorSize, double &_forceLength, float &_cameraUpdateRate, ignition::math::Pose3f &_depthCameraOffset, int &_visualizationResolution)
 Constructor. More...
 
void AddNormalForceToMarkerMsgs (ignition::msgs::Marker &_positionMarkerMsg, ignition::msgs::Marker &_forceMarkerMsg, ignition::math::Vector3f &_position, ignition::math::Vector3f &_normalForce, ignition::math::Pose3f &_sensorWorldPose)
 Add a normal force to the marker messages representing the normal forces computed. More...
 
void RequestNormalForcesMarkerMsgs (ignition::msgs::Marker &_positionMarkerMsg, ignition::msgs::Marker &_forceMarkerMsg)
 Request the "/marker" service for the marker messages representing the normal forces. More...
 
void RequestSensorMarkerMsg (ignition::math::Pose3f const &_sensorPose)
 Request the "/marker" service for the sensor marker. This can be helpful when debbuging, given that there shouldn't be a visual tag in the plugin's model. More...
 

Constructor & Destructor Documentation

◆ OpticalTactilePluginVisualization()

OpticalTactilePluginVisualization ( std::string _modelName,
ignition::math::Vector3d _sensorSize,
double &  _forceLength,
float &  _cameraUpdateRate,
ignition::math::Pose3f _depthCameraOffset,
int &  _visualizationResolution 
)

Constructor.

Parameters
[in]_modelNameName of the model to which the sensor is attached
[in]_sensorSizeSize of the contact sensor
[in]_forceLengthValue of the forceLength attribute
[in]_cameraUpdateRateValue of the cameraUpdateRate attribute
[in]_depthCameraOffsetValue of the depthCameraOffset attribute
[in]_visualizationResolutionValue of the visualizationResolution attribute

Member Function Documentation

◆ AddNormalForceToMarkerMsgs()

void AddNormalForceToMarkerMsgs ( ignition::msgs::Marker _positionMarkerMsg,
ignition::msgs::Marker _forceMarkerMsg,
ignition::math::Vector3f _position,
ignition::math::Vector3f _normalForce,
ignition::math::Pose3f _sensorWorldPose 
)

Add a normal force to the marker messages representing the normal forces computed.

Parameters
[out]_positionMarkerMsgMessage for visualizing the contact positions
[out]_forceMarkerMsgMessage for visualizing the contact normal forces
[in]_positionPosition of the normal force referenced to the depth camera's origin
[in]_normalForceValue of the normal force referenced to the depth camera's origin
[in]_sensorWorldPosePose of the plugin's model referenced to the world's origin

◆ RequestNormalForcesMarkerMsgs()

void RequestNormalForcesMarkerMsgs ( ignition::msgs::Marker _positionMarkerMsg,
ignition::msgs::Marker _forceMarkerMsg 
)

Request the "/marker" service for the marker messages representing the normal forces.

Parameters
[in]_positionMarkerMsgMessage for visualizing the contact positions
[in]_forceMarkerMsgMessage for visualizing the contact normal forces

◆ RequestSensorMarkerMsg()

void RequestSensorMarkerMsg ( ignition::math::Pose3f const &  _sensorPose)

Request the "/marker" service for the sensor marker. This can be helpful when debbuging, given that there shouldn't be a visual tag in the plugin's model.

Parameters
[in]_sensorPosePose of the optical tactile sensor

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